diff --git a/libraries/AP_Motors/AP_MotorsHeli.h b/libraries/AP_Motors/AP_MotorsHeli.h index f246c5cfc1..fcb2dd765c 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.h +++ b/libraries/AP_Motors/AP_MotorsHeli.h @@ -108,11 +108,6 @@ public: // enable - starts allowing signals to be sent to motors void enable(); - // get basic information about the platform - uint8_t get_num_motors() { - return 5; - }; - // motor test void output_test(); diff --git a/libraries/AP_Motors/AP_MotorsMatrix.h b/libraries/AP_Motors/AP_MotorsMatrix.h index 6499e60c46..20996940bf 100644 --- a/libraries/AP_Motors/AP_MotorsMatrix.h +++ b/libraries/AP_Motors/AP_MotorsMatrix.h @@ -34,18 +34,13 @@ public: // set update rate to motors - a value in hertz // you must have setup_motors before calling this - virtual void set_update_rate( uint16_t speed_hz ); + virtual void set_update_rate( uint16_t speed_hz ); // set frame orientation (normally + or X) - virtual void set_frame_orientation( uint8_t new_orientation ); + virtual void set_frame_orientation( uint8_t new_orientation ); // enable - starts allowing signals to be sent to motors - virtual void enable(); - - // get basic information about the platform - virtual uint8_t get_num_motors() { - return _num_motors; - }; + virtual void enable(); // motor test virtual void output_test(); diff --git a/libraries/AP_Motors/AP_MotorsTri.h b/libraries/AP_Motors/AP_MotorsTri.h index 4d3b05ef34..92311a9fc2 100644 --- a/libraries/AP_Motors/AP_MotorsTri.h +++ b/libraries/AP_Motors/AP_MotorsTri.h @@ -25,18 +25,13 @@ public: }; // init - virtual void Init(); + virtual void Init(); // set update rate to motors - a value in hertz - void set_update_rate( uint16_t speed_hz ); + void set_update_rate( uint16_t speed_hz ); // enable - starts allowing signals to be sent to motors - virtual void enable(); - - // get basic information about the platform - virtual uint8_t get_num_motors() { - return 4; - }; // 3 motors + 1 tail servo + virtual void enable(); // motor test virtual void output_test(); diff --git a/libraries/AP_Motors/AP_Motors_Class.h b/libraries/AP_Motors/AP_Motors_Class.h index f7495f1e4f..98881fc8b9 100644 --- a/libraries/AP_Motors/AP_Motors_Class.h +++ b/libraries/AP_Motors/AP_Motors_Class.h @@ -117,11 +117,6 @@ public: return _reached_limit & which_limit; } - // get basic information about the platform - virtual uint8_t get_num_motors() { - return 0; - }; - // motor test virtual void output_test() { };