mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 17:38:32 -04:00
RC_Channel: remove unused enumeration
This commit is contained in:
parent
833bc8f12a
commit
8808991638
@ -16,13 +16,6 @@ public:
|
|||||||
// Constructor
|
// Constructor
|
||||||
RC_Channel(void);
|
RC_Channel(void);
|
||||||
|
|
||||||
// used to get min/max/trim limit value based on _reverse
|
|
||||||
enum LimitValue {
|
|
||||||
RC_CHANNEL_LIMIT_TRIM,
|
|
||||||
RC_CHANNEL_LIMIT_MIN,
|
|
||||||
RC_CHANNEL_LIMIT_MAX
|
|
||||||
};
|
|
||||||
|
|
||||||
enum InputIgnore {
|
enum InputIgnore {
|
||||||
RC_IGNORE_RECEIVER = (1 << 0), // RC receiver modules
|
RC_IGNORE_RECEIVER = (1 << 0), // RC receiver modules
|
||||||
RC_IGNORE_OVERRIDES = (1 << 1), // MAVLink overrides
|
RC_IGNORE_OVERRIDES = (1 << 1), // MAVLink overrides
|
||||||
|
Loading…
Reference in New Issue
Block a user