Browse Source

SITL: fix when speedup is specified as a startup parameter

zr-v5.1
Tatsuya Yamaguchi 5 years ago committed by Andrew Tridgell
parent
commit
829cd29d7c
  1. 5
      libraries/SITL/SIM_Aircraft.cpp

5
libraries/SITL/SIM_Aircraft.cpp

@ -432,6 +432,11 @@ void Aircraft::fill_fdm(struct sitl_fdm &fdm) @@ -432,6 +432,11 @@ void Aircraft::fill_fdm(struct sitl_fdm &fdm)
fdm.quaternion.from_rotation_matrix(m);
}
}
// in the first call here, if a speedup option is specified, overwrite it
if (is_equal(last_speedup, -1.0f) && !is_equal(get_speedup(), 1.0f)) {
sitl->speedup = get_speedup();
}
if (!is_equal(last_speedup, float(sitl->speedup)) && sitl->speedup > 0) {
set_speedup(sitl->speedup);

Loading…
Cancel
Save