mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
RC_Channel: add accessor for channel number
some places want to be able to report this to the user
This commit is contained in:
parent
8f5861283b
commit
1871170f98
@ -26,6 +26,12 @@ public:
|
||||
RANGE = 1,
|
||||
};
|
||||
|
||||
// ch returns the radio channel be read, starting at 1. so
|
||||
// typically Roll=1, Pitch=2, throttle=3, yaw=4. If this returns
|
||||
// 0 then this is the dummy object which means that one of roll,
|
||||
// pitch, yaw or throttle has not been configured correctly.
|
||||
uint8_t ch() const { return ch_in + 1; }
|
||||
|
||||
// setup the control preferences
|
||||
void set_range(uint16_t high);
|
||||
uint16_t get_range() const { return high_in; }
|
||||
|
Loading…
Reference in New Issue
Block a user