mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
RC_Channel: privatise range accessors
This commit is contained in:
parent
f79c43eebd
commit
d41388f242
@ -56,8 +56,6 @@ public:
|
|||||||
bool within_min_dz() const;
|
bool within_min_dz() const;
|
||||||
|
|
||||||
uint8_t percent_input() const;
|
uint8_t percent_input() const;
|
||||||
int16_t pwm_to_range() const;
|
|
||||||
int16_t pwm_to_range_dz(uint16_t dead_zone) const;
|
|
||||||
|
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
@ -358,6 +356,9 @@ private:
|
|||||||
int16_t pwm_to_angle() const;
|
int16_t pwm_to_angle() const;
|
||||||
int16_t pwm_to_angle_dz(uint16_t dead_zone) const;
|
int16_t pwm_to_angle_dz(uint16_t dead_zone) const;
|
||||||
|
|
||||||
|
int16_t pwm_to_range() const;
|
||||||
|
int16_t pwm_to_range_dz(uint16_t dead_zone) const;
|
||||||
|
|
||||||
// Structure used to detect and debounce switch changes
|
// Structure used to detect and debounce switch changes
|
||||||
struct {
|
struct {
|
||||||
int8_t debounce_position = -1;
|
int8_t debounce_position = -1;
|
||||||
|
Loading…
Reference in New Issue
Block a user