mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Copter: fix get_non_takeoff_throttle
The throttle_mid parameter (for historic reason) is interpreted as a value that includes throttle_min. This means we must subtract the throttle_min value from it when converting it to a throttle in the 0 to 1 range.
This commit is contained in:
parent
4a06ca4be2
commit
a5c55c3fbd
@ -199,7 +199,9 @@ float Copter::get_pilot_desired_climb_rate(float throttle_control)
|
||||
// get_non_takeoff_throttle - a throttle somewhere between min and mid throttle which should not lead to a takeoff
|
||||
float Copter::get_non_takeoff_throttle()
|
||||
{
|
||||
return (((float)g.throttle_mid/1000.0f)/2.0f);
|
||||
// ensure mid throttle is set within a reasonable range
|
||||
g.throttle_mid = constrain_int16(g.throttle_mid,g.throttle_min+50,700);
|
||||
return MAX(0,g.throttle_mid-g.throttle_min) / ((float)(1000-g.throttle_min) * 2.0f);
|
||||
}
|
||||
|
||||
float Copter::get_takeoff_trigger_throttle()
|
||||
|
Loading…
Reference in New Issue
Block a user