mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
RC_Channel: comment some of our range conventions on RC channel options
This commit is contained in:
parent
47e4e9f7c9
commit
349c11d631
@ -182,6 +182,8 @@ public:
|
|||||||
Q_ASSIST = 82, // disable, enable and force Q assist
|
Q_ASSIST = 82, // disable, enable and force Q assist
|
||||||
ZIGZAG_Auto = 83, // zigzag auto switch
|
ZIGZAG_Auto = 83, // zigzag auto switch
|
||||||
AIRMODE = 84, // enable / disable airmode for copter
|
AIRMODE = 84, // enable / disable airmode for copter
|
||||||
|
// entries from 100 onwards are expected to be developer
|
||||||
|
// options used for testing
|
||||||
KILL_IMU1 = 100, // disable first IMU (for IMU failure testing)
|
KILL_IMU1 = 100, // disable first IMU (for IMU failure testing)
|
||||||
KILL_IMU2 = 101, // disable second IMU (for IMU failure testing)
|
KILL_IMU2 = 101, // disable second IMU (for IMU failure testing)
|
||||||
CAM_MODE_TOGGLE = 102, // Momentary switch to cycle camera modes
|
CAM_MODE_TOGGLE = 102, // Momentary switch to cycle camera modes
|
||||||
@ -191,7 +193,7 @@ public:
|
|||||||
// if you add something here, make sure to update the documentation of the parameter in RC_Channel.cpp!
|
// if you add something here, make sure to update the documentation of the parameter in RC_Channel.cpp!
|
||||||
// also, if you add an option >255, you will need to fix duplicate_options_exist
|
// also, if you add an option >255, you will need to fix duplicate_options_exist
|
||||||
|
|
||||||
// inputs eventually used to replace RCMAP
|
// inputs from 200 will eventually used to replace RCMAP
|
||||||
MAINSAIL = 207, // mainsail input
|
MAINSAIL = 207, // mainsail input
|
||||||
FLAP = 208, // flap input
|
FLAP = 208, // flap input
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user