From abd0831239e7831e62a5ca07fd24ecd5d0258607 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 16 Jun 2017 21:23:37 +1000 Subject: [PATCH] AP_Motors: changed BRUSHED16kHz to BRUSHED --- libraries/AP_Motors/AP_MotorsMulticopter.cpp | 2 +- libraries/AP_Motors/AP_Motors_Class.cpp | 4 ++-- libraries/AP_Motors/AP_Motors_Class.h | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.cpp b/libraries/AP_Motors/AP_MotorsMulticopter.cpp index 4fea1d7d96..22ec517523 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.cpp +++ b/libraries/AP_Motors/AP_MotorsMulticopter.cpp @@ -83,7 +83,7 @@ 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, OneShot or brushed motor output - // @Values: 0:Normal,1:OneShot,2:OneShot125,3:Brushed16kHz + // @Values: 0:Normal,1:OneShot,2:OneShot125,3:Brushed // @User: Advanced // @RebootRequired: True AP_GROUPINFO("PWM_TYPE", 15, AP_MotorsMulticopter, _pwm_type, PWM_TYPE_NORMAL), diff --git a/libraries/AP_Motors/AP_Motors_Class.cpp b/libraries/AP_Motors/AP_Motors_Class.cpp index 69e8f53ad0..ad1a283332 100644 --- a/libraries/AP_Motors/AP_Motors_Class.cpp +++ b/libraries/AP_Motors/AP_Motors_Class.cpp @@ -120,8 +120,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); + } else if (_pwm_type == PWM_TYPE_BRUSHED) { + hal.rcout->set_output_mode(AP_HAL::RCOutput::MODE_PWM_BRUSHED); } } diff --git a/libraries/AP_Motors/AP_Motors_Class.h b/libraries/AP_Motors/AP_Motors_Class.h index df1269937e..17069b1775 100644 --- a/libraries/AP_Motors/AP_Motors_Class.h +++ b/libraries/AP_Motors/AP_Motors_Class.h @@ -164,7 +164,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, PWM_TYPE_BRUSHED16kHz=3 }; + enum pwm_type { PWM_TYPE_NORMAL=0, PWM_TYPE_ONESHOT=1, PWM_TYPE_ONESHOT125=2, PWM_TYPE_BRUSHED=3 }; pwm_type get_pwm_type(void) const { return (pwm_type)_pwm_type.get(); } protected: