mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-02 03:49:12 +08:00
FlightModeManager: switch to failsafe task if orbit is rejected
This commit is contained in:
@@ -428,7 +428,7 @@ void FlightModeManager::handleCommand()
|
|||||||
|
|
||||||
// if we just switched and parameters are not accepted, go to failsafe
|
// if we just switched and parameters are not accepted, go to failsafe
|
||||||
if (switch_result >= FlightTaskError::NoError) {
|
if (switch_result >= FlightTaskError::NoError) {
|
||||||
switchTask(FlightTaskIndex::ManualPosition);
|
switchTask(FlightTaskIndex::Failsafe);
|
||||||
cmd_result = vehicle_command_ack_s::VEHICLE_RESULT_FAILED;
|
cmd_result = vehicle_command_ack_s::VEHICLE_RESULT_FAILED;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
Reference in New Issue
Block a user