mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
ACMotors: remove unused get_num_motors function
Saves about 4 bytes of RAM
This commit is contained in:
parent
5bb0582854
commit
bd07b1e57b
@ -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();
|
||||
|
||||
|
@ -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();
|
||||
|
@ -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();
|
||||
|
@ -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…
Reference in New Issue
Block a user