SITL: allow motor multiplier to work on quad simulation

This commit is contained in:
Andrew Tridgell 2013-01-22 20:09:47 +11:00
parent f0469a21f2
commit 37be83994f

View File

@ -393,6 +393,7 @@ void SITL_State::_simulator_output(void)
_motors_on = false;
for (i=0; i<4; i++) {
if ((control.pwm[i]-1000)/1000.0 > 0) {
control.pwm[i] = ((control.pwm[i]-1000) * _sitl->engine_mul) + 1000;
_motors_on = true;
}
}