From 81f0141da559f320da86c8a645c7d23ca6ca63ba Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 1 Nov 2019 09:32:04 +1100 Subject: [PATCH] Copter: correct compilation when AdvancedFailsafe is disabled --- ArduCopter/afs_copter.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/ArduCopter/afs_copter.cpp b/ArduCopter/afs_copter.cpp index 859c05291c..940459bfe9 100644 --- a/ArduCopter/afs_copter.cpp +++ b/ArduCopter/afs_copter.cpp @@ -18,7 +18,7 @@ AP_AdvancedFailsafe_Copter::AP_AdvancedFailsafe_Copter(AP_Mission &_mission) : void AP_AdvancedFailsafe_Copter::terminate_vehicle(void) { if (_terminate_action == TERMINATE_ACTION_LAND) { - copter.set_mode(LAND, MODE_REASON_TERMINATE); + copter.set_mode(Mode::Number::LAND, ModeReason::TERMINATE); } else { // stop motors copter.motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN); @@ -62,10 +62,10 @@ void AP_AdvancedFailsafe_Copter::setup_IO_failsafe(void) AP_AdvancedFailsafe::control_mode AP_AdvancedFailsafe_Copter::afs_mode(void) { switch (copter.control_mode) { - case AUTO: - case GUIDED: - case RTL: - case LAND: + case Mode::Number::AUTO: + case Mode::Number::GUIDED: + case Mode::Number::RTL: + case Mode::Number::LAND: return AP_AdvancedFailsafe::AFS_AUTO; default: break;