From a6bf2d9cd6fd98ba9926b95cda1a929785950a11 Mon Sep 17 00:00:00 2001
From: Pat Hickey <pat@galois.com>
Date: Fri, 25 Nov 2011 14:55:30 -0800
Subject: [PATCH] ArduPlane: LED digital writes use LED_OFF and LED_ON

---
 ArduPlane/sensors.pde | 12 ++++++------
 ArduPlane/system.pde  | 16 ++++++++--------
 ArduPlane/test.pde    |  8 ++++----
 3 files changed, 18 insertions(+), 18 deletions(-)

diff --git a/ArduPlane/sensors.pde b/ArduPlane/sensors.pde
index a4da47bba..64b0c582a 100644
--- a/ArduPlane/sensors.pde
+++ b/ArduPlane/sensors.pde
@@ -31,16 +31,16 @@ static void init_barometer(void)
 
 		mavlink_delay(20);
 		if(flashcount == 5) {
-			digitalWrite(C_LED_PIN, LOW);
-			digitalWrite(A_LED_PIN, HIGH);
-			digitalWrite(B_LED_PIN, LOW);
+			digitalWrite(C_LED_PIN, LED_OFF);
+			digitalWrite(A_LED_PIN, LED_ON);
+			digitalWrite(B_LED_PIN, LED_OFF);
 		}
 
 		if(flashcount >= 10) {
 			flashcount = 0;
-			digitalWrite(C_LED_PIN, HIGH);
-			digitalWrite(A_LED_PIN, LOW);
-			digitalWrite(B_LED_PIN, HIGH);
+			digitalWrite(C_LED_PIN, LED_ON);
+			digitalWrite(A_LED_PIN, LED_OFF);
+			digitalWrite(B_LED_PIN, LED_ON);
 		}
 		flashcount++;
 	}
diff --git a/ArduPlane/system.pde b/ArduPlane/system.pde
index 5834abb73..e01c4f105 100644
--- a/ArduPlane/system.pde
+++ b/ArduPlane/system.pde
@@ -233,7 +233,7 @@ static void init_ardupilot()
 	//
 #if CLI_ENABLED == ENABLED && CLI_SLIDER_ENABLED == ENABLED
 	if (digitalRead(SLIDE_SWITCH_PIN) == 0) {
-		digitalWrite(A_LED_PIN,HIGH);		// turn on setup-mode LED
+		digitalWrite(A_LED_PIN,LED_ON);		// turn on setup-mode LED
 		Serial.printf_P(PSTR("\n"
 							 "Entering interactive setup mode...\n"
 							 "\n"
@@ -474,9 +474,9 @@ static void startup_IMU_ground(void)
 
 #endif // HIL_MODE_ATTITUDE
 
-	digitalWrite(B_LED_PIN, HIGH);		// Set LED B high to indicate IMU ready
-	digitalWrite(A_LED_PIN, LOW);
-	digitalWrite(C_LED_PIN, LOW);
+	digitalWrite(B_LED_PIN, LED_ON);		// Set LED B high to indicate IMU ready
+	digitalWrite(A_LED_PIN, LED_OFF);
+	digitalWrite(C_LED_PIN, LED_OFF);
 }
 
 
@@ -486,23 +486,23 @@ static void update_GPS_light(void)
 	// ---------------------------------------------------------------------
 	switch (g_gps->status()) {
 		case(2):
-			digitalWrite(C_LED_PIN, HIGH);  //Turn LED C on when gps has valid fix.
+			digitalWrite(C_LED_PIN, LED_ON);  //Turn LED C on when gps has valid fix.
 			break;
 
 		case(1):
 			if (g_gps->valid_read == true){
 				GPS_light = !GPS_light; // Toggle light on and off to indicate gps messages being received, but no GPS fix lock
 				if (GPS_light){
-					digitalWrite(C_LED_PIN, LOW);
+					digitalWrite(C_LED_PIN, LED_OFF);
 				} else {
-					digitalWrite(C_LED_PIN, HIGH);
+					digitalWrite(C_LED_PIN, LED_ON);
 				}
 				g_gps->valid_read = false;
 			}
 			break;
 
 		default:
-			digitalWrite(C_LED_PIN, LOW);
+			digitalWrite(C_LED_PIN, LED_OFF);
 			break;
 	}
 }
diff --git a/ArduPlane/test.pde b/ArduPlane/test.pde
index 9fb162553..1bf763b43 100644
--- a/ArduPlane/test.pde
+++ b/ArduPlane/test.pde
@@ -719,14 +719,14 @@ test_rawgps(uint8_t argc, const Menu::arg *argv)
 
 	while(1){
 		if (Serial3.available()){
-			digitalWrite(B_LED_PIN, HIGH); 		// Blink Yellow LED if we are sending data to GPS
+			digitalWrite(B_LED_PIN, LED_ON); 		// Blink Yellow LED if we are sending data to GPS
 			Serial1.write(Serial3.read());
-			digitalWrite(B_LED_PIN, LOW);
+			digitalWrite(B_LED_PIN, LED_OFF);
 		}
 		if (Serial1.available()){
-			digitalWrite(C_LED_PIN, HIGH);		// Blink Red LED if we are receiving data from GPS
+			digitalWrite(C_LED_PIN, LED_ON);		// Blink Red LED if we are receiving data from GPS
 			Serial3.write(Serial1.read());
-			digitalWrite(C_LED_PIN, LOW);
+			digitalWrite(C_LED_PIN, LED_OFF);
 		}
 		if(Serial.available() > 0){
 			return (0);
-- 
GitLab