mirror of https://github.com/ArduPilot/ardupilot
RC_Channel: add autotune switch
This commit is contained in:
parent
d5bd30bce0
commit
9da6f321a0
|
@ -239,6 +239,7 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = {
|
|||
// @Values{Plane}: 176:Quadplane Fwd Throttle Override enable
|
||||
// @Values{Copter, Rover, Plane, Blimp}: 177:Mount LRF enable
|
||||
// @Values{Copter}: 178:FlightMode Pause/Resume
|
||||
// @Values{Copter, Plane}: 180:Test autotuned gains after tune is complete
|
||||
// @Values{Rover}: 201:Roll
|
||||
// @Values{Rover}: 202:Pitch
|
||||
// @Values{Rover}: 207:MainSail
|
||||
|
|
|
@ -119,7 +119,7 @@ public:
|
|||
ACRO_TRAINER = 14, // low = disabled, middle = leveled, high = leveled and limited
|
||||
SPRAYER = 15, // enable/disable the crop sprayer
|
||||
AUTO = 16, // change to auto flight mode
|
||||
AUTOTUNE = 17, // auto tune
|
||||
AUTOTUNE_MODE = 17, // auto tune
|
||||
LAND = 18, // change to LAND flight mode
|
||||
GRIPPER = 19, // Operate cargo grippers low=off, middle=neutral, high=on
|
||||
PARACHUTE_ENABLE = 21, // Parachute enable/disable
|
||||
|
@ -252,6 +252,7 @@ public:
|
|||
VFWD_THR_OVERRIDE = 176, // force enabled VTOL forward throttle method
|
||||
MOUNT_LRF_ENABLE = 177, // mount LRF enable/disable
|
||||
FLIGHTMODE_PAUSE = 178, // e.g. pause movement towards waypoint
|
||||
AUTOTUNE_TEST_GAINS = 180, // auto tune tuning switch to test or revert gains
|
||||
|
||||
|
||||
// inputs from 200 will eventually used to replace RCMAP
|
||||
|
|
Loading…
Reference in New Issue