From fc0be6c4fc5fa14ad8e8d40e4d13401a414143ec Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Mon, 28 Mar 2022 11:40:17 +0200 Subject: [PATCH] FlightModeManager: switch to failsafe task if orbit is rejected --- src/modules/flight_mode_manager/FlightModeManager.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/flight_mode_manager/FlightModeManager.cpp b/src/modules/flight_mode_manager/FlightModeManager.cpp index 70bb9671a1..366ba68f94 100644 --- a/src/modules/flight_mode_manager/FlightModeManager.cpp +++ b/src/modules/flight_mode_manager/FlightModeManager.cpp @@ -428,7 +428,7 @@ void FlightModeManager::handleCommand() // if we just switched and parameters are not accepted, go to failsafe if (switch_result >= FlightTaskError::NoError) { - switchTask(FlightTaskIndex::ManualPosition); + switchTask(FlightTaskIndex::Failsafe); cmd_result = vehicle_command_ack_s::VEHICLE_RESULT_FAILED; } }