AP_Landing: refactor bool variables into flag stucts

This commit is contained in:
Tom Pittenger 2017-01-26 13:05:45 -08:00
parent bdafc2c025
commit 644f75942b
3 changed files with 33 additions and 27 deletions

View File

@ -143,7 +143,7 @@ const AP_Param::GroupInfo AP_Landing::var_info[] = {
void AP_Landing::do_land(const AP_Mission::Mission_Command& cmd, const float relative_altitude)
{
commanded_go_around = false;
flags.commanded_go_around = false;
switch (type) {
case TYPE_STANDARD_GLIDE_SLOPE:
@ -214,7 +214,7 @@ void AP_Landing::adjust_landing_slope_for_rangefinder_bump(AP_Vehicle::FixedWing
// return true while the aircraft should be in a flaring state
bool AP_Landing::is_flaring(void) const
{
if (!in_progress) {
if (!flags.in_progress) {
return false;
}
@ -229,7 +229,7 @@ bool AP_Landing::is_flaring(void) const
// return true while the aircraft is performing a landing approach
bool AP_Landing::is_on_approach(void) const
{
if (!in_progress) {
if (!flags.in_progress) {
return false;
}
@ -244,7 +244,7 @@ bool AP_Landing::is_on_approach(void) const
// return true when at the last stages of a land when an impact with the ground is expected soon
bool AP_Landing::is_expecting_impact(void) const
{
if (!in_progress) {
if (!flags.in_progress) {
return false;
}
@ -371,7 +371,7 @@ float AP_Landing::head_wind(void)
*/
int32_t AP_Landing::get_target_airspeed_cm(void)
{
if (!in_progress) {
if (!flags.in_progress) {
// not landing, use regular cruise airspeed
return aparm.airspeed_cruise_cm;
}
@ -400,8 +400,8 @@ bool AP_Landing::request_go_around(void)
void AP_Landing::handle_flight_stage_change(const bool _in_landing_stage)
{
in_progress = _in_landing_stage;
commanded_go_around = false;
flags.in_progress = _in_landing_stage;
flags.commanded_go_around = false;
}
/*

View File

@ -96,7 +96,7 @@ 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; }
bool is_commanded_go_around(void) const { return commanded_go_around; }
bool is_commanded_go_around(void) const { return flags.commanded_go_around; }
bool is_complete(void) const;
void set_initial_slope(void) { initial_slope = slope; }
bool is_expecting_impact(void) const;
@ -106,13 +106,13 @@ public:
private:
// once landed, post some landing statistics to the GCS
bool post_stats;
bool has_aborted_due_to_slope_recalc;
struct {
// denotes if a go-around has been commanded for landing
bool commanded_go_around;
bool commanded_go_around:1;
// are we in auto and flight_stage is LAND
bool in_progress:1;
} flags;
// same as land_slope but sampled once before a rangefinder changes the slope. This should be the original mission planned slope
float initial_slope;
@ -120,8 +120,6 @@ private:
// 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;
// are we in auto and flight_stage is LAND
bool in_progress;
AP_Mission &mission;
AP_AHRS &ahrs;
@ -153,13 +151,21 @@ private:
AP_Int8 type;
// Land Type STANDARD GLIDE SLOPE
enum slope_stage {
enum {
SLOPE_STAGE_NORMAL,
SLOPE_STAGE_APPROACH,
SLOPE_STAGE_PREFLARE,
SLOPE_STAGE_FINAL
};
slope_stage type_slope_stage;
} type_slope_stage;
struct {
// once landed, post some landing statistics to the GCS
bool post_stats:1;
bool has_aborted_due_to_slope_recalc:1;
} type_slope_flags;
void type_slope_do_land(const AP_Mission::Mission_Command& cmd, const float relative_altitude);
void type_slope_verify_abort_landing(const Location &prev_WP_loc, Location &next_WP_loc, bool &throttle_suppressed);
bool type_slope_verify_land(const Location &prev_WP_loc, Location &next_WP_loc, const Location &current_loc,

View File

@ -27,7 +27,7 @@ void AP_Landing::type_slope_do_land(const AP_Mission::Mission_Command& cmd, cons
slope = 0;
// once landed, post some landing statistics to the GCS
post_stats = false;
type_slope_flags.post_stats = false;
type_slope_stage = SLOPE_STAGE_NORMAL;
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Landing approach start at %.1fm", (double)relative_altitude);
@ -94,7 +94,7 @@ bool AP_Landing::type_slope_verify_land(const Location &prev_WP_loc, Location &n
probably_crashed) {
if (type_slope_stage != SLOPE_STAGE_FINAL) {
post_stats = true;
type_slope_flags.post_stats = true;
if (is_flying && (AP_HAL::millis()-last_flying_ms) > 3000) {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "Flare crash detected: speed=%.1f", (double)ahrs.get_gps().ground_speed());
} else {
@ -137,8 +137,8 @@ bool AP_Landing::type_slope_verify_land(const Location &prev_WP_loc, Location &n
// once landed and stationary, post some statistics
// this is done before disarm_if_autoland_complete() so that it happens on the next loop after the disarm
if (post_stats && !is_armed) {
post_stats = false;
if (type_slope_flags.post_stats && !is_armed) {
type_slope_flags.post_stats = false;
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Distance from LAND point=%.2fm", (double)get_distance(current_loc, next_WP_loc));
}
@ -183,7 +183,7 @@ void AP_Landing::type_slope_adjust_landing_slope_for_rangefinder_bump(AP_Vehicle
// correction positive means we're too low so we should continue on with
// the newly computed shallower slope instead of pitching/throttling up
} else if (slope_recalc_steep_threshold_to_abort > 0 && !has_aborted_due_to_slope_recalc) {
} else if (slope_recalc_steep_threshold_to_abort > 0 && !type_slope_flags.has_aborted_due_to_slope_recalc) {
// correction negative means we're too high and need to point down (and speed up) to re-align
// to land on target. A large negative correction means we would have to dive down a lot and will
// generating way too much speed that we can not bleed off in time. It is better to remember
@ -199,8 +199,8 @@ void AP_Landing::type_slope_adjust_landing_slope_for_rangefinder_bump(AP_Vehicle
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Landing slope too steep, aborting (%.0fm %.1fdeg)",
(double)rangefinder_state.correction, (double)(new_slope_deg - initial_slope_deg));
alt_offset = rangefinder_state.correction;
commanded_go_around = true;
has_aborted_due_to_slope_recalc = true; // only allow this once.
flags.commanded_go_around = true;
type_slope_flags.has_aborted_due_to_slope_recalc = true; // only allow this once.
}
}
}
@ -208,7 +208,7 @@ 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;
flags.commanded_go_around = true;
return true;
}