From 40e5a15452595d5dfe547689eed13b9e27d2e509 Mon Sep 17 00:00:00 2001
From: rmackay9 <rmackay9@yahoo.com>
Date: Wed, 4 Apr 2012 23:59:51 +0900
Subject: [PATCH] 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.

---
 libraries/AP_Motors/AP_Motors.h         | 2 +-
 libraries/AP_Motors/AP_MotorsMatrix.cpp | 2 +-
 2 files changed, 2 insertions(+), 2 deletions(-)

diff --git a/libraries/AP_Motors/AP_Motors.h b/libraries/AP_Motors/AP_Motors.h
index 1d5f9e718..0e8d72373 100644
--- a/libraries/AP_Motors/AP_Motors.h
+++ b/libraries/AP_Motors/AP_Motors.h
@@ -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
diff --git a/libraries/AP_Motors/AP_MotorsMatrix.cpp b/libraries/AP_Motors/AP_MotorsMatrix.cpp
index 851f06365..36d52f2da 100644
--- a/libraries/AP_Motors/AP_MotorsMatrix.cpp
+++ b/libraries/AP_Motors/AP_MotorsMatrix.cpp
@@ -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]);
-- 
GitLab