mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
ACMotors: make a few more functions non-virtual
Saves at least 22 bytes of RAM
This commit is contained in:
parent
ad00e0ee1e
commit
cd5795a4ac
@ -62,7 +62,7 @@ public:
|
||||
virtual void Init();
|
||||
|
||||
// set mapping from motor number to RC channel
|
||||
virtual void set_motor_to_channel_map( uint8_t mot_1, uint8_t mot_2, uint8_t mot_3, uint8_t mot_4, uint8_t mot_5, uint8_t mot_6, uint8_t mot_7, uint8_t mot_8 ) {
|
||||
void set_motor_to_channel_map( uint8_t mot_1, uint8_t mot_2, uint8_t mot_3, uint8_t mot_4, uint8_t mot_5, uint8_t mot_6, uint8_t mot_7, uint8_t mot_8 ) {
|
||||
_motor_to_channel_map[AP_MOTORS_MOT_1] = mot_1;
|
||||
_motor_to_channel_map[AP_MOTORS_MOT_2] = mot_2;
|
||||
_motor_to_channel_map[AP_MOTORS_MOT_3] = mot_3;
|
||||
@ -74,37 +74,24 @@ public:
|
||||
}
|
||||
|
||||
// set update rate to motors - a value in hertz
|
||||
virtual void set_update_rate( uint16_t speed_hz ) {
|
||||
_speed_hz = speed_hz;
|
||||
};
|
||||
virtual void set_update_rate( uint16_t speed_hz ) { _speed_hz = speed_hz; };
|
||||
|
||||
// set frame orientation (normally + or X)
|
||||
virtual void set_frame_orientation( uint8_t new_orientation ) {
|
||||
_frame_orientation = new_orientation;
|
||||
};
|
||||
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() {};
|
||||
|
||||
// arm, disarm or check status status of motors
|
||||
virtual bool armed() {
|
||||
return _armed;
|
||||
};
|
||||
virtual void armed(bool arm) {
|
||||
_armed = arm;
|
||||
};
|
||||
bool armed() { return _armed; };
|
||||
void armed(bool arm) { _armed = arm; };
|
||||
|
||||
// set_min_throttle - sets the minimum throttle that will be sent to the engines when they're not off (i.e. to prevents issues with some motors spinning and some not at very low throttle)
|
||||
virtual void set_min_throttle(uint16_t min_throttle) {
|
||||
_min_throttle = min_throttle;
|
||||
};
|
||||
virtual void set_max_throttle(uint16_t max_throttle) {
|
||||
_max_throttle = max_throttle;
|
||||
};
|
||||
void set_min_throttle(uint16_t min_throttle) { _min_throttle = min_throttle; };
|
||||
void set_max_throttle(uint16_t max_throttle) { _max_throttle = max_throttle; };
|
||||
|
||||
// output - sends commands to the motors
|
||||
virtual void output() {
|
||||
void output() {
|
||||
if( _armed ) { output_armed(); }else{ output_disarmed(); }
|
||||
};
|
||||
|
||||
@ -113,7 +100,7 @@ public:
|
||||
};
|
||||
|
||||
// reached_limits - return whether we hit the limits of the motors
|
||||
virtual uint8_t reached_limit( uint8_t which_limit = AP_MOTOR_ANY_LIMIT ) {
|
||||
uint8_t reached_limit( uint8_t which_limit = AP_MOTOR_ANY_LIMIT ) {
|
||||
return _reached_limit & which_limit;
|
||||
}
|
||||
|
||||
@ -126,7 +113,7 @@ public:
|
||||
|
||||
// setup_throttle_curve - used to linearlise thrust output by motors
|
||||
// returns true if curve is created successfully
|
||||
virtual bool setup_throttle_curve();
|
||||
bool setup_throttle_curve();
|
||||
|
||||
// 1 if motor is enabled, 0 otherwise
|
||||
bool motor_enabled[AP_MOTORS_MAX_NUM_MOTORS];
|
||||
|
Loading…
Reference in New Issue
Block a user