SITL: allow motor multiplier to work on quad simulation
This commit is contained in:
parent
f0469a21f2
commit
37be83994f
@ -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;
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user