diff --git a/libraries/AP_Motors/AP_Motors6DOF.cpp b/libraries/AP_Motors/AP_Motors6DOF.cpp index 239544f9685bd6..1cadb4cc7615f7 100644 --- a/libraries/AP_Motors/AP_Motors6DOF.cpp +++ b/libraries/AP_Motors/AP_Motors6DOF.cpp @@ -20,6 +20,7 @@ #include #include #include "AP_Motors6DOF.h" +#include extern const AP_HAL::HAL& hal; @@ -237,6 +238,17 @@ int16_t AP_Motors6DOF::calc_thrust_to_pwm(float thrust_in) const return 1500 + thrust_in * (thrust_in > 0 ? range_up : range_down); } +void AP_Motors6DOF::rc_write(uint8_t chan, uint16_t pwm) +{ + SRV_Channel::Aux_servo_function_t function = SRV_Channels::get_motor_function(chan); + if ((1U<