mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-04 06:58:39 -04:00
RC_Channel: added get_type() method
This commit is contained in:
parent
eaeebeba53
commit
45e994c1fb
@ -97,7 +97,10 @@ public:
|
|||||||
void set_and_save_radio_trim(int16_t val) { radio_trim.set_and_save_ifchanged(val);}
|
void set_and_save_radio_trim(int16_t val) { radio_trim.set_and_save_ifchanged(val);}
|
||||||
|
|
||||||
bool min_max_configured() const;
|
bool min_max_configured() const;
|
||||||
|
|
||||||
|
// return the type of the channel (angle or range)
|
||||||
|
uint8_t get_type() const { return type_in; }
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
// pwm is stored here
|
// pwm is stored here
|
||||||
|
Loading…
Reference in New Issue
Block a user