rover: Fix parameter type capitalization

This parameter type is used by groundstation to create the parameter subcategory
Since this creationg is case sensitive, the capitalization should be done here.

Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
Patrick José Pereira 2019-05-17 10:39:25 -03:00 committed by Randy Mackay
parent c69adf8a7d
commit 1c816b1fe1
1 changed files with 2 additions and 2 deletions

View File

@ -72,7 +72,7 @@ const AP_Param::Info Rover::var_info[] = {
// @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:APM TriggerPin0,1:APM TriggerPin1,2:APM TriggerPin2,3:APM TriggerPin3,4:APM TriggerPin4,5:APM TriggerPin5,6:APM TriggerPin6,7:APM TriggerPin7,8:APM TriggerPin8,50:Pixhawk TriggerPin50,51:Pixhawk TriggerPin51,52:Pixhawk TriggerPin52,53:Pixhawk TriggerPin53,54:Pixhawk TriggerPin54,55:Pixhawk TriggerPin55
// @User: standard
// @User: Standard
GSCALAR(auto_trigger_pin, "AUTO_TRIGGER_PIN", -1),
// @Param: AUTO_KICKSTART
@ -81,7 +81,7 @@ const AP_Param::Info Rover::var_info[] = {
// @Units: m/s/s
// @Range: 0 20
// @Increment: 0.1
// @User: standard
// @User: Standard
GSCALAR(auto_kickstart, "AUTO_KICKSTART", 0.0f),
// @Param: CRUISE_SPEED