mirror of https://github.com/ArduPilot/ardupilot
RC_Channel: Support for Standby functions
This commit is contained in:
parent
e8e969af62
commit
05f1161e63
|
@ -173,6 +173,7 @@ public:
|
|||
DRIFT = 73, // drift mode
|
||||
SAILBOAT_MOTOR_3POS = 74, // Sailboat motoring 3pos
|
||||
SURFACE_TRACKING = 75, // Surface tracking upwards or downwards
|
||||
STAND_BY = 76, // Standy signal magnitude
|
||||
KILL_IMU1 = 100, // disable first IMU (for IMU failure testing)
|
||||
KILL_IMU2 = 101, // disable second IMU (for IMU failure testing)
|
||||
// if you add something here, make sure to update the documentation of the parameter in RC_Channel.cpp!
|
||||
|
|
Loading…
Reference in New Issue