mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 17:38:32 -04:00
Plane: fixed hover learn in quadplanes for THR_MIN>0
petrol quadplanes commonly have THR_MIN>0, and without this change cannot ever learn the hover throttle
This commit is contained in:
parent
7c5a0a6a43
commit
e9b8a20312
@ -1975,7 +1975,8 @@ void QuadPlane::update_throttle_hover()
|
|||||||
}
|
}
|
||||||
|
|
||||||
// do not update if quadplane forward motor is running (wing may be generating lift)
|
// do not update if quadplane forward motor is running (wing may be generating lift)
|
||||||
if (!is_tailsitter() && (SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) != 0)) {
|
// we use the THR_MIN value to account for petrol motors idling at THR_MIN
|
||||||
|
if (!is_tailsitter() && (SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) > MAX(0,plane.aparm.throttle_min+10))) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user