AP_Motors: make AP_Motors::PWMType enum class

Co-authored-by: muramura <ma2maru@gmail.com>
This commit is contained in:
Peter Barker 2024-07-26 11:06:14 +10:00 committed by Peter Barker
parent a211b66472
commit 70a1bc7606
3 changed files with 46 additions and 46 deletions

View File

@ -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 // @Values: 0:Normal,1:OneShot,2:OneShot125,3:Brushed,4:DShot150,5:DShot300,6:DShot600,7:DShot1200,8:PWMRange,9:PWMAngle
// @User: Advanced // @User: Advanced
// @RebootRequired: True // @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 // @Param: PWM_MIN
// @DisplayName: PWM output minimum // @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 // 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 // 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_min.set_and_default(1000);
_pwm_max.set_and_default(2000); _pwm_max.set_and_default(2000);
} }

View File

@ -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_freq(mask, freq_hz);
hal.rcout->set_dshot_esc_type(SRV_Channels::get_dshot_esc_type()); 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) { switch (type) {
case PWM_TYPE_ONESHOT: case PWMType::ONESHOT:
if (freq_hz > 50 && mask != 0) { if (freq_hz > 50 && mask != 0) {
hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_ONESHOT); hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_ONESHOT);
} }
break; break;
case PWM_TYPE_ONESHOT125: case PWMType::ONESHOT125:
if (freq_hz > 50 && mask != 0) { if (freq_hz > 50 && mask != 0) {
hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_ONESHOT125); hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_ONESHOT125);
} }
break; break;
case PWM_TYPE_BRUSHED: case PWMType::BRUSHED:
hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_BRUSHED); hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_BRUSHED);
break; break;
case PWM_TYPE_DSHOT150: case PWMType::DSHOT150:
hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_DSHOT150); hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_DSHOT150);
break; break;
case PWM_TYPE_DSHOT300: case PWMType::DSHOT300:
hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_DSHOT300); hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_DSHOT300);
break; break;
case PWM_TYPE_DSHOT600: case PWMType::DSHOT600:
hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_DSHOT600); hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_DSHOT600);
break; break;
case PWM_TYPE_DSHOT1200: case PWMType::DSHOT1200:
hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_DSHOT1200); hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_DSHOT1200);
break; break;
case PWM_TYPE_PWM_RANGE: case PWMType::PWM_RANGE:
case PWM_TYPE_PWM_ANGLE: case PWMType::PWM_ANGLE:
/* /*
this is a motor output type for multirotors which honours this is a motor output type for multirotors which honours
the SERVOn_MIN/MAX (and TRIM for angle) values per channel 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. 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; _motor_pwm_scaled.offset = 1000.0;
} else { } else {
// PWM_TYPE_PWM_ANGLE // PWMType::PWM_ANGLE
_motor_pwm_scaled.offset = 1500.0; _motor_pwm_scaled.offset = 1500.0;
} }
_motor_pwm_scaled.mask |= motor_mask; _motor_pwm_scaled.mask |= motor_mask;
for (uint8_t i=0; i<16; i++) { for (uint8_t i=0; i<16; i++) {
if ((1U<<i) & motor_mask) { if ((1U<<i) & motor_mask) {
if (type == PWM_TYPE_PWM_RANGE) { if (type == PWMType::PWM_RANGE) {
SRV_Channels::set_range(SRV_Channels::get_motor_function(i), 1000); SRV_Channels::set_range(SRV_Channels::get_motor_function(i), 1000);
} else { } else {
// PWM_TYPE_PWM_ANGLE // PWMType::PWM_ANGLE
SRV_Channels::set_angle(SRV_Channels::get_motor_function(i), 500); SRV_Channels::set_angle(SRV_Channels::get_motor_function(i), 500);
} }
} }
@ -251,19 +251,19 @@ void AP_Motors::set_external_limits(bool roll, bool pitch, bool yaw, bool thrott
// returns true if the configured PWM type is digital and should have fixed endpoints // returns true if the configured PWM type is digital and should have fixed endpoints
bool AP_Motors::is_digital_pwm_type() const bool AP_Motors::is_digital_pwm_type() const
{ {
switch (_pwm_type) { switch ((PWMType)_pwm_type) {
case PWM_TYPE_DSHOT150: case PWMType::DSHOT150:
case PWM_TYPE_DSHOT300: case PWMType::DSHOT300:
case PWM_TYPE_DSHOT600: case PWMType::DSHOT600:
case PWM_TYPE_DSHOT1200: case PWMType::DSHOT1200:
return true; return true;
case PWM_TYPE_NORMAL: case PWMType::NORMAL:
case PWM_TYPE_ONESHOT: case PWMType::ONESHOT:
case PWM_TYPE_ONESHOT125: case PWMType::ONESHOT125:
case PWM_TYPE_BRUSHED: case PWMType::BRUSHED:
case PWM_TYPE_PWM_RANGE: case PWMType::PWM_RANGE:
case PWM_TYPE_PWM_ANGLE: case PWMType::PWM_ANGLE:
break; break;
} }
return false; return false;
} }

View File

@ -262,10 +262,10 @@ public:
bool is_digital_pwm_type() const; bool is_digital_pwm_type() const;
// returns true is pwm type is brushed // returns true is pwm type is brushed
bool is_brushed_pwm_type() const { return _pwm_type == PWM_TYPE_BRUSHED; } bool is_brushed_pwm_type() const { return _pwm_type == PWMType::BRUSHED; }
// returns true is pwm type is normal // returns true is pwm type is normal
bool is_normal_pwm_type() const { return (_pwm_type == PWM_TYPE_NORMAL) || (_pwm_type == PWM_TYPE_PWM_RANGE) || (_pwm_type == PWM_TYPE_PWM_ANGLE); } bool is_normal_pwm_type() const { return (_pwm_type == PWMType::NORMAL) || (_pwm_type == PWMType::PWM_RANGE) || (_pwm_type == PWMType::PWM_ANGLE); }
MAV_TYPE get_frame_mav_type() const { return _mav_type; } MAV_TYPE get_frame_mav_type() const { return _mav_type; }
@ -333,7 +333,7 @@ protected:
// mask of what channels need fast output // mask of what channels need fast output
uint32_t _motor_fast_mask; uint32_t _motor_fast_mask;
// Used with PWM_TYPE_PWM_RANGE and PWM_TYPE_PWM_ANGLE // Used with PWMType::PWM_RANGE and PWMType::PWM_ANGLE
struct { struct {
// Mask of motors using scaled output // Mask of motors using scaled output
uint32_t mask; uint32_t mask;
@ -349,7 +349,20 @@ protected:
float _throttle_radio_passthrough; // throttle/collective input from pilot in 0 ~ 1 range. used for setup and providing servo feedback while landed float _throttle_radio_passthrough; // throttle/collective input from pilot in 0 ~ 1 range. used for setup and providing servo feedback while landed
float _yaw_radio_passthrough; // yaw input from pilot in -1 ~ +1 range. used for setup and providing servo feedback while landed float _yaw_radio_passthrough; // yaw input from pilot in -1 ~ +1 range. used for setup and providing servo feedback while landed
AP_Int8 _pwm_type; // PWM output type enum class PWMType : uint8_t {
NORMAL = 0,
ONESHOT = 1,
ONESHOT125 = 2,
BRUSHED = 3,
DSHOT150 = 4,
DSHOT300 = 5,
DSHOT600 = 6,
DSHOT1200 = 7,
PWM_RANGE = 8,
PWM_ANGLE = 9,
};
AP_Enum<PWMType> _pwm_type; // PWM output type
// motor failure handling // motor failure handling
bool _thrust_boost; // true if thrust boost is enabled to handle motor failure 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; 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 // return string corresponding to frame_class
virtual const char* _get_frame_string() const = 0; virtual const char* _get_frame_string() const = 0;