SITL: added SIM_SPEEDUP parameter

allows changing speed of simulation while running
This commit is contained in:
Andrew Tridgell 2016-09-19 07:45:24 +10:00
parent 13fe8cb4d0
commit c275e7c61d
4 changed files with 8 additions and 0 deletions

View File

@ -360,6 +360,11 @@ void Aircraft::fill_fdm(struct sitl_fdm &fdm)
fdm.longitude = smoothing.location.lng * 1.0e-7;
fdm.altitude = smoothing.location.alt * 1.0e-2;
}
if (last_speedup != sitl->speedup && sitl->speedup > 0) {
set_speedup(sitl->speedup);
last_speedup = sitl->speedup;
}
}
uint64_t Aircraft::get_wall_time_us() const

View File

@ -147,6 +147,7 @@ protected:
const char *autotest_dir;
const char *frame;
bool use_time_sync = true;
float last_speedup = -1;
enum {
GROUND_BEHAVIOR_NONE=0,

View File

@ -83,6 +83,7 @@ const AP_Param::GroupInfo SITL::var_info[] = {
AP_GROUPINFO("MAG_ALY_HGT", 49, SITL, mag_anomaly_hgt, 1.0f),
AP_GROUPINFO("PIN_MASK", 50, SITL, pin_mask, 0),
AP_GROUPINFO("ADSB_TX", 51, SITL, adsb_tx, 0),
AP_GROUPINFO("SPEEDUP", 52, SITL, speedup, -1),
AP_GROUPEND
};

View File

@ -104,6 +104,7 @@ public:
AP_Int8 flow_delay; // optflow data delay
AP_Int8 terrain_enable; // enable using terrain for height
AP_Int8 pin_mask; // for GPIO emulation
AP_Float speedup; // simulation speedup
// wind control
float wind_speed_active;