diff --git a/libraries/AP_Motors/AP_MotorsTri.cpp b/libraries/AP_Motors/AP_MotorsTri.cpp index 3cab6084b0..525af754c4 100644 --- a/libraries/AP_Motors/AP_MotorsTri.cpp +++ b/libraries/AP_Motors/AP_MotorsTri.cpp @@ -252,13 +252,6 @@ void AP_MotorsTri::output_armed_stabilizing() hal.rcout->push(); } -// output_disarmed - sends commands to the motors -void AP_MotorsTri::output_disarmed() -{ - // Send minimum values to all motors - output_min(); -} - // output_test - spin a motor at the pwm value specified // motor_seq is the motor's sequence number from 1 to the number of motors on the frame // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000 diff --git a/libraries/AP_Motors/AP_MotorsTri.h b/libraries/AP_Motors/AP_MotorsTri.h index 58ce6e4583..5cf293463a 100644 --- a/libraries/AP_Motors/AP_MotorsTri.h +++ b/libraries/AP_Motors/AP_MotorsTri.h @@ -50,7 +50,6 @@ public: protected: // output - sends commands to the motors void output_armed_stabilizing(); - void output_disarmed(); // calc_yaw_radio_output - calculate final radio output for yaw channel int16_t calc_yaw_radio_output(); // calculate radio output for yaw servo, typically in range of 1100-1900