From 3ae9b606ffe125b318ab6394dad973317dd3a957 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 2 Feb 2016 21:08:22 +0900 Subject: [PATCH] AP_Motors: remove unnecessary output_to_motors declaration This is declared down in the AP_MotorsMulticopter --- libraries/AP_Motors/AP_Motors_Class.h | 3 --- 1 file changed, 3 deletions(-) diff --git a/libraries/AP_Motors/AP_Motors_Class.h b/libraries/AP_Motors/AP_Motors_Class.h index 3fb3fe1fe4..9a480b7d9f 100644 --- a/libraries/AP_Motors/AP_Motors_Class.h +++ b/libraries/AP_Motors/AP_Motors_Class.h @@ -109,9 +109,6 @@ public: // output_min - sends minimum values out to the motors virtual void output_min() = 0; - // output_to_motors - sends minimum values out to the motors - virtual void output_to_motors() = 0; - // 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