mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
RC_Channel: Added Quicktune
This commit is contained in:
parent
04b8d36984
commit
7dcad6c4f0
@ -260,6 +260,7 @@ public:
|
|||||||
FLIGHTMODE_PAUSE = 178, // e.g. pause movement towards waypoint
|
FLIGHTMODE_PAUSE = 178, // e.g. pause movement towards waypoint
|
||||||
ICE_START_STOP = 179, // AP_ICEngine start stop
|
ICE_START_STOP = 179, // AP_ICEngine start stop
|
||||||
AUTOTUNE_TEST_GAINS = 180, // auto tune tuning switch to test or revert gains
|
AUTOTUNE_TEST_GAINS = 180, // auto tune tuning switch to test or revert gains
|
||||||
|
QUICKTUNE = 181, //quicktune 3 position switch
|
||||||
|
|
||||||
|
|
||||||
// inputs from 200 will eventually used to replace RCMAP
|
// inputs from 200 will eventually used to replace RCMAP
|
||||||
|
Loading…
Reference in New Issue
Block a user