AP_Landing: abstract land abort request method

This commit is contained in:
Tom Pittenger 2016-12-06 12:21:04 -08:00
parent 8c1509ad47
commit e061e1734c
3 changed files with 28 additions and 3 deletions

View File

@ -322,3 +322,18 @@ int32_t AP_Landing::get_target_airspeed_cm(const AP_SpdHgtControl::FlightStage f
// Do not lower it or exceed cruise speed
return constrain_int32(target_airspeed_cm + head_wind_compensation_cm, target_airspeed_cm, aparm.airspeed_cruise_cm);
}
/*
* request a landing abort given the landing type
* return true on success
*/
bool AP_Landing::request_go_around(void)
{
switch (type) {
default:
case TYPE_STANDARD_GLIDE_SLOPE:
return type_slope_request_go_around();
}
}

View File

@ -73,6 +73,7 @@ public:
void setup_landing_glide_slope(const Location &prev_WP_loc, const Location &next_WP_loc, const Location &current_loc, int32_t &target_altitude_offset_cm);
void check_if_need_to_abort(const AP_Vehicle::FixedWing::Rangefinder_State &rangefinder_state);
bool request_go_around(void);
static const struct AP_Param::GroupInfo var_info[];
@ -90,6 +91,7 @@ public:
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; }
// Flag to indicate if we have landed.
@ -111,9 +113,6 @@ public:
// landing altitude offset (meters)
float alt_offset;
// denotes if a go-around has been commanded for landing
bool commanded_go_around;
private:
// once landed, post some landing statistics to the GCS
@ -121,6 +120,9 @@ private:
bool has_aborted_due_to_slope_recalc;
// denotes if a go-around has been commanded for landing
bool commanded_go_around;
AP_Mission &mission;
AP_AHRS &ahrs;
AP_SpdHgtControl *SpdHgt_Controller;
@ -159,5 +161,6 @@ private:
void type_slope_setup_landing_glide_slope(const Location &prev_WP_loc, const Location &next_WP_loc, const Location &current_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);
};

View File

@ -197,6 +197,13 @@ void AP_Landing::type_slope_adjust_landing_slope_for_rangefinder_bump(AP_Vehicle
}
}
bool AP_Landing::type_slope_request_go_around(void)
{
commanded_go_around = true;
return true;
}
/*
a special glide slope calculation for the landing approach