SITL: added SIM_ENGINE_MUL

this allows for simulated engine failures
This commit is contained in:
Andrew Tridgell 2012-08-17 14:21:43 +10:00
parent ebd399d11f
commit 1ccff12b54
3 changed files with 8 additions and 0 deletions

View File

@ -187,6 +187,12 @@ static void sitl_simulator_output(void)
}
if (!desktop_state.quadcopter) {
// add in engine multiplier
if (pwm[2] > 1000) {
pwm[2] = ((pwm[2]-1000) * sitl.engine_mul) + 1000;
if (pwm[2] > 2000) pwm[2] = 2000;
}
// 400kV motor, 16V
sitl_motor_speed[0] = ((pwm[2]-1000)/1000.0) * 400 * 16 / 60.0;
} else {

View File

@ -23,6 +23,7 @@ const AP_Param::GroupInfo SITL::var_info[] PROGMEM = {
AP_GROUPINFO("DRIFT_SPEED",5, SITL, drift_speed, 0.2),
AP_GROUPINFO("DRIFT_TIME", 6, SITL, drift_time, 5),
AP_GROUPINFO("GPS_DELAY", 7, SITL, gps_delay, 4),
AP_GROUPINFO("ENGINE_MUL", 8, SITL, engine_mul, 1),
AP_GROUPEND
};

View File

@ -50,6 +50,7 @@ public:
AP_Float drift_speed; // degrees/second/minute
AP_Float drift_time; // period in minutes
AP_Float engine_mul; // engine multiplier
AP_Int8 gps_disable; // disable simulated GPS
AP_Int8 gps_delay; // delay in samples