mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
AP_MotorsMulticopter: Use same throttle value used by motors
This commit is contained in:
parent
d74ae535d1
commit
0a56d69d54
@ -378,7 +378,7 @@ void AP_MotorsMulticopter::set_throttle_range(int16_t radio_min, int16_t radio_m
|
||||
void AP_MotorsMulticopter::update_throttle_hover(float dt)
|
||||
{
|
||||
if (_throttle_hover_learn != HOVER_LEARN_DISABLED) {
|
||||
_throttle_hover = _throttle_hover + (dt/(dt+AP_MOTORS_THST_HOVER_TC))*(_throttle_in-_throttle_hover);
|
||||
_throttle_hover = _throttle_hover + (dt/(dt+AP_MOTORS_THST_HOVER_TC))*(get_throttle()-_throttle_hover);
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user