mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
Plane: take advantage of L1 stale flag and correctly inhibit flight stage if not lined up on approach
This commit is contained in:
parent
25c3367341
commit
183369b92a
@ -927,9 +927,11 @@ void Plane::update_flight_stage(void)
|
||||
} else if (auto_state.land_pre_flare == true) {
|
||||
set_flight_stage(AP_SpdHgtControl::FLIGHT_LAND_PREFLARE);
|
||||
} else if (flight_stage != AP_SpdHgtControl::FLIGHT_LAND_APPROACH) {
|
||||
bool lined_up = abs(nav_controller->bearing_error_cd()) < 1000;
|
||||
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();
|
||||
bool below_prev_WP = current_loc.alt < prev_WP_loc.alt;
|
||||
if ((auto_state.wp_proportion > 0.15 && lined_up && below_prev_WP) ||
|
||||
if ((auto_state.wp_proportion >= 0 && heading_lined_up && on_flight_line) ||
|
||||
(auto_state.wp_proportion > 0.15f && heading_lined_up && below_prev_WP) ||
|
||||
(auto_state.wp_proportion > 0.5f)) {
|
||||
set_flight_stage(AP_SpdHgtControl::FLIGHT_LAND_APPROACH);
|
||||
} else {
|
||||
|
@ -32,6 +32,8 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd)
|
||||
// once landed, post some landing statistics to the GCS
|
||||
auto_state.post_landing_stats = false;
|
||||
|
||||
nav_controller->set_data_is_stale();
|
||||
|
||||
// reset loiter start time. New command is a new loiter
|
||||
loiter.start_time_ms = 0;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user