mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
AP_Motors: MotorsMulticopter fix floating boost output
This commit is contained in:
parent
b2a298fa5f
commit
2f036c65f3
@ -266,6 +266,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);
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user