mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: support MODE_PWM_BRUSHED16KHZ
This commit is contained in:
parent
b3286c3da0
commit
ce517384e1
|
@ -82,8 +82,8 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = {
|
|||
|
||||
// @Param: PWM_TYPE
|
||||
// @DisplayName: Output PWM type
|
||||
// @Description: This selects the output PWM type, allowing for normal PWM continuous output or OneShot125
|
||||
// @Values: 0:Normal,1:OneShot,2:OneShot125
|
||||
// @Description: This selects the output PWM type, allowing for normal PWM continuous output, OneShot or brushed motor output
|
||||
// @Values: 0:Normal,1:OneShot,2:OneShot125,3:Brushed16kHz
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("PWM_TYPE", 15, AP_MotorsMulticopter, _pwm_type, PWM_TYPE_NORMAL),
|
||||
|
||||
|
|
|
@ -118,6 +118,8 @@ void AP_Motors::rc_set_freq(uint32_t mask, uint16_t freq_hz)
|
|||
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_BRUSHED16kHz) {
|
||||
hal.rcout->set_output_mode(AP_HAL::RCOutput::MODE_PWM_BRUSHED16KHZ);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -134,7 +134,7 @@ 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 };
|
||||
enum pwm_type { PWM_TYPE_NORMAL=0, PWM_TYPE_ONESHOT=1, PWM_TYPE_ONESHOT125=2, PWM_TYPE_BRUSHED16kHz=3 };
|
||||
pwm_type get_pwm_type(void) const { return (pwm_type)_pwm_type.get(); }
|
||||
|
||||
protected:
|
||||
|
|
Loading…
Reference in New Issue