mirror of https://github.com/ArduPilot/ardupilot
AR_Motors: make AP_Motors::PWMType enum class
Co-authored-by: muramura <ma2maru@gmail.com>
This commit is contained in:
parent
70a1bc7606
commit
70b23733ac
|
@ -33,7 +33,7 @@ const AP_Param::GroupInfo AP_MotorsUGV::var_info[] = {
|
||||||
// @Values: 0:Normal,1:OneShot,2:OneShot125,3:BrushedWithRelay,4:BrushedBiPolar,5:DShot150,6:DShot300,7:DShot600,8:DShot1200
|
// @Values: 0:Normal,1:OneShot,2:OneShot125,3:BrushedWithRelay,4:BrushedBiPolar,5:DShot150,6:DShot300,7:DShot600,8:DShot1200
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
// @RebootRequired: True
|
// @RebootRequired: True
|
||||||
AP_GROUPINFO("PWM_TYPE", 1, AP_MotorsUGV, _pwm_type, PWM_TYPE_NORMAL),
|
AP_GROUPINFO("PWM_TYPE", 1, AP_MotorsUGV, _pwm_type, PWMType::NORMAL),
|
||||||
|
|
||||||
// @Param: PWM_FREQ
|
// @Param: PWM_FREQ
|
||||||
// @DisplayName: Motor Output PWM freq for brushed motors
|
// @DisplayName: Motor Output PWM freq for brushed motors
|
||||||
|
@ -149,7 +149,7 @@ void AP_MotorsUGV::init(uint8_t frtype)
|
||||||
|
|
||||||
bool AP_MotorsUGV::get_legacy_relay_index(int8_t &index1, int8_t &index2, int8_t &index3, int8_t &index4) const
|
bool AP_MotorsUGV::get_legacy_relay_index(int8_t &index1, int8_t &index2, int8_t &index3, int8_t &index4) const
|
||||||
{
|
{
|
||||||
if (_pwm_type != PWM_TYPE_BRUSHED_WITH_RELAY) {
|
if (_pwm_type != PWMType::BRUSHED_WITH_RELAY) {
|
||||||
// Relays only used if PWM type is set to brushed with relay
|
// Relays only used if PWM type is set to brushed with relay
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
@ -177,7 +177,7 @@ bool AP_MotorsUGV::get_legacy_relay_index(int8_t &index1, int8_t &index2, int8_t
|
||||||
// setup output in case of main CPU failure
|
// setup output in case of main CPU failure
|
||||||
void AP_MotorsUGV::setup_safety_output()
|
void AP_MotorsUGV::setup_safety_output()
|
||||||
{
|
{
|
||||||
if (_pwm_type == PWM_TYPE_BRUSHED_WITH_RELAY) {
|
if (_pwm_type == PWMType::BRUSHED_WITH_RELAY) {
|
||||||
// set trim to min to set duty cycle range (0 - 100%) to servo range
|
// set trim to min to set duty cycle range (0 - 100%) to servo range
|
||||||
// ignore servo revese flag, it is used by the relay
|
// ignore servo revese flag, it is used by the relay
|
||||||
SRV_Channels::set_trim_to_min_for(SRV_Channel::k_throttle, true);
|
SRV_Channels::set_trim_to_min_for(SRV_Channel::k_throttle, true);
|
||||||
|
@ -529,7 +529,7 @@ bool AP_MotorsUGV::pre_arm_check(bool report) const
|
||||||
// Check relays are configured for brushed with relay outputs
|
// Check relays are configured for brushed with relay outputs
|
||||||
#if AP_RELAY_ENABLED
|
#if AP_RELAY_ENABLED
|
||||||
AP_Relay*relay = AP::relay();
|
AP_Relay*relay = AP::relay();
|
||||||
if ((_pwm_type == PWM_TYPE_BRUSHED_WITH_RELAY) && (relay != nullptr)) {
|
if ((_pwm_type == PWMType::BRUSHED_WITH_RELAY) && (relay != nullptr)) {
|
||||||
// If a output is configured its relay must be enabled
|
// If a output is configured its relay must be enabled
|
||||||
struct RelayTable {
|
struct RelayTable {
|
||||||
bool output_assigned;
|
bool output_assigned;
|
||||||
|
@ -581,27 +581,27 @@ void AP_MotorsUGV::setup_pwm_type()
|
||||||
}
|
}
|
||||||
|
|
||||||
switch (_pwm_type) {
|
switch (_pwm_type) {
|
||||||
case PWM_TYPE_ONESHOT:
|
case PWMType::ONESHOT:
|
||||||
hal.rcout->set_output_mode(_motor_mask, AP_HAL::RCOutput::MODE_PWM_ONESHOT);
|
hal.rcout->set_output_mode(_motor_mask, AP_HAL::RCOutput::MODE_PWM_ONESHOT);
|
||||||
break;
|
break;
|
||||||
case PWM_TYPE_ONESHOT125:
|
case PWMType::ONESHOT125:
|
||||||
hal.rcout->set_output_mode(_motor_mask, AP_HAL::RCOutput::MODE_PWM_ONESHOT125);
|
hal.rcout->set_output_mode(_motor_mask, AP_HAL::RCOutput::MODE_PWM_ONESHOT125);
|
||||||
break;
|
break;
|
||||||
case PWM_TYPE_BRUSHED_WITH_RELAY:
|
case PWMType::BRUSHED_WITH_RELAY:
|
||||||
case PWM_TYPE_BRUSHED_BIPOLAR:
|
case PWMType::BRUSHED_BIPOLAR:
|
||||||
hal.rcout->set_output_mode(_motor_mask, AP_HAL::RCOutput::MODE_PWM_BRUSHED);
|
hal.rcout->set_output_mode(_motor_mask, AP_HAL::RCOutput::MODE_PWM_BRUSHED);
|
||||||
hal.rcout->set_freq(_motor_mask, uint16_t(_pwm_freq * 1000));
|
hal.rcout->set_freq(_motor_mask, uint16_t(_pwm_freq * 1000));
|
||||||
break;
|
break;
|
||||||
case PWM_TYPE_DSHOT150:
|
case PWMType::DSHOT150:
|
||||||
hal.rcout->set_output_mode(_motor_mask, AP_HAL::RCOutput::MODE_PWM_DSHOT150);
|
hal.rcout->set_output_mode(_motor_mask, AP_HAL::RCOutput::MODE_PWM_DSHOT150);
|
||||||
break;
|
break;
|
||||||
case PWM_TYPE_DSHOT300:
|
case PWMType::DSHOT300:
|
||||||
hal.rcout->set_output_mode(_motor_mask, AP_HAL::RCOutput::MODE_PWM_DSHOT300);
|
hal.rcout->set_output_mode(_motor_mask, AP_HAL::RCOutput::MODE_PWM_DSHOT300);
|
||||||
break;
|
break;
|
||||||
case PWM_TYPE_DSHOT600:
|
case PWMType::DSHOT600:
|
||||||
hal.rcout->set_output_mode(_motor_mask, AP_HAL::RCOutput::MODE_PWM_DSHOT600);
|
hal.rcout->set_output_mode(_motor_mask, AP_HAL::RCOutput::MODE_PWM_DSHOT600);
|
||||||
break;
|
break;
|
||||||
case PWM_TYPE_DSHOT1200:
|
case PWMType::DSHOT1200:
|
||||||
hal.rcout->set_output_mode(_motor_mask, AP_HAL::RCOutput::MODE_PWM_DSHOT1200);
|
hal.rcout->set_output_mode(_motor_mask, AP_HAL::RCOutput::MODE_PWM_DSHOT1200);
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
|
@ -988,7 +988,7 @@ void AP_MotorsUGV::output_throttle(SRV_Channel::Aux_servo_function_t function, f
|
||||||
// set relay if necessary
|
// set relay if necessary
|
||||||
#if AP_RELAY_ENABLED
|
#if AP_RELAY_ENABLED
|
||||||
AP_Relay*relay = AP::relay();
|
AP_Relay*relay = AP::relay();
|
||||||
if ((_pwm_type == PWM_TYPE_BRUSHED_WITH_RELAY) && (relay != nullptr)) {
|
if ((_pwm_type == PWMType::BRUSHED_WITH_RELAY) && (relay != nullptr)) {
|
||||||
|
|
||||||
// find the output channel, if not found return
|
// find the output channel, if not found return
|
||||||
const SRV_Channel *out_chan = SRV_Channels::get_channel_for(function);
|
const SRV_Channel *out_chan = SRV_Channels::get_channel_for(function);
|
||||||
|
@ -1153,17 +1153,17 @@ bool AP_MotorsUGV::active() const
|
||||||
bool AP_MotorsUGV::is_digital_pwm_type() const
|
bool AP_MotorsUGV::is_digital_pwm_type() const
|
||||||
{
|
{
|
||||||
switch (_pwm_type) {
|
switch (_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_WITH_RELAY:
|
case PWMType::BRUSHED_WITH_RELAY:
|
||||||
case PWM_TYPE_BRUSHED_BIPOLAR:
|
case PWMType::BRUSHED_BIPOLAR:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
|
@ -131,16 +131,16 @@ public:
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
enum pwm_type {
|
enum PWMType {
|
||||||
PWM_TYPE_NORMAL = 0,
|
NORMAL = 0,
|
||||||
PWM_TYPE_ONESHOT = 1,
|
ONESHOT = 1,
|
||||||
PWM_TYPE_ONESHOT125 = 2,
|
ONESHOT125 = 2,
|
||||||
PWM_TYPE_BRUSHED_WITH_RELAY = 3,
|
BRUSHED_WITH_RELAY = 3,
|
||||||
PWM_TYPE_BRUSHED_BIPOLAR = 4,
|
BRUSHED_BIPOLAR = 4,
|
||||||
PWM_TYPE_DSHOT150 = 5,
|
DSHOT150 = 5,
|
||||||
PWM_TYPE_DSHOT300 = 6,
|
DSHOT300 = 6,
|
||||||
PWM_TYPE_DSHOT600 = 7,
|
DSHOT600 = 7,
|
||||||
PWM_TYPE_DSHOT1200 = 8
|
DSHOT1200 = 8
|
||||||
};
|
};
|
||||||
|
|
||||||
// sanity check parameters
|
// sanity check parameters
|
||||||
|
|
Loading…
Reference in New Issue