mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 18:48:30 -04:00
AP_Landing: use a common reset for uniform landing wipe
This commit is contained in:
parent
7daf1a87be
commit
f09007cbe9
@ -189,14 +189,16 @@ void AP_Landing::setup_landing_glide_slope(const Location &prev_WP_loc, const Lo
|
||||
/*
|
||||
* initialize state for new nav command
|
||||
*/
|
||||
void AP_Landing::init_start_nav_cmd(void)
|
||||
void AP_Landing::reset(void)
|
||||
{
|
||||
switch (type) {
|
||||
default:
|
||||
case TYPE_STANDARD_GLIDE_SLOPE:
|
||||
type_slope_init_start_nav_cmd();
|
||||
break;
|
||||
}
|
||||
complete = false;
|
||||
pre_flare = false;
|
||||
commanded_go_around = false;
|
||||
initial_slope = 0;
|
||||
slope = 0;
|
||||
|
||||
// once landed, post some landing statistics to the GCS
|
||||
post_stats = false;
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -74,6 +74,7 @@ public:
|
||||
|
||||
|
||||
// helper functions
|
||||
void reset(void);
|
||||
bool restart_landing_sequence(void);
|
||||
float wind_alignment(const float heading_deg);
|
||||
float head_wind(void);
|
||||
@ -89,8 +90,8 @@ public:
|
||||
int8_t get_abort_throttle_enable(void) const { return abort_throttle_enable; }
|
||||
int8_t get_flap_percent(void) const { return flap_percent; }
|
||||
int8_t get_throttle_slewrate(void) const { return throttle_slewrate; }
|
||||
void init_start_nav_cmd(void);
|
||||
bool is_commanded_go_around(void) const { return commanded_go_around; }
|
||||
void set_initial_slope() { initial_slope = slope; }
|
||||
|
||||
|
||||
// Flag to indicate if we have landed.
|
||||
@ -103,12 +104,6 @@ public:
|
||||
// are we in auto and flight mode is approach || pre-flare || final (flare)
|
||||
bool in_progress;
|
||||
|
||||
// calculated approach slope during auto-landing: ((prev_WP_loc.alt - next_WP_loc.alt)*0.01f - flare_sec * sink_rate) / get_distance(prev_WP_loc, next_WP_loc)
|
||||
float slope;
|
||||
|
||||
// same as land_slope but sampled once before a rangefinder changes the slope. This should be the original mission planned slope
|
||||
float initial_slope;
|
||||
|
||||
// landing altitude offset (meters)
|
||||
float alt_offset;
|
||||
|
||||
@ -122,6 +117,12 @@ private:
|
||||
// denotes if a go-around has been commanded for landing
|
||||
bool commanded_go_around;
|
||||
|
||||
// same as land_slope but sampled once before a rangefinder changes the slope. This should be the original mission planned slope
|
||||
float initial_slope;
|
||||
|
||||
// calculated approach slope during auto-landing: ((prev_WP_loc.alt - next_WP_loc.alt)*0.01f - flare_sec * sink_rate) / get_distance(prev_WP_loc, next_WP_loc)
|
||||
float slope;
|
||||
|
||||
AP_Mission &mission;
|
||||
AP_AHRS &ahrs;
|
||||
AP_SpdHgtControl *SpdHgt_Controller;
|
||||
@ -159,7 +160,6 @@ private:
|
||||
|
||||
void type_slope_setup_landing_glide_slope(const Location &prev_WP_loc, const Location &next_WP_loc, const Location ¤t_loc, int32_t &target_altitude_offset_cm);
|
||||
void type_slope_check_if_need_to_abort(const AP_Vehicle::FixedWing::Rangefinder_State &rangefinder_state);
|
||||
void type_slope_init_start_nav_cmd(void);
|
||||
bool type_slope_request_go_around(void);
|
||||
|
||||
};
|
||||
|
@ -300,14 +300,4 @@ void AP_Landing::type_slope_setup_landing_glide_slope(const Location &prev_WP_lo
|
||||
constrain_target_altitude_location_fn(loc, prev_WP_loc);
|
||||
}
|
||||
|
||||
void AP_Landing::type_slope_init_start_nav_cmd(void)
|
||||
{
|
||||
complete = false;
|
||||
pre_flare = false;
|
||||
|
||||
// if a go around had been commanded, clear it now.
|
||||
commanded_go_around = false;
|
||||
|
||||
// once landed, post some landing statistics to the GCS
|
||||
post_stats = false;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user