From 86b162e32f8aaf67ecaf3ad8771cd1c0851e0fd9 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 23 Feb 2018 16:40:29 +1100 Subject: [PATCH] Copter: add option to disable BRAKE flight mode --- ArduCopter/APM_Config.h | 1 + ArduCopter/Copter.h | 2 ++ ArduCopter/GCS_Mavlink.cpp | 4 ++++ ArduCopter/config.h | 6 ++++++ ArduCopter/mode.cpp | 2 ++ 5 files changed, 15 insertions(+) diff --git a/ArduCopter/APM_Config.h b/ArduCopter/APM_Config.h index ad546791f7..3c82fc756c 100644 --- a/ArduCopter/APM_Config.h +++ b/ArduCopter/APM_Config.h @@ -24,6 +24,7 @@ //#define SPRAYER DISABLED // disable the crop sprayer feature (two ESC controlled pumps the speed of which depends upon the vehicle's horizontal velocity) //#define WINCH_ENABLED DISABLED // disable winch support //#define MODE_AUTO_ENABLED DISABLED // disable auto mode support +//#define MODE_BRAKE_ENABLED DISABLED // disable brake 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 diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index a173df9f02..6b71543192 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -962,7 +962,9 @@ private: #if AUTOTUNE_ENABLED == ENABLED ModeAutoTune mode_autotune; #endif +#if MODE_BRAKE_ENABLED == ENABLED ModeBrake mode_brake; +#endif ModeCircle mode_circle; #if MODE_DRIFT_ENABLED == ENABLED ModeDrift mode_drift; diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 289a486137..62ae7b6be7 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -1303,11 +1303,15 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg) bool shot_mode = (!is_zero(packet.param1) && (copter.control_mode == GUIDED || copter.control_mode == GUIDED_NOGPS)); if (!shot_mode) { +#if MODE_BRAKE_ENABLED == ENABLED if (copter.set_mode(BRAKE, MODE_REASON_GCS_COMMAND)) { copter.mode_brake.timeout_to_loiter_ms(2500); } else { copter.set_mode(ALT_HOLD, MODE_REASON_GCS_COMMAND); } +#else + copter.set_mode(ALT_HOLD, MODE_REASON_GCS_COMMAND); +#endif } else { // SoloLink is expected to handle pause in shots } diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 0fcdc63517..0721015600 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -273,6 +273,12 @@ # define MODE_AUTO_ENABLED ENABLED #endif +////////////////////////////////////////////////////////////////////////////// +// Brake mode - bring vehicle to stop +#ifndef MODE_BRAKE_ENABLED +# define MODE_BRAKE_ENABLED ENABLED +#endif + ////////////////////////////////////////////////////////////////////////////// // Drift - fly vehicle in altitude-held, coordinated-turn mode #ifndef MODE_DRIFT_ENABLED diff --git a/ArduCopter/mode.cpp b/ArduCopter/mode.cpp index 84b9c3a0df..4cb5ee59a0 100644 --- a/ArduCopter/mode.cpp +++ b/ArduCopter/mode.cpp @@ -110,9 +110,11 @@ Copter::Mode *Copter::mode_from_mode_num(const uint8_t mode) break; #endif +#if MODE_BRAKE_ENABLED == ENABLED case BRAKE: ret = &mode_brake; break; +#endif case THROW: ret = &mode_throw;