Browse Source

ACMotors: remove unused get_num_motors function

Saves about 4 bytes of RAM
mission-4.1.18
Randy Mackay 12 years ago
parent
commit
bd07b1e57b
  1. 5
      libraries/AP_Motors/AP_MotorsHeli.h
  2. 5
      libraries/AP_Motors/AP_MotorsMatrix.h
  3. 5
      libraries/AP_Motors/AP_MotorsTri.h
  4. 5
      libraries/AP_Motors/AP_Motors_Class.h

5
libraries/AP_Motors/AP_MotorsHeli.h

@ -108,11 +108,6 @@ public: @@ -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();

5
libraries/AP_Motors/AP_MotorsMatrix.h

@ -42,11 +42,6 @@ public: @@ -42,11 +42,6 @@ public:
// 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;
};
// motor test
virtual void output_test();

5
libraries/AP_Motors/AP_MotorsTri.h

@ -33,11 +33,6 @@ public: @@ -33,11 +33,6 @@ public:
// 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
// motor test
virtual void output_test();

5
libraries/AP_Motors/AP_Motors_Class.h

@ -117,11 +117,6 @@ public: @@ -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() {
};

Loading…
Cancel
Save