From af53f9ce64e9e432ca52110568b5d807755db7c1 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 1 Oct 2020 21:45:40 +1000 Subject: [PATCH] Copter: correct compilation when AUTO/RTL are disabled --- ArduCopter/AP_Arming.cpp | 2 ++ ArduCopter/GCS_Mavlink.cpp | 2 ++ 2 files changed, 4 insertions(+) diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index 5e4942f636..b39c460f91 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -229,6 +229,7 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure) #endif // HELI_FRAME // checks when using range finder for RTL +#if MODE_RTL_ENABLED == ENABLED if (copter.mode_rtl.get_alt_type() == ModeRTL::RTLAltType::RTL_ALTTYPE_TERRAIN) { // get terrain source from wpnav switch (copter.wp_nav->get_terrain_source()) { @@ -267,6 +268,7 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure) break; } } +#endif // check adsb avoidance failsafe #if HAL_ADSB_ENABLED diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index fb526f26e2..c19d78a215 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -697,11 +697,13 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_ return MAV_RESULT_ACCEPTED; } +#if MODE_AUTO_ENABLED == ENABLED case MAV_CMD_DO_LAND_START: if (copter.mode_auto.mission.jump_to_landing_sequence() && copter.set_mode(Mode::Number::AUTO, ModeReason::GCS_COMMAND)) { return MAV_RESULT_ACCEPTED; } return MAV_RESULT_FAILED; +#endif case MAV_CMD_NAV_LOITER_UNLIM: if (!copter.set_mode(Mode::Number::LOITER, ModeReason::GCS_COMMAND)) {