diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.cpp b/libraries/AP_Motors/AP_MotorsMulticopter.cpp index 11630bb775..abec6ab26e 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.cpp +++ b/libraries/AP_Motors/AP_MotorsMulticopter.cpp @@ -90,7 +90,7 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = { // @Values: 0:Normal,1:OneShot,2:OneShot125,3:Brushed,4:DShot150,5:DShot300,6:DShot600,7:DShot1200,8:PWMRange,9:PWMAngle // @User: Advanced // @RebootRequired: True - AP_GROUPINFO("PWM_TYPE", 15, AP_MotorsMulticopter, _pwm_type, PWM_TYPE_NORMAL), + AP_GROUPINFO("PWM_TYPE", 15, AP_MotorsMulticopter, _pwm_type, float(PWMType::NORMAL)), // @Param: PWM_MIN // @DisplayName: PWM output minimum @@ -474,7 +474,7 @@ void AP_MotorsMulticopter::update_throttle_range() { // if all outputs are digital adjust the range. We also do this for type PWM_RANGE, as those use the // scaled output, which is then mapped to PWM via the SRV_Channel library - if (SRV_Channels::have_digital_outputs(get_motor_mask()) || (_pwm_type == PWM_TYPE_PWM_RANGE) || (_pwm_type == PWM_TYPE_PWM_ANGLE)) { + if (SRV_Channels::have_digital_outputs(get_motor_mask()) || (_pwm_type == PWMType::PWM_RANGE) || (_pwm_type == PWMType::PWM_ANGLE)) { _pwm_min.set_and_default(1000); _pwm_max.set_and_default(2000); } diff --git a/libraries/AP_Motors/AP_Motors_Class.cpp b/libraries/AP_Motors/AP_Motors_Class.cpp index 9995dca6b7..42d7deebda 100644 --- a/libraries/AP_Motors/AP_Motors_Class.cpp +++ b/libraries/AP_Motors/AP_Motors_Class.cpp @@ -135,35 +135,35 @@ void AP_Motors::rc_set_freq(uint32_t motor_mask, uint16_t freq_hz) hal.rcout->set_freq(mask, freq_hz); hal.rcout->set_dshot_esc_type(SRV_Channels::get_dshot_esc_type()); - const pwm_type type = (pwm_type)_pwm_type.get(); + const PWMType type = _pwm_type; switch (type) { - case PWM_TYPE_ONESHOT: + case PWMType::ONESHOT: if (freq_hz > 50 && mask != 0) { hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_ONESHOT); } break; - case PWM_TYPE_ONESHOT125: + case PWMType::ONESHOT125: if (freq_hz > 50 && mask != 0) { hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_ONESHOT125); } break; - case PWM_TYPE_BRUSHED: + case PWMType::BRUSHED: hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_BRUSHED); break; - case PWM_TYPE_DSHOT150: + case PWMType::DSHOT150: hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_DSHOT150); break; - case PWM_TYPE_DSHOT300: + case PWMType::DSHOT300: hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_DSHOT300); break; - case PWM_TYPE_DSHOT600: + case PWMType::DSHOT600: hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_DSHOT600); break; - case PWM_TYPE_DSHOT1200: + case PWMType::DSHOT1200: hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_DSHOT1200); break; - case PWM_TYPE_PWM_RANGE: - case PWM_TYPE_PWM_ANGLE: + case PWMType::PWM_RANGE: + case PWMType::PWM_ANGLE: /* this is a motor output type for multirotors which honours the SERVOn_MIN/MAX (and TRIM for angle) values per channel @@ -173,20 +173,20 @@ void AP_Motors::rc_set_freq(uint32_t motor_mask, uint16_t freq_hz) Angle type offsets by 1500 to get -500 to 500. */ - if (type == PWM_TYPE_PWM_RANGE) { + if (type == PWMType::PWM_RANGE) { _motor_pwm_scaled.offset = 1000.0; } else { - // PWM_TYPE_PWM_ANGLE + // PWMType::PWM_ANGLE _motor_pwm_scaled.offset = 1500.0; } _motor_pwm_scaled.mask |= motor_mask; for (uint8_t i=0; i<16; i++) { if ((1U< _pwm_type; // PWM output type // motor failure handling bool _thrust_boost; // true if thrust boost is enabled to handle motor failure @@ -361,19 +374,6 @@ protected: MAV_TYPE _mav_type; // MAV_TYPE_GENERIC = 0; - enum pwm_type { - PWM_TYPE_NORMAL = 0, - PWM_TYPE_ONESHOT = 1, - PWM_TYPE_ONESHOT125 = 2, - PWM_TYPE_BRUSHED = 3, - PWM_TYPE_DSHOT150 = 4, - PWM_TYPE_DSHOT300 = 5, - PWM_TYPE_DSHOT600 = 6, - PWM_TYPE_DSHOT1200 = 7, - PWM_TYPE_PWM_RANGE = 8, - PWM_TYPE_PWM_ANGLE = 9 - }; - // return string corresponding to frame_class virtual const char* _get_frame_string() const = 0;