mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
AP_TECS: fixed throttle demand on underspeed
thanks to Philipp Oettershagen for finding this bug!
This commit is contained in:
parent
d6508acfa5
commit
2b48434e60
@ -455,7 +455,7 @@ void AP_TECS::_update_throttle(void)
|
|||||||
// If underspeed condition is set, then demand full throttle
|
// If underspeed condition is set, then demand full throttle
|
||||||
if (_underspeed)
|
if (_underspeed)
|
||||||
{
|
{
|
||||||
_throttle_dem_unc = 1.0f;
|
_throttle_dem = 1.0f;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
|
@ -206,9 +206,6 @@ private:
|
|||||||
// climbout mode
|
// climbout mode
|
||||||
enum FlightStage _flight_stage;
|
enum FlightStage _flight_stage;
|
||||||
|
|
||||||
// throttle demand before limiting
|
|
||||||
float _throttle_dem_unc;
|
|
||||||
|
|
||||||
// pitch demand before limiting
|
// pitch demand before limiting
|
||||||
float _pitch_dem_unc;
|
float _pitch_dem_unc;
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user