mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_Motors: remove motor_out array
Saves 16bytes of RAM
This commit is contained in:
parent
5f89e9e746
commit
83321b8786
@ -86,11 +86,6 @@ AP_Motors::AP_Motors( RC_Channel* rc_roll, RC_Channel* rc_pitch, RC_Channel* rc_
|
||||
|
||||
// slow start motors from zero to min throttle
|
||||
_flags.slow_start_low_end = true;
|
||||
|
||||
// clear output arrays
|
||||
for(i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
|
||||
motor_out[i] = 0;
|
||||
}
|
||||
};
|
||||
|
||||
// init
|
||||
@ -222,4 +217,4 @@ void AP_Motors::update_max_throttle()
|
||||
_max_throttle = AP_MOTORS_DEFAULT_MAX_THROTTLE;
|
||||
_flags.slow_start = false;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -168,7 +168,6 @@ protected:
|
||||
// internal variables
|
||||
RC_Channel* _rc_roll, *_rc_pitch, *_rc_throttle, *_rc_yaw; // input in from users
|
||||
uint8_t _motor_to_channel_map[AP_MOTORS_MAX_NUM_MOTORS]; // mapping of motor number (as received from upper APM code) to RC channel output - used to account for differences between APM1 and APM2
|
||||
int16_t motor_out[AP_MOTORS_MAX_NUM_MOTORS]; // final output values sent to the motors
|
||||
uint16_t _speed_hz; // speed in hz to send updates to motors
|
||||
int16_t _min_throttle; // the minimum throttle to be sent to the motors when they're on (prevents motors stalling while flying)
|
||||
int16_t _max_throttle; // the maximum throttle to be sent to the motors (sometimes limited by slow start)
|
||||
|
Loading…
Reference in New Issue
Block a user