From 28f2f87b2611427b3ec6de12785358e429ad9c1b Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 31 May 2013 14:17:08 +0900 Subject: [PATCH] Copter Motors: minor formatting change --- libraries/AP_Motors/AP_Motors_Class.h | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/libraries/AP_Motors/AP_Motors_Class.h b/libraries/AP_Motors/AP_Motors_Class.h index 6790e4d2ee..aca193c410 100644 --- a/libraries/AP_Motors/AP_Motors_Class.h +++ b/libraries/AP_Motors/AP_Motors_Class.h @@ -81,7 +81,7 @@ public: virtual void set_frame_orientation( uint8_t new_orientation ) { _frame_orientation = new_orientation; }; // enable - starts allowing signals to be sent to motors - virtual void enable() {}; + virtual void enable() = 0; // arm, disarm or check status status of motors bool armed() { return _armed; }; @@ -100,8 +100,7 @@ public: }; // output_min - sends minimum values out to the motors - virtual void output_min() { - }; + virtual void output_min() = 0; // reached_limits - return whether we hit the limits of the motors uint8_t reached_limit( uint8_t which_limit = AP_MOTOR_ANY_LIMIT ) { @@ -109,8 +108,7 @@ public: } // motor test - virtual void output_test() { - }; + virtual void output_test() = 0; // throttle_pass_through - passes pilot's throttle input directly to all motors - dangerous but used for initialising ESCs virtual void throttle_pass_through();