Plane: correct on_flight_line landing stage check

This commit is contained in:
Peter Barker 2016-12-06 21:46:33 +11:00 committed by Tom Pittenger
parent 3e89580383
commit 669dc01b67

View File

@ -990,7 +990,7 @@ void Plane::update_flight_stage(void)
set_flight_stage(AP_SpdHgtControl::FLIGHT_LAND_PREFLARE);
} else if (flight_stage != AP_SpdHgtControl::FLIGHT_LAND_APPROACH) {
bool heading_lined_up = abs(nav_controller->bearing_error_cd()) < 1000 && !nav_controller->data_is_stale();
bool on_flight_line = abs(nav_controller->crosstrack_error() < 5) && !nav_controller->data_is_stale();
const bool on_flight_line = fabs(nav_controller->crosstrack_error()) < 5.0f && !nav_controller->data_is_stale();
bool below_prev_WP = current_loc.alt < prev_WP_loc.alt;
if ((mission.get_prev_nav_cmd_id() == MAV_CMD_NAV_LOITER_TO_ALT) ||
(auto_state.wp_proportion >= 0 && heading_lined_up && on_flight_line) ||