diff --git a/libraries/AP_Motors/AP_MotorsCoax.cpp b/libraries/AP_Motors/AP_MotorsCoax.cpp index f2595a9279..4207bd26d5 100644 --- a/libraries/AP_Motors/AP_MotorsCoax.cpp +++ b/libraries/AP_Motors/AP_MotorsCoax.cpp @@ -88,23 +88,23 @@ void AP_MotorsCoax::set_update_rate( uint16_t speed_hz ) uint32_t mask2 = 1U << AP_MOTORS_MOT_3 | 1U << AP_MOTORS_MOT_4 ; - hal.rcout->set_freq(mask2, _speed_hz); + rc_set_freq(mask2, _speed_hz); // set update rate for the two servos uint32_t mask = 1U << AP_MOTORS_MOT_1 | 1U << AP_MOTORS_MOT_2 ; - hal.rcout->set_freq(mask, _servo_speed); + rc_set_freq(mask, _servo_speed); } // enable - starts allowing signals to be sent to motors void AP_MotorsCoax::enable() { // enable output channels - hal.rcout->enable_ch(AP_MOTORS_MOT_1); - hal.rcout->enable_ch(AP_MOTORS_MOT_2); - hal.rcout->enable_ch(AP_MOTORS_MOT_3); - hal.rcout->enable_ch(AP_MOTORS_MOT_4); + rc_enable_ch(AP_MOTORS_MOT_1); + rc_enable_ch(AP_MOTORS_MOT_2); + rc_enable_ch(AP_MOTORS_MOT_3); + rc_enable_ch(AP_MOTORS_MOT_4); } // output_min - sends minimum values out to the motor and trim values to the servos diff --git a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp index ab0bfed3c1..27451eb9bd 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp @@ -131,19 +131,19 @@ void AP_MotorsHeli_Single::set_update_rate( uint16_t speed_hz ) 1U << AP_MOTORS_MOT_2 | 1U << AP_MOTORS_MOT_3 | 1U << AP_MOTORS_MOT_4; - hal.rcout->set_freq(mask, _speed_hz); + rc_set_freq(mask, _speed_hz); } // enable - starts allowing signals to be sent to motors and servos void AP_MotorsHeli_Single::enable() { // enable output channels - hal.rcout->enable_ch(AP_MOTORS_MOT_1); // swash servo 1 - hal.rcout->enable_ch(AP_MOTORS_MOT_2); // swash servo 2 - hal.rcout->enable_ch(AP_MOTORS_MOT_3); // swash servo 3 - hal.rcout->enable_ch(AP_MOTORS_MOT_4); // yaw - hal.rcout->enable_ch(AP_MOTORS_HELI_SINGLE_AUX); // output for gyro gain or direct drive variable pitch tail motor - hal.rcout->enable_ch(AP_MOTORS_HELI_SINGLE_RSC); // output for main rotor esc + rc_enable_ch(AP_MOTORS_MOT_1); // swash servo 1 + rc_enable_ch(AP_MOTORS_MOT_2); // swash servo 2 + rc_enable_ch(AP_MOTORS_MOT_3); // swash servo 3 + rc_enable_ch(AP_MOTORS_MOT_4); // yaw + rc_enable_ch(AP_MOTORS_HELI_SINGLE_AUX); // output for gyro gain or direct drive variable pitch tail motor + rc_enable_ch(AP_MOTORS_HELI_SINGLE_RSC); // output for main rotor esc } // init_outputs - initialise Servo/PWM ranges and endpoints diff --git a/libraries/AP_Motors/AP_MotorsMatrix.cpp b/libraries/AP_Motors/AP_MotorsMatrix.cpp index b03cb512ff..dd15bc97dc 100644 --- a/libraries/AP_Motors/AP_MotorsMatrix.cpp +++ b/libraries/AP_Motors/AP_MotorsMatrix.cpp @@ -49,7 +49,7 @@ void AP_MotorsMatrix::set_update_rate( uint16_t speed_hz ) mask |= 1U << i; } } - hal.rcout->set_freq( mask, _speed_hz ); + rc_set_freq( mask, _speed_hz ); } // set frame orientation (normally + or X) @@ -78,7 +78,7 @@ void AP_MotorsMatrix::enable() // enable output channels for( i=0; ienable_ch(i); + rc_enable_ch(i); } } } diff --git a/libraries/AP_Motors/AP_MotorsSingle.cpp b/libraries/AP_Motors/AP_MotorsSingle.cpp index 8705088ba9..a1a21b2f62 100644 --- a/libraries/AP_Motors/AP_MotorsSingle.cpp +++ b/libraries/AP_Motors/AP_MotorsSingle.cpp @@ -96,20 +96,20 @@ void AP_MotorsSingle::set_update_rate( uint16_t speed_hz ) 1U << AP_MOTORS_MOT_2 | 1U << AP_MOTORS_MOT_3 | 1U << AP_MOTORS_MOT_4 ; - hal.rcout->set_freq(mask, _servo_speed); + rc_set_freq(mask, _servo_speed); uint32_t mask2 = 1U << AP_MOTORS_MOT_7; - hal.rcout->set_freq(mask2, _speed_hz); + rc_set_freq(mask2, _speed_hz); } // enable - starts allowing signals to be sent to motors void AP_MotorsSingle::enable() { // enable output channels - hal.rcout->enable_ch(AP_MOTORS_MOT_1); - hal.rcout->enable_ch(AP_MOTORS_MOT_2); - hal.rcout->enable_ch(AP_MOTORS_MOT_3); - hal.rcout->enable_ch(AP_MOTORS_MOT_4); - hal.rcout->enable_ch(AP_MOTORS_MOT_7); + rc_enable_ch(AP_MOTORS_MOT_1); + rc_enable_ch(AP_MOTORS_MOT_2); + rc_enable_ch(AP_MOTORS_MOT_3); + rc_enable_ch(AP_MOTORS_MOT_4); + rc_enable_ch(AP_MOTORS_MOT_7); } // output_min - sends minimum values out to the motor and trim values to the servos diff --git a/libraries/AP_Motors/AP_MotorsTri.cpp b/libraries/AP_Motors/AP_MotorsTri.cpp index 8edec89246..ef169a5d46 100644 --- a/libraries/AP_Motors/AP_MotorsTri.cpp +++ b/libraries/AP_Motors/AP_MotorsTri.cpp @@ -97,17 +97,17 @@ void AP_MotorsTri::set_update_rate( uint16_t speed_hz ) 1U << AP_MOTORS_MOT_1 | 1U << AP_MOTORS_MOT_2 | 1U << AP_MOTORS_MOT_4; - hal.rcout->set_freq(mask, _speed_hz); + rc_set_freq(mask, _speed_hz); } // enable - starts allowing signals to be sent to motors void AP_MotorsTri::enable() { // enable output channels - hal.rcout->enable_ch(AP_MOTORS_MOT_1); - hal.rcout->enable_ch(AP_MOTORS_MOT_2); - hal.rcout->enable_ch(AP_MOTORS_MOT_4); - hal.rcout->enable_ch(AP_MOTORS_CH_TRI_YAW); + rc_enable_ch(AP_MOTORS_MOT_1); + rc_enable_ch(AP_MOTORS_MOT_2); + rc_enable_ch(AP_MOTORS_MOT_4); + rc_enable_ch(AP_MOTORS_CH_TRI_YAW); } // output_min - sends minimum values out to the motors diff --git a/libraries/AP_Motors/AP_Motors_Class.cpp b/libraries/AP_Motors/AP_Motors_Class.cpp index d2fbd87ac3..e65e186ef5 100644 --- a/libraries/AP_Motors/AP_Motors_Class.cpp +++ b/libraries/AP_Motors/AP_Motors_Class.cpp @@ -76,3 +76,32 @@ void AP_Motors::rc_write(uint8_t chan, uint16_t pwm) } hal.rcout->write(chan, pwm); } + +/* + set frequency of a set of channels + */ +void AP_Motors::rc_set_freq(uint32_t mask, uint16_t freq_hz) +{ + uint32_t mask2 = 0; + for (uint8_t i=0; i<32; i++) { + uint32_t bit = 1UL<set_freq(mask2, freq_hz); +} + +void AP_Motors::rc_enable_ch(uint8_t chan) +{ + if (_motor_map_mask & (1U<enable_ch(chan); +} diff --git a/libraries/AP_Motors/AP_Motors_Class.h b/libraries/AP_Motors/AP_Motors_Class.h index ad1094c0ac..fff392a597 100644 --- a/libraries/AP_Motors/AP_Motors_Class.h +++ b/libraries/AP_Motors/AP_Motors_Class.h @@ -130,6 +130,8 @@ protected: virtual void output_armed_zero_throttle() { output_min(); } virtual void output_disarmed()=0; virtual void rc_write(uint8_t chan, uint16_t pwm); + virtual void rc_set_freq(uint32_t mask, uint16_t freq_hz); + virtual void rc_enable_ch(uint8_t chan); // update the throttle input filter virtual void update_throttle_filter() = 0;