mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
ArduCopter: use an enumeration for the AP_Avoidance recovery action
This commit is contained in:
parent
36e6ce6e5e
commit
38122eb35e
@ -97,7 +97,7 @@ MAV_COLLISION_ACTION AP_Avoidance_Copter::handle_avoidance(const AP_Avoidance::O
|
||||
return actual_action;
|
||||
}
|
||||
|
||||
void AP_Avoidance_Copter::handle_recovery(uint8_t recovery_action)
|
||||
void AP_Avoidance_Copter::handle_recovery(RecoveryAction recovery_action)
|
||||
{
|
||||
// check we are coming out of failsafe
|
||||
if (copter.failsafe.adsb) {
|
||||
@ -109,19 +109,19 @@ void AP_Avoidance_Copter::handle_recovery(uint8_t recovery_action)
|
||||
if (copter.control_mode_reason == ModeReason::AVOIDANCE) {
|
||||
switch (recovery_action) {
|
||||
|
||||
case AP_AVOIDANCE_RECOVERY_REMAIN_IN_AVOID_ADSB:
|
||||
case RecoveryAction::REMAIN_IN_AVOID_ADSB:
|
||||
// do nothing, we'll stay in the AVOID_ADSB mode which is guided which will loiter forever
|
||||
break;
|
||||
|
||||
case AP_AVOIDANCE_RECOVERY_RESUME_PREVIOUS_FLIGHTMODE:
|
||||
case RecoveryAction::RESUME_PREVIOUS_FLIGHTMODE:
|
||||
set_mode_else_try_RTL_else_LAND(prev_control_mode);
|
||||
break;
|
||||
|
||||
case AP_AVOIDANCE_RECOVERY_RTL:
|
||||
case RecoveryAction::RTL:
|
||||
set_mode_else_try_RTL_else_LAND(Mode::Number::RTL);
|
||||
break;
|
||||
|
||||
case AP_AVOIDANCE_RECOVERY_RESUME_IF_AUTO_ELSE_LOITER:
|
||||
case RecoveryAction::RESUME_IF_AUTO_ELSE_LOITER:
|
||||
if (prev_control_mode == Mode::Number::AUTO) {
|
||||
set_mode_else_try_RTL_else_LAND(Mode::Number::AUTO);
|
||||
}
|
||||
|
@ -24,7 +24,7 @@ protected:
|
||||
MAV_COLLISION_ACTION handle_avoidance(const AP_Avoidance::Obstacle *obstacle, MAV_COLLISION_ACTION requested_action) override;
|
||||
|
||||
// override recovery handler
|
||||
void handle_recovery(uint8_t recovery_action) override;
|
||||
void handle_recovery(RecoveryAction recovery_action) override;
|
||||
|
||||
// check flight mode is avoid_adsb
|
||||
bool check_flightmode(bool allow_mode_change);
|
||||
|
Loading…
Reference in New Issue
Block a user