mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_MotorsMatrix: remove unused _num_motors
Saves 1 byte of RAM
This commit is contained in:
parent
32a0992985
commit
2c6470f87b
@ -377,7 +377,6 @@ void AP_MotorsMatrix::add_motor_raw(int8_t motor_num, float roll_fac, float pitc
|
|||||||
// increment number of motors if this motor is being newly motor_enabled
|
// increment number of motors if this motor is being newly motor_enabled
|
||||||
if( !motor_enabled[motor_num] ) {
|
if( !motor_enabled[motor_num] ) {
|
||||||
motor_enabled[motor_num] = true;
|
motor_enabled[motor_num] = true;
|
||||||
_num_motors++;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// set roll, pitch, thottle factors and opposite motor (for stability patch)
|
// set roll, pitch, thottle factors and opposite motor (for stability patch)
|
||||||
@ -411,11 +410,6 @@ void AP_MotorsMatrix::remove_motor(int8_t motor_num)
|
|||||||
{
|
{
|
||||||
// ensure valid motor number is provided
|
// ensure valid motor number is provided
|
||||||
if( motor_num >= 0 && motor_num < AP_MOTORS_MAX_NUM_MOTORS ) {
|
if( motor_num >= 0 && motor_num < AP_MOTORS_MAX_NUM_MOTORS ) {
|
||||||
|
|
||||||
// if the motor was enabled decrement the number of motors
|
|
||||||
if( motor_enabled[motor_num] )
|
|
||||||
_num_motors--;
|
|
||||||
|
|
||||||
// disable the motor, set all factors to zero
|
// disable the motor, set all factors to zero
|
||||||
motor_enabled[motor_num] = false;
|
motor_enabled[motor_num] = false;
|
||||||
_roll_factor[motor_num] = 0;
|
_roll_factor[motor_num] = 0;
|
||||||
@ -430,5 +424,4 @@ void AP_MotorsMatrix::remove_all_motors()
|
|||||||
for( int8_t i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++ ) {
|
for( int8_t i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++ ) {
|
||||||
remove_motor(i);
|
remove_motor(i);
|
||||||
}
|
}
|
||||||
_num_motors = 0;
|
|
||||||
}
|
}
|
||||||
|
@ -22,9 +22,8 @@ public:
|
|||||||
|
|
||||||
/// Constructor
|
/// Constructor
|
||||||
AP_MotorsMatrix( RC_Channel* rc_roll, RC_Channel* rc_pitch, RC_Channel* rc_throttle, RC_Channel* rc_yaw, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) :
|
AP_MotorsMatrix( RC_Channel* rc_roll, RC_Channel* rc_pitch, RC_Channel* rc_throttle, RC_Channel* rc_yaw, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) :
|
||||||
AP_Motors(rc_roll, rc_pitch, rc_throttle, rc_yaw, speed_hz),
|
AP_Motors(rc_roll, rc_pitch, rc_throttle, rc_yaw, speed_hz)
|
||||||
_num_motors(0) {
|
{};
|
||||||
};
|
|
||||||
|
|
||||||
// init
|
// init
|
||||||
virtual void Init();
|
virtual void Init();
|
||||||
@ -67,7 +66,6 @@ protected:
|
|||||||
// add_motor using raw roll, pitch, throttle and yaw factors
|
// add_motor using raw roll, pitch, throttle and yaw factors
|
||||||
void add_motor_raw(int8_t motor_num, float roll_fac, float pitch_fac, float yaw_fac, uint8_t testing_order);
|
void add_motor_raw(int8_t motor_num, float roll_fac, float pitch_fac, float yaw_fac, uint8_t testing_order);
|
||||||
|
|
||||||
int8_t _num_motors; // not a very useful variable as you really need to check the motor_enabled array to see which motors are enabled
|
|
||||||
float _roll_factor[AP_MOTORS_MAX_NUM_MOTORS]; // each motors contribution to roll
|
float _roll_factor[AP_MOTORS_MAX_NUM_MOTORS]; // each motors contribution to roll
|
||||||
float _pitch_factor[AP_MOTORS_MAX_NUM_MOTORS]; // each motors contribution to pitch
|
float _pitch_factor[AP_MOTORS_MAX_NUM_MOTORS]; // each motors contribution to pitch
|
||||||
float _yaw_factor[AP_MOTORS_MAX_NUM_MOTORS]; // each motors contribution to yaw (normally 1 or -1)
|
float _yaw_factor[AP_MOTORS_MAX_NUM_MOTORS]; // each motors contribution to yaw (normally 1 or -1)
|
||||||
|
Loading…
Reference in New Issue
Block a user