mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
FlightModeManager: switch to failsafe task if orbit is rejected
This commit is contained in:
parent
18074dec5a
commit
fc0be6c4fc
@ -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;
|
||||
}
|
||||
}
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user