From 4884932280f9b422f610e8572d89eb0384372a18 Mon Sep 17 00:00:00 2001 From: Dario Lindo Andres Date: Fri, 10 Apr 2015 10:15:41 +0200 Subject: [PATCH] Rover: Updated AUTO_TRIGGER_PIN value definitions Mission Planner and parameter.h definitions seem to be outdated. A bit confusing because when its readed, you think you need to define it between 0-8 (APM boards) instead of 50-55 (PX4-Pixhawk boards). --- APMrover2/Parameters.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/APMrover2/Parameters.pde b/APMrover2/Parameters.pde index 0b5082a02a..943a366902 100644 --- a/APMrover2/Parameters.pde +++ b/APMrover2/Parameters.pde @@ -82,7 +82,7 @@ const AP_Param::Info var_info[] PROGMEM = { // @Param: AUTO_TRIGGER_PIN // @DisplayName: Auto mode trigger pin // @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 + // @Values: -1:Disabled, 0-8:APM TriggerPin, 50-55: Pixhawk TriggerPin // @User: standard GSCALAR(auto_trigger_pin, "AUTO_TRIGGER_PIN", -1),