|
|
@ -830,6 +830,9 @@ bool set_nav_state(struct vehicle_status_s *status, |
|
|
|
} else if (offb_loss_rc_act == 4 && status_flags->condition_global_position_valid) { |
|
|
|
} else if (offb_loss_rc_act == 4 && status_flags->condition_global_position_valid) { |
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LAND; |
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LAND; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
} else if (offb_loss_rc_act == 5 && status_flags->condition_global_position_valid) { |
|
|
|
|
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER; |
|
|
|
|
|
|
|
|
|
|
|
} else if (status_flags->condition_local_altitude_valid) { |
|
|
|
} else if (status_flags->condition_local_altitude_valid) { |
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_DESCEND; |
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_DESCEND; |
|
|
|
|
|
|
|
|
|
|
|