From a0bf49ab420ae00915ad1e0c8b4c780bc4f947a7 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 2 Jun 2013 07:55:38 +1000 Subject: [PATCH] Rover: updated AUTO_TRIGGER_PIN docs --- APMrover2/Parameters.pde | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/APMrover2/Parameters.pde b/APMrover2/Parameters.pde index eab5e10680..54d36f5c5d 100644 --- a/APMrover2/Parameters.pde +++ b/APMrover2/Parameters.pde @@ -142,8 +142,8 @@ const AP_Param::Info var_info[] PROGMEM = { // @Param: AUTO_TRIGGER_PIN // @DisplayName: Auto mode trigger pin - // @Description: pin number to use to trigger start of auto mode. If set to -1 then don't use a trigger, otherwise this is a pin number which if held low in auto mode will start the motor, and otherwise will force the throttle off. This can be used in combination with INITIAL_MODE to give a 'press button to start' rover with no receiver. - // @Values: -1:Disabled,0-9:TiggerPin + // @Description: pin number to use to enable the throttle in auto mode. If set to -1 then don't use a trigger, otherwise this is a pin number which if held low in auto mode will enable the motor to run. If the switch is released while in AUTO then the motor will stop again. This can be used in combination with INITIAL_MODE to give a 'press button to start' rover with no receiver. + // @Values: -1:Disabled,0-8:TiggerPin // @User: standard GSCALAR(auto_trigger_pin, "AUTO_TRIGGER_PIN", -1),