mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
AP_SpdHgtControl: added FightStage parameter to update_pitch_throttle()
will be used for special landing handling
This commit is contained in:
parent
6ffd84b0bd
commit
2b80df6319
@ -24,11 +24,22 @@ public:
|
|||||||
// Should be called at 50Hz or faster
|
// Should be called at 50Hz or faster
|
||||||
virtual void update_50hz(float height_above_field) = 0;
|
virtual void update_50hz(float height_above_field) = 0;
|
||||||
|
|
||||||
|
/**
|
||||||
|
stages of flight so the altitude controller can choose to
|
||||||
|
prioritise height or speed
|
||||||
|
*/
|
||||||
|
enum FlightStage {
|
||||||
|
FLIGHT_NORMAL = 1,
|
||||||
|
FLIGHT_TAKEOFF = 2,
|
||||||
|
FLIGHT_LAND_APPROACH = 3,
|
||||||
|
FLIGHT_LAND_FINAL = 4
|
||||||
|
};
|
||||||
|
|
||||||
// Update of the pitch and throttle demands
|
// Update of the pitch and throttle demands
|
||||||
// Should be called at 10Hz or faster
|
// Should be called at 10Hz or faster
|
||||||
virtual void update_pitch_throttle( int32_t hgt_dem_cm,
|
virtual void update_pitch_throttle( int32_t hgt_dem_cm,
|
||||||
int32_t EAS_dem_cm,
|
int32_t EAS_dem_cm,
|
||||||
bool climbOutDem,
|
enum FlightStage flight_stage,
|
||||||
int32_t ptchMinCO_cd,
|
int32_t ptchMinCO_cd,
|
||||||
int16_t throttle_nudge,
|
int16_t throttle_nudge,
|
||||||
float hgt_afe) = 0;
|
float hgt_afe) = 0;
|
||||||
@ -54,6 +65,7 @@ public:
|
|||||||
CONTROLLER_TECS = 1
|
CONTROLLER_TECS = 1
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user