mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Landing: move enum FlightStages to AP_Vehicle::FixedWing
This commit is contained in:
parent
8019cedf5b
commit
502768c979
@ -146,7 +146,7 @@ const AP_Param::GroupInfo AP_Landing::var_info[] = {
|
||||
update navigation for landing. Called when on landing approach or
|
||||
final flare
|
||||
*/
|
||||
bool AP_Landing::verify_land(const AP_SpdHgtControl::FlightStage flight_stage, const Location &prev_WP_loc, Location &next_WP_loc, const Location ¤t_loc,
|
||||
bool AP_Landing::verify_land(const AP_Vehicle::FixedWing::FlightStage flight_stage, const Location &prev_WP_loc, Location &next_WP_loc, const Location ¤t_loc,
|
||||
const int32_t auto_state_takeoff_altitude_rel_cm, const float height, const float sink_rate, const float wp_proportion, const uint32_t last_flying_ms, const bool is_armed, const bool is_flying, const bool rangefinder_state_in_range, bool &throttle_suppressed)
|
||||
{
|
||||
switch (type) {
|
||||
@ -283,7 +283,7 @@ float AP_Landing::head_wind(void)
|
||||
/*
|
||||
* returns target airspeed in cm/s depending on flight stage
|
||||
*/
|
||||
int32_t AP_Landing::get_target_airspeed_cm(const AP_SpdHgtControl::FlightStage flight_stage)
|
||||
int32_t AP_Landing::get_target_airspeed_cm(const AP_Vehicle::FixedWing::FlightStage flight_stage)
|
||||
{
|
||||
int32_t target_airspeed_cm = aparm.airspeed_cruise_cm;
|
||||
|
||||
@ -298,14 +298,14 @@ int32_t AP_Landing::get_target_airspeed_cm(const AP_SpdHgtControl::FlightStage f
|
||||
const float land_airspeed = SpdHgt_Controller->get_land_airspeed();
|
||||
|
||||
switch (flight_stage) {
|
||||
case AP_SpdHgtControl::FLIGHT_LAND_APPROACH:
|
||||
case AP_Vehicle::FixedWing::FLIGHT_LAND_APPROACH:
|
||||
if (land_airspeed >= 0) {
|
||||
target_airspeed_cm = land_airspeed * 100;
|
||||
}
|
||||
break;
|
||||
|
||||
case AP_SpdHgtControl::FLIGHT_LAND_PREFLARE:
|
||||
case AP_SpdHgtControl::FLIGHT_LAND_FINAL:
|
||||
case AP_Vehicle::FixedWing::FLIGHT_LAND_PREFLARE:
|
||||
case AP_Vehicle::FixedWing::FLIGHT_LAND_FINAL:
|
||||
if (pre_flare && get_pre_flare_airspeed() > 0) {
|
||||
// if we just preflared then continue using the pre-flare airspeed during final flare
|
||||
target_airspeed_cm = get_pre_flare_airspeed() * 100;
|
||||
|
@ -65,7 +65,7 @@ public:
|
||||
// TODO: TYPE_HELICAL,
|
||||
};
|
||||
|
||||
bool verify_land(const AP_SpdHgtControl::FlightStage flight_stage, const Location &prev_WP_loc, Location &next_WP_loc, const Location ¤t_loc,
|
||||
bool verify_land(const AP_Vehicle::FixedWing::FlightStage flight_stage, const Location &prev_WP_loc, Location &next_WP_loc, const Location ¤t_loc,
|
||||
const int32_t auto_state_takeoff_altitude_rel_cm, const float height, const float sink_rate, const float wp_proportion, const uint32_t last_flying_ms, const bool is_armed, const bool is_flying, const bool rangefinder_state_in_range, bool &throttle_suppressed);
|
||||
void adjust_landing_slope_for_rangefinder_bump(AP_Vehicle::FixedWing::Rangefinder_State &rangefinder_state, Location &prev_WP_loc, Location &next_WP_loc, const Location ¤t_loc, const float wp_distance, int32_t &target_altitude_offset_cm);
|
||||
void setup_landing_glide_slope(const Location &prev_WP_loc, const Location &next_WP_loc, const Location ¤t_loc, int32_t &target_altitude_offset_cm);
|
||||
@ -78,7 +78,7 @@ public:
|
||||
bool restart_landing_sequence(void);
|
||||
float wind_alignment(const float heading_deg);
|
||||
float head_wind(void);
|
||||
int32_t get_target_airspeed_cm(const AP_SpdHgtControl::FlightStage flight_stage);
|
||||
int32_t get_target_airspeed_cm(const AP_Vehicle::FixedWing::FlightStage flight_stage);
|
||||
|
||||
// accessor functions for the params and states
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
@ -155,7 +155,7 @@ private:
|
||||
AP_Int8 type;
|
||||
|
||||
// Land Type STANDARD GLIDE SLOPE
|
||||
bool type_slope_verify_land(const AP_SpdHgtControl::FlightStage flight_stage, const Location &prev_WP_loc, Location &next_WP_loc, const Location ¤t_loc,
|
||||
bool type_slope_verify_land(const AP_Vehicle::FixedWing::FlightStage flight_stage, const Location &prev_WP_loc, Location &next_WP_loc, const Location ¤t_loc,
|
||||
const int32_t auto_state_takeoff_altitude_rel_cm, const float height, const float sink_rate, const float wp_proportion, const uint32_t last_flying_ms, const bool is_armed, const bool is_flying, const bool rangefinder_state_in_range, bool &throttle_suppressed);
|
||||
|
||||
void type_slope_adjust_landing_slope_for_rangefinder_bump(AP_Vehicle::FixedWing::Rangefinder_State &rangefinder_state, Location &prev_WP_loc, Location &next_WP_loc, const Location ¤t_loc, const float wp_distance, int32_t &target_altitude_offset_cm);
|
||||
|
@ -26,7 +26,7 @@
|
||||
update navigation for landing. Called when on landing approach or
|
||||
final flare
|
||||
*/
|
||||
bool AP_Landing::type_slope_verify_land(const AP_SpdHgtControl::FlightStage flight_stage, const Location &prev_WP_loc, Location &next_WP_loc, const Location ¤t_loc,
|
||||
bool AP_Landing::type_slope_verify_land(const AP_Vehicle::FixedWing::FlightStage flight_stage, const Location &prev_WP_loc, Location &next_WP_loc, const Location ¤t_loc,
|
||||
const int32_t auto_state_takeoff_altitude_rel_cm, const float height, const float sink_rate, const float wp_proportion, const uint32_t last_flying_ms, const bool is_armed, const bool is_flying, const bool rangefinder_state_in_range, bool &throttle_suppressed)
|
||||
{
|
||||
// we don't 'verify' landing in the sense that it never completes,
|
||||
@ -35,7 +35,7 @@ bool AP_Landing::type_slope_verify_land(const AP_SpdHgtControl::FlightStage flig
|
||||
|
||||
// when aborting a landing, mimic the verify_takeoff with steering hold. Once
|
||||
// the altitude has been reached, restart the landing sequence
|
||||
if (flight_stage == AP_SpdHgtControl::FLIGHT_LAND_ABORT) {
|
||||
if (flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND_ABORT) {
|
||||
|
||||
throttle_suppressed = false;
|
||||
|
||||
@ -74,8 +74,8 @@ bool AP_Landing::type_slope_verify_land(const AP_SpdHgtControl::FlightStage flig
|
||||
// 2) passed land point and don't have an accurate AGL
|
||||
// 3) probably crashed (ensures motor gets turned off)
|
||||
|
||||
bool on_approach_stage = (flight_stage == AP_SpdHgtControl::FLIGHT_LAND_APPROACH ||
|
||||
flight_stage == AP_SpdHgtControl::FLIGHT_LAND_PREFLARE);
|
||||
bool on_approach_stage = (flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND_APPROACH ||
|
||||
flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND_PREFLARE);
|
||||
bool below_flare_alt = (height <= flare_alt);
|
||||
bool below_flare_sec = (flare_sec > 0 && height <= sink_rate * flare_sec);
|
||||
bool probably_crashed = (aparm.crash_detection_enable && fabsf(sink_rate) < 0.2f && !is_flying);
|
||||
|
Loading…
Reference in New Issue
Block a user