mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
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:
parent
998058ec07
commit
926211f0f0
@ -79,7 +79,7 @@ public:
|
||||
|
||||
// arm, disarm or check status status of motors
|
||||
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
|
||||
// Note: this should probably be moved out of this class as it has little to do with the motors
|
||||
|
@ -101,7 +101,7 @@ void AP_MotorsMatrix::output_min()
|
||||
int8_t i;
|
||||
|
||||
// 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] ) {
|
||||
motor_out[i] = _rc_throttle->radio_min;
|
||||
_rc->OutputCh(_motor_to_channel_map[i], motor_out[i]);
|
||||
|
Loading…
Reference in New Issue
Block a user