introduce new nav state to allow normal rtl with RC switch

This commit is contained in:
Thomas Gubler
2014-08-26 22:22:59 +02:00
parent 8a9da209d1
commit 3d528a2c97
3 changed files with 6 additions and 2 deletions

View File

@@ -462,7 +462,7 @@ bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_en
status->failsafe = true;
if (status->condition_global_position_valid && status->condition_home_position_valid) {
status->nav_state = NAVIGATION_STATE_AUTO_RTL;
status->nav_state = NAVIGATION_STATE_AUTO_RCRECOVER;
} else if (status->condition_local_position_valid) {
status->nav_state = NAVIGATION_STATE_LAND;
} else if (status->condition_local_altitude_valid) {