mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Plane: Resore old default behaviour for throttle curves
The change in this made QStabilize behave very differently then it had, which is quite shocking in a test flight.
This commit is contained in:
parent
cb054e714b
commit
f9580424f6
@ -982,12 +982,16 @@ float QuadPlane::get_pilot_throttle()
|
|||||||
// normalize to [0,1]
|
// normalize to [0,1]
|
||||||
throttle_in /= plane.channel_throttle->get_range();
|
throttle_in /= plane.channel_throttle->get_range();
|
||||||
|
|
||||||
// get hover throttle level [0,1]
|
if (is_positive(throttle_expo)) {
|
||||||
float thr_mid = motors->get_throttle_hover();
|
// get hover throttle level [0,1]
|
||||||
float thrust_curve_expo = constrain_float(throttle_expo, 0.0f, 1.0f);
|
float thr_mid = motors->get_throttle_hover();
|
||||||
|
float thrust_curve_expo = constrain_float(throttle_expo, 0.0f, 1.0f);
|
||||||
|
|
||||||
// this puts mid stick at hover throttle
|
// this puts mid stick at hover throttle
|
||||||
return throttle_curve(thr_mid, thrust_curve_expo, throttle_in);;
|
return throttle_curve(thr_mid, thrust_curve_expo, throttle_in);;
|
||||||
|
} else {
|
||||||
|
return throttle_in;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
Loading…
Reference in New Issue
Block a user