AP_Motors - fix compiler warning re shadowing a variable caused by badly named parameter in armed function.

Another compiler warning fixed in AP_MotorsMatrix.cpp caused by declaring "i" twice.
This commit is contained in:
rmackay9 2012-04-04 23:59:51 +09:00
parent 998058ec07
commit 926211f0f0
2 changed files with 2 additions and 2 deletions

View File

@ -79,7 +79,7 @@ public:
// arm, disarm or check status status of motors // arm, disarm or check status status of motors
virtual bool armed() { return _armed; }; virtual bool armed() { return _armed; };
virtual void armed(bool armed) { _armed = armed; }; virtual void armed(bool arm) { _armed = arm; };
// check or set status of auto_armed - controls whether autopilot can take control of throttle // check or set status of auto_armed - controls whether autopilot can take control of throttle
// Note: this should probably be moved out of this class as it has little to do with the motors // Note: this should probably be moved out of this class as it has little to do with the motors

View File

@ -101,7 +101,7 @@ void AP_MotorsMatrix::output_min()
int8_t i; int8_t i;
// fill the motor_out[] array for HIL use and send minimum value to each motor // fill the motor_out[] array for HIL use and send minimum value to each motor
for( int8_t i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++ ) { for( i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++ ) {
if( motor_enabled[i] ) { if( motor_enabled[i] ) {
motor_out[i] = _rc_throttle->radio_min; motor_out[i] = _rc_throttle->radio_min;
_rc->OutputCh(_motor_to_channel_map[i], motor_out[i]); _rc->OutputCh(_motor_to_channel_map[i], motor_out[i]);