diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index b215d2e18f..5b8b471a22 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -116,13 +116,13 @@ RC_Channel::RC_Channel(void) void RC_Channel::set_range(uint16_t high) { - type_in = RC_CHANNEL_TYPE_RANGE; + type_in = ControlType::RANGE; high_in = high; } void RC_Channel::set_angle(uint16_t angle) { - type_in = RC_CHANNEL_TYPE_ANGLE; + type_in = ControlType::ANGLE; high_in = angle; } @@ -147,10 +147,10 @@ bool RC_Channel::update(void) return false; } - if (type_in == RC_CHANNEL_TYPE_RANGE) { + if (type_in == ControlType::RANGE) { control_in = pwm_to_range(); } else { - //RC_CHANNEL_TYPE_ANGLE + // ControlType::ANGLE control_in = pwm_to_angle(); } @@ -163,7 +163,7 @@ bool RC_Channel::update(void) */ int16_t RC_Channel::get_control_mid() const { - if (type_in == RC_CHANNEL_TYPE_RANGE) { + if (type_in == ControlType::RANGE) { int16_t r_in = (radio_min.get() + radio_max.get())/2; int16_t radio_trim_low = radio_min + dead_zone; @@ -248,7 +248,7 @@ int16_t RC_Channel::pwm_to_range() const int16_t RC_Channel::get_control_in_zero_dz(void) const { - if (type_in == RC_CHANNEL_TYPE_RANGE) { + if (type_in == ControlType::RANGE) { return pwm_to_range_dz(0); } return pwm_to_angle_dz(0); diff --git a/libraries/RC_Channel/RC_Channel.h b/libraries/RC_Channel/RC_Channel.h index d0a66d86ef..0c2df648aa 100644 --- a/libraries/RC_Channel/RC_Channel.h +++ b/libraries/RC_Channel/RC_Channel.h @@ -17,9 +17,9 @@ public: // Constructor RC_Channel(void); - enum ChannelType { - RC_CHANNEL_TYPE_ANGLE = 0, - RC_CHANNEL_TYPE_RANGE = 1, + enum class ControlType { + ANGLE = 0, + RANGE = 1, }; // setup the control preferences @@ -91,7 +91,7 @@ public: // check if any of the trim/min/max param are configured in storage, this would indicate that the user has done a calibration at somepoint bool configured_in_storage() { return radio_min.configured_in_storage() || radio_max.configured_in_storage() || radio_trim.configured_in_storage(); } - ChannelType get_type(void) const { return type_in; } + ControlType get_type(void) const { return type_in; } AP_Int16 option; // e.g. activate EPM gripper / enable fence @@ -337,7 +337,7 @@ private: AP_Int8 reversed; AP_Int16 dead_zone; - ChannelType type_in; + ControlType type_in; int16_t high_in; // the input channel this corresponds to