commander NAV_RETURN_TO_LAUNCH change mode to RTL

This commit is contained in:
Daniel Agar 2016-10-30 16:10:02 -04:00 committed by Lorenz Meier
parent 0bff3593d3
commit 27a50275b6
1 changed files with 13 additions and 3 deletions

View File

@ -1048,6 +1048,18 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s
} }
break; break;
case vehicle_command_s::VEHICLE_CMD_NAV_RETURN_TO_LAUNCH: {
if (TRANSITION_CHANGED == main_state_transition(&status, commander_state_s::MAIN_STATE_AUTO_RTL, main_state_prev, &status_flags, &internal_state)) {
mavlink_and_console_log_info(&mavlink_log_pub, "Returning to launch");
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
} else {
mavlink_log_critical(&mavlink_log_pub, "Return to launch denied");
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
}
}
break;
case vehicle_command_s::VEHICLE_CMD_NAV_TAKEOFF: { case vehicle_command_s::VEHICLE_CMD_NAV_TAKEOFF: {
/* ok, home set, use it to take off */ /* ok, home set, use it to take off */
if (TRANSITION_CHANGED == main_state_transition(&status, commander_state_s::MAIN_STATE_AUTO_TAKEOFF, main_state_prev, &status_flags, &internal_state)) { if (TRANSITION_CHANGED == main_state_transition(&status, commander_state_s::MAIN_STATE_AUTO_TAKEOFF, main_state_prev, &status_flags, &internal_state)) {
@ -1058,7 +1070,6 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s
mavlink_log_critical(&mavlink_log_pub, "Takeoff denied, disarm and re-try"); mavlink_log_critical(&mavlink_log_pub, "Takeoff denied, disarm and re-try");
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED; cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
} }
} }
break; break;
@ -1068,10 +1079,9 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED; cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
} else { } else {
mavlink_log_critical(&mavlink_log_pub, "Landing denied, land manually."); mavlink_log_critical(&mavlink_log_pub, "Landing denied, land manually");
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED; cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
} }
} }
break; break;