From b8c432b1a13d3320762c8b4baa009b435b33e9aa Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 23 Feb 2018 15:09:07 +1100 Subject: [PATCH] Copter: add option to disable GUIDED flight mode Saves about 6kB of flash --- ArduCopter/APM_Config.h | 1 + ArduCopter/Copter.h | 2 ++ ArduCopter/GCS_Mavlink.cpp | 2 ++ ArduCopter/config.h | 10 ++++++++++ ArduCopter/mode.cpp | 2 ++ ArduCopter/takeoff.cpp | 2 ++ 6 files changed, 19 insertions(+) diff --git a/ArduCopter/APM_Config.h b/ArduCopter/APM_Config.h index 41f51db89e..c254703f52 100644 --- a/ArduCopter/APM_Config.h +++ b/ArduCopter/APM_Config.h @@ -25,6 +25,7 @@ //#define WINCH_ENABLED DISABLED // disable winch support //#define MODE_AUTO_ENABLED DISABLED // disable auto mode support //#define MODE_DRIFT_ENABLED DISABLED // disable drift mode support +//#define MODE_GUIDED_ENABLED DISABLED // disable guided mode support //#define MODE_LOITER_ENABLED DISABLED // disable loiter mode support //#define MODE_POSHOLD_ENABLED DISABLED // disable poshold mode support //#define MODE_SMARTRTL_ENABLED DISABLED // disable smartrtl mode support diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index c0d7fd8136..97d7d711e8 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -968,7 +968,9 @@ private: ModeDrift mode_drift; #endif ModeFlip mode_flip; +#if MODE_GUIDED_ENABLED == ENABLED ModeGuided mode_guided; +#endif ModeLand mode_land; #if MODE_LOITER_ENABLED == ENABLED ModeLoiter mode_loiter; diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index b6d14f64ce..289a486137 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -1341,6 +1341,7 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg) break; } +#if MODE_GUIDED_ENABLED == ENABLED case MAVLINK_MSG_ID_SET_ATTITUDE_TARGET: // MAV ID: 82 { // decode packet @@ -1581,6 +1582,7 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg) break; } +#endif case MAVLINK_MSG_ID_DISTANCE_SENSOR: { diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 299076e6c9..e040b56f67 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -279,6 +279,12 @@ # define MODE_DRIFT_ENABLED ENABLED #endif +////////////////////////////////////////////////////////////////////////////// +// Guided mode - control vehicle's position or angles from GCS +#ifndef MODE_GUIDED_ENABLED +# define MODE_GUIDED_ENABLED ENABLED +#endif + ////////////////////////////////////////////////////////////////////////////// // Loiter mode - allows vehicle to hold global position #ifndef MODE_LOITER_ENABLED @@ -616,6 +622,10 @@ #error AC_Avoidance relies on AC_FENCE which is disabled #endif +#if MODE_AUTO_ENABLED && !MODE_GUIDED_ENABLED + #error ModeAuto requires ModeGuided which is disabled +#endif + ////////////////////////////////////////////////////////////////////////////// // Developer Items // diff --git a/ArduCopter/mode.cpp b/ArduCopter/mode.cpp index c9b8896f8d..d75b91f823 100644 --- a/ArduCopter/mode.cpp +++ b/ArduCopter/mode.cpp @@ -66,9 +66,11 @@ Copter::Mode *Copter::mode_from_mode_num(const uint8_t mode) break; #endif +#if MODE_GUIDED_ENABLED == ENABLED case GUIDED: ret = &mode_guided; break; +#endif case LAND: ret = &mode_land; diff --git a/ArduCopter/takeoff.cpp b/ArduCopter/takeoff.cpp index 401fe0a413..5116c8120e 100644 --- a/ArduCopter/takeoff.cpp +++ b/ArduCopter/takeoff.cpp @@ -36,12 +36,14 @@ bool Copter::do_user_takeoff(float takeoff_alt_cm, bool must_navigate) #endif switch(control_mode) { +#if MODE_GUIDED_ENABLED == ENABLED case GUIDED: if (mode_guided.takeoff_start(takeoff_alt_cm)) { set_auto_armed(true); return true; } return false; +#endif case LOITER: case POSHOLD: case ALT_HOLD: