From 3f9ade2b1f448242d0045a86ebefa96eda951330 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 3 May 2013 07:59:15 +1000 Subject: [PATCH] Rover: added INITIAL_MODE option this should be useful for sparkfun comp --- APMrover2/Parameters.h | 2 ++ APMrover2/Parameters.pde | 7 +++++++ APMrover2/system.pde | 2 +- 3 files changed, 10 insertions(+), 1 deletion(-) diff --git a/APMrover2/Parameters.h b/APMrover2/Parameters.h index e9f86243ab..237ee29bc7 100644 --- a/APMrover2/Parameters.h +++ b/APMrover2/Parameters.h @@ -31,6 +31,7 @@ public: k_param_log_bitmask = 10, k_param_num_resets, k_param_reset_switch_chan, + k_param_initial_mode, // IO pins k_param_rssi_pin = 20, @@ -150,6 +151,7 @@ public: AP_Int16 log_bitmask; AP_Int16 num_resets; AP_Int8 reset_switch_chan; + AP_Int8 initial_mode; // IO pins AP_Int8 rssi_pin; diff --git a/APMrover2/Parameters.pde b/APMrover2/Parameters.pde index d7ea250e2e..192910b698 100644 --- a/APMrover2/Parameters.pde +++ b/APMrover2/Parameters.pde @@ -22,6 +22,13 @@ const AP_Param::Info var_info[] PROGMEM = { GSCALAR(num_resets, "SYS_NUM_RESETS", 0), GSCALAR(reset_switch_chan, "RST_SWITCH_CH", 0), + // @Param: INITIAL_MODE + // @DisplayName: Initial driving 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. Usuallly used in combination with when AUTO_TRIGGER_PIN or AUTO_KICKSTART. + // @Values: 0:MANUAL,2:LEARNING,3:STEERING,4:HOLD,10:AUTO,11:RTL,15:GUIDED + // @User: Advanced + GSCALAR(initial_mode, "INITIAL_MODE", MANUAL), + // @Param: RSSI_PIN // @DisplayName: Receiver RSSI sensing pin // @Description: This selects an analog pin for the receiver RSSI voltage. It assumes the voltage is 5V for max rssi, 0V for minimum diff --git a/APMrover2/system.pde b/APMrover2/system.pde index 8a5280ab52..ecb52d6738 100644 --- a/APMrover2/system.pde +++ b/APMrover2/system.pde @@ -248,7 +248,7 @@ static void init_ardupilot() if (g.log_bitmask & MASK_LOG_CMD) Log_Write_Startup(TYPE_GROUNDSTART_MSG); - set_mode(MANUAL); + set_mode((enum mode)g.initial_mode.get()); // set the correct flight mode // ---------------------------