Plane: simplify flight stage landing check to use landing.in_progress

This commit is contained in:
Tom Pittenger 2016-12-13 18:56:57 -08:00
parent 84e11fd899
commit 04f32b6ec6
7 changed files with 10 additions and 31 deletions

View File

@ -1083,9 +1083,7 @@ float Plane::tecs_hgt_afe(void)
coming.
*/
float hgt_afe;
if (flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND_FINAL ||
flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND_PREFLARE ||
flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND_APPROACH) {
if (landing.in_progress) {
hgt_afe = height_above_target();
hgt_afe -= rangefinder_correction();
} else {

View File

@ -1346,9 +1346,7 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
//Not allowing go around at FLIGHT_LAND_FINAL stage on purpose --
//if plane is close to the ground a go around could be dangerous.
if (plane.flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND_APPROACH ||
plane.flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND_PREFLARE ||
plane.flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND_FINAL) {
if (plane.landing.in_progress) {
// Initiate an aborted landing. This will trigger a pitch-up and
// climb-out to a safe altitude holding heading then one of the
// following actions will occur, check for in this order:

View File

@ -380,9 +380,7 @@ void Plane::set_offset_altitude_location(const Location &loc)
}
#endif
if (flight_stage != AP_Vehicle::FixedWing::FLIGHT_LAND_PREFLARE &&
flight_stage != AP_Vehicle::FixedWing::FLIGHT_LAND_APPROACH &&
flight_stage != AP_Vehicle::FixedWing::FLIGHT_LAND_FINAL) {
if (!landing.in_progress) {
// if we are within GLIDE_SLOPE_MIN meters of the target altitude
// then reset the offset to not use a glide slope. This allows for
// more accurate flight of missions where the aircraft may lose or
@ -577,9 +575,7 @@ float Plane::rangefinder_correction(void)
// for now we only support the rangefinder for landing
bool using_rangefinder = (g.rangefinder_landing &&
control_mode == AUTO &&
(flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND_APPROACH ||
flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND_PREFLARE ||
flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND_FINAL));
landing.in_progress);
if (!using_rangefinder) {
return 0;
}
@ -620,9 +616,7 @@ void Plane::rangefinder_height_update(void)
} else {
rangefinder_state.in_range = true;
if (!rangefinder_state.in_use &&
(flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND_APPROACH ||
flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND_PREFLARE ||
flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND_FINAL ||
(landing.in_progress ||
control_mode == QLAND ||
control_mode == QRTL ||
(control_mode == AUTO && plane.mission.get_current_nav_cmd().id == MAV_CMD_NAV_VTOL_LAND)) &&

View File

@ -141,9 +141,7 @@ void Plane::low_battery_event(void)
}
gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Low battery %.2fV used %.0f mAh",
(double)battery.voltage(), (double)battery.current_total_mah());
if (flight_stage != AP_Vehicle::FixedWing::FLIGHT_LAND_FINAL &&
flight_stage != AP_Vehicle::FixedWing::FLIGHT_LAND_PREFLARE &&
flight_stage != AP_Vehicle::FixedWing::FLIGHT_LAND_APPROACH) {
if (!landing.in_progress) {
set_mode(RTL, MODE_REASON_BATTERY_FAILSAFE);
aparm.throttle_cruise.load();
}

View File

@ -33,9 +33,7 @@ void Plane::read_rangefinder(void)
#endif
{
// use the best available alt estimate via baro above home
if (flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND_APPROACH ||
flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND_PREFLARE ||
flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND_FINAL) {
if (landing.in_progress) {
// ensure the rangefinder is powered-on when land alt is higher than home altitude.
// This is done using the target alt which we know is below us and we are sinking to it
height = height_above_target();

View File

@ -28,8 +28,7 @@ void Plane::throttle_slew_limit(int16_t last_throttle)
if (control_mode==AUTO) {
if (auto_state.takeoff_complete == false && g.takeoff_throttle_slewrate != 0) {
slewrate = g.takeoff_throttle_slewrate;
} else if (landing.get_throttle_slewrate() != 0 &&
(flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND_APPROACH || flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND_FINAL || flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND_PREFLARE)) {
} else if (landing.get_throttle_slewrate() != 0 && landing.in_progress) {
slewrate = landing.get_throttle_slewrate();
}
}

View File

@ -551,10 +551,7 @@ void Plane::check_long_failsafe()
uint32_t tnow = millis();
// only act on changes
// -------------------
if(failsafe.state != FAILSAFE_LONG && failsafe.state != FAILSAFE_GCS &&
flight_stage != AP_Vehicle::FixedWing::FLIGHT_LAND_FINAL &&
flight_stage != AP_Vehicle::FixedWing::FLIGHT_LAND_PREFLARE &&
flight_stage != AP_Vehicle::FixedWing::FLIGHT_LAND_APPROACH) {
if(failsafe.state != FAILSAFE_LONG && failsafe.state != FAILSAFE_GCS && !landing.in_progress) {
if (failsafe.state == FAILSAFE_SHORT &&
(tnow - failsafe.ch3_timer_ms) > g.long_fs_timeout*1000) {
failsafe_long_on_event(FAILSAFE_LONG, MODE_REASON_RADIO_FAILSAFE);
@ -587,10 +584,7 @@ void Plane::check_short_failsafe()
{
// only act on changes
// -------------------
if(failsafe.state == FAILSAFE_NONE &&
flight_stage != AP_Vehicle::FixedWing::FLIGHT_LAND_FINAL &&
flight_stage != AP_Vehicle::FixedWing::FLIGHT_LAND_PREFLARE &&
flight_stage != AP_Vehicle::FixedWing::FLIGHT_LAND_APPROACH) {
if(failsafe.state == FAILSAFE_NONE && !landing.in_progress) {
// The condition is checked and the flag ch3_failsafe is set in radio.cpp
if(failsafe.ch3_failsafe) {
failsafe_short_on_event(FAILSAFE_SHORT, MODE_REASON_RADIO_FAILSAFE);