mirror of https://github.com/ArduPilot/ardupilot
Plane: do not use guided waypoint for loiter location
Currently this waypoint is set 10,000m away by the avoidance behaviour Instead, immediately enter loiter mode
This commit is contained in:
parent
07d0336334
commit
9e45882340
|
@ -134,11 +134,20 @@ void AP_Avoidance_Plane::handle_recovery(RecoveryAction recovery_action)
|
|||
case RecoveryAction::RESUME_IF_AUTO_ELSE_LOITER:
|
||||
if (prev_control_mode_number == Mode::Number::AUTO) {
|
||||
plane.set_mode(plane.mode_auto, ModeReason::AVOIDANCE_RECOVERY);
|
||||
} else {
|
||||
// let ModeAvoidADSB continue in its guided
|
||||
// behaviour, but reset the loiter location,
|
||||
// rather than where the avoidance location was
|
||||
plane.guided_WP_loc = plane.current_loc;
|
||||
plane.set_guided_WP();
|
||||
}
|
||||
// else do nothing, same as RecoveryAction::LOITER
|
||||
break;
|
||||
|
||||
default:
|
||||
// user has specified an invalid recovery action;
|
||||
// loiter where we are
|
||||
plane.guided_WP_loc = plane.current_loc;
|
||||
plane.set_guided_WP();
|
||||
break;
|
||||
} // switch
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue