AP_Motors: MotorsMulticopter fix floating boost output

This commit is contained in:
Peter Hall 2020-02-28 00:22:29 +00:00 committed by Randy Mackay
parent 96c97589ae
commit 33af883275

View File

@ -263,6 +263,8 @@ void AP_MotorsMulticopter::output_boost_throttle(void)
if (_boost_scale > 0) {
float throttle = constrain_float(get_throttle() * _boost_scale, 0, 1);
SRV_Channels::set_output_scaled(SRV_Channel::k_boost_throttle, throttle * 1000);
} else {
SRV_Channels::set_output_scaled(SRV_Channel::k_boost_throttle, 0);
}
}