Rover: added INITIAL_MODE option

this should be useful for sparkfun comp
This commit is contained in:
Andrew Tridgell 2013-05-03 07:59:15 +10:00
parent b890fbdba2
commit 3f9ade2b1f
3 changed files with 10 additions and 1 deletions

View File

@ -31,6 +31,7 @@ public:
k_param_log_bitmask = 10, k_param_log_bitmask = 10,
k_param_num_resets, k_param_num_resets,
k_param_reset_switch_chan, k_param_reset_switch_chan,
k_param_initial_mode,
// IO pins // IO pins
k_param_rssi_pin = 20, k_param_rssi_pin = 20,
@ -150,6 +151,7 @@ public:
AP_Int16 log_bitmask; AP_Int16 log_bitmask;
AP_Int16 num_resets; AP_Int16 num_resets;
AP_Int8 reset_switch_chan; AP_Int8 reset_switch_chan;
AP_Int8 initial_mode;
// IO pins // IO pins
AP_Int8 rssi_pin; AP_Int8 rssi_pin;

View File

@ -22,6 +22,13 @@ const AP_Param::Info var_info[] PROGMEM = {
GSCALAR(num_resets, "SYS_NUM_RESETS", 0), GSCALAR(num_resets, "SYS_NUM_RESETS", 0),
GSCALAR(reset_switch_chan, "RST_SWITCH_CH", 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 // @Param: RSSI_PIN
// @DisplayName: Receiver RSSI sensing 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 // @Description: This selects an analog pin for the receiver RSSI voltage. It assumes the voltage is 5V for max rssi, 0V for minimum

View File

@ -248,7 +248,7 @@ static void init_ardupilot()
if (g.log_bitmask & MASK_LOG_CMD) if (g.log_bitmask & MASK_LOG_CMD)
Log_Write_Startup(TYPE_GROUNDSTART_MSG); Log_Write_Startup(TYPE_GROUNDSTART_MSG);
set_mode(MANUAL); set_mode((enum mode)g.initial_mode.get());
// set the correct flight mode // set the correct flight mode
// --------------------------- // ---------------------------