From be2e24391618e5cb3dd16f2f4a741f14fed51e42 Mon Sep 17 00:00:00 2001 From: Pierre Kancir Date: Mon, 2 Nov 2020 18:46:01 +0100 Subject: [PATCH] Copter: add initial mode parameter --- ArduCopter/Parameters.cpp | 7 +++++++ ArduCopter/Parameters.h | 2 ++ 2 files changed, 9 insertions(+) diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index faa917bfa9..2c41adb7eb 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -308,6 +308,13 @@ const AP_Param::Info Copter::var_info[] = { // @User: Advanced GSCALAR(flight_mode_chan, "FLTMODE_CH", CH_MODE_DEFAULT), + // @Param: INITIAL_MODE + // @DisplayName: Initial flight mode + // @Description: This selects the mode to start in on boot. This is useful for when you want to start in AUTO mode on boot without a receiver. + // @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL,22:FlowHold,23:Follow,24:ZigZag,25:SystemID,26:Heli_Autorotate + // @User: Advanced + GSCALAR(initial_mode, "INITIAL_MODE", (uint8_t)Mode::Number::STABILIZE), + // @Param: SIMPLE // @DisplayName: Simple mode bitmask // @Description: Bitmask which holds which flight modes use simple heading mode (eg bit 0 = 1 means Flight Mode 0 uses simple mode) diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index 463952d5bd..1ce292305d 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -315,6 +315,7 @@ public: k_param_flight_mode6, k_param_simple_modes, k_param_flight_mode_chan, + k_param_initial_mode, // // 210: Waypoint data @@ -431,6 +432,7 @@ public: AP_Int8 flight_mode6; AP_Int8 simple_modes; AP_Int8 flight_mode_chan; + AP_Int8 initial_mode; // Misc //