SITL: use SIM_ENGINE_MUL to simulate motor failure

This commit is contained in:
Randy Mackay 2013-05-19 14:29:08 +09:00
parent 9fdab5e8fe
commit b914f9ba06

View File

@ -392,10 +392,16 @@ void SITL_State::_simulator_output(void)
_motors_on = ((control.pwm[2]-1500)/500.0) != 0;
} else {
_motors_on = false;
// apply engine multiplier to first motor
control.pwm[0] = ((control.pwm[0]-1000) * _sitl->engine_mul) + 1000;
// run checks on each motor
for (i=0; i<4; i++) {
// check motors do not exceed their limits
if (control.pwm[i] > 2000) control.pwm[i] = 2000;
if (control.pwm[i] < 1000) control.pwm[i] = 1000;
// update motor_on flag
if ((control.pwm[i]-1000)/1000.0 > 0) {
control.pwm[i] = ((control.pwm[i]-1000) * _sitl->engine_mul) + 1000;
_motors_on = true;
_motors_on = true;
}
}
}