AP_Motors: setup for DShot output modes

This commit is contained in:
Andrew Tridgell 2018-03-14 17:04:20 +11:00
parent e7dc304f4e
commit 2c84d77306
2 changed files with 36 additions and 9 deletions

View File

@ -107,16 +107,36 @@ void AP_Motors::rc_set_freq(uint32_t mask, uint16_t freq_hz)
if (freq_hz > 50) {
_motor_fast_mask |= mask;
}
mask = rc_map_mask(mask);
hal.rcout->set_freq(mask, freq_hz);
if ((_pwm_type == PWM_TYPE_ONESHOT ||
_pwm_type == PWM_TYPE_ONESHOT125) &&
freq_hz > 50 &&
mask != 0) {
// tell HAL to do immediate output
hal.rcout->set_output_mode(AP_HAL::RCOutput::MODE_PWM_ONESHOT);
} else if (_pwm_type == PWM_TYPE_BRUSHED) {
hal.rcout->set_output_mode(AP_HAL::RCOutput::MODE_PWM_BRUSHED);
switch (pwm_type(_pwm_type.get())) {
case PWM_TYPE_ONESHOT:
case PWM_TYPE_ONESHOT125:
if (freq_hz > 50 && mask != 0) {
// tell HAL to do immediate output
hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_ONESHOT);
}
break;
case PWM_TYPE_BRUSHED:
hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_BRUSHED);
break;
case PWM_TYPE_DSHOT150:
hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_DSHOT150);
break;
case PWM_TYPE_DSHOT300:
hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_DSHOT300);
break;
case PWM_TYPE_DSHOT600:
hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_DSHOT600);
break;
case PWM_TYPE_DSHOT1200:
hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_DSHOT1200);
break;
default:
hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_NORMAL);
break;
}
}

View File

@ -148,7 +148,14 @@ public:
// set loop rate. Used to support loop rate as a parameter
void set_loop_rate(uint16_t loop_rate) { _loop_rate = loop_rate; }
enum pwm_type { PWM_TYPE_NORMAL=0, PWM_TYPE_ONESHOT=1, PWM_TYPE_ONESHOT125=2, PWM_TYPE_BRUSHED=3 };
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 get_pwm_type(void) const { return (pwm_type)_pwm_type.get(); }
protected: