mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: MotorsMulticopter fix floating boost output
This commit is contained in:
parent
83ca008f4e
commit
18cab7a414
|
@ -263,6 +263,8 @@ void AP_MotorsMulticopter::output_boost_throttle(void)
|
||||||
if (_boost_scale > 0) {
|
if (_boost_scale > 0) {
|
||||||
float throttle = constrain_float(get_throttle() * _boost_scale, 0, 1);
|
float throttle = constrain_float(get_throttle() * _boost_scale, 0, 1);
|
||||||
SRV_Channels::set_output_scaled(SRV_Channel::k_boost_throttle, throttle * 1000);
|
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