mirror of https://github.com/ArduPilot/ardupilot
purple: use the new LED_ON/LED_OFF macros for LED level
this gets this right on both APM1 and purple for ArduCopter
This commit is contained in:
parent
3f2692d1da
commit
4869ac3385
|
@ -19,23 +19,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;
|
||||
}
|
||||
}
|
||||
|
@ -47,14 +47,14 @@ static void update_motor_light(void)
|
|||
|
||||
// blink
|
||||
if(motor_light){
|
||||
digitalWrite(A_LED_PIN, HIGH);
|
||||
digitalWrite(A_LED_PIN, LED_ON);
|
||||
}else{
|
||||
digitalWrite(A_LED_PIN, LOW);
|
||||
digitalWrite(A_LED_PIN, LED_OFF);
|
||||
}
|
||||
}else{
|
||||
if(!motor_light){
|
||||
motor_light = true;
|
||||
digitalWrite(A_LED_PIN, HIGH);
|
||||
digitalWrite(A_LED_PIN, LED_ON);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -69,26 +69,26 @@ static void dancing_light()
|
|||
switch(step)
|
||||
{
|
||||
case 0:
|
||||
digitalWrite(C_LED_PIN, LOW);
|
||||
digitalWrite(A_LED_PIN, HIGH);
|
||||
digitalWrite(C_LED_PIN, LED_OFF);
|
||||
digitalWrite(A_LED_PIN, LED_ON);
|
||||
break;
|
||||
|
||||
case 1:
|
||||
digitalWrite(A_LED_PIN, LOW);
|
||||
digitalWrite(B_LED_PIN, HIGH);
|
||||
digitalWrite(A_LED_PIN, LED_OFF);
|
||||
digitalWrite(B_LED_PIN, LED_ON);
|
||||
break;
|
||||
|
||||
case 2:
|
||||
digitalWrite(B_LED_PIN, LOW);
|
||||
digitalWrite(C_LED_PIN, HIGH);
|
||||
digitalWrite(B_LED_PIN, LED_OFF);
|
||||
digitalWrite(C_LED_PIN, LED_ON);
|
||||
break;
|
||||
}
|
||||
}
|
||||
static void clear_leds()
|
||||
{
|
||||
digitalWrite(A_LED_PIN, LOW);
|
||||
digitalWrite(B_LED_PIN, LOW);
|
||||
digitalWrite(C_LED_PIN, LOW);
|
||||
digitalWrite(A_LED_PIN, LED_OFF);
|
||||
digitalWrite(B_LED_PIN, LED_OFF);
|
||||
digitalWrite(C_LED_PIN, LED_OFF);
|
||||
motor_light = false;
|
||||
led_mode = NORMAL_LEDS;
|
||||
}
|
||||
|
|
|
@ -92,10 +92,18 @@ static void init_ardupilot()
|
|||
report_version();
|
||||
|
||||
// setup IO pins
|
||||
pinMode(C_LED_PIN, OUTPUT); // GPS status LED
|
||||
pinMode(A_LED_PIN, OUTPUT); // GPS status LED
|
||||
pinMode(B_LED_PIN, OUTPUT); // GPS status LED
|
||||
pinMode(SLIDE_SWITCH_PIN, INPUT); // To enter interactive mode
|
||||
digitalWrite(A_LED_PIN, LED_OFF);
|
||||
|
||||
pinMode(B_LED_PIN, OUTPUT); // GPS status LED
|
||||
digitalWrite(B_LED_PIN, LED_OFF);
|
||||
|
||||
pinMode(C_LED_PIN, OUTPUT); // GPS status LED
|
||||
digitalWrite(C_LED_PIN, LED_OFF);
|
||||
|
||||
#if SLIDE_SWITCH_PIN > 0
|
||||
pinMode(SLIDE_SWITCH_PIN, INPUT); // To enter interactive mode
|
||||
#endif
|
||||
pinMode(PUSHBUTTON_PIN, INPUT); // unused
|
||||
DDRL |= B00000100; // Set Port L, pin 2 to output for the relay
|
||||
|
||||
|
@ -141,13 +149,13 @@ static void init_ardupilot()
|
|||
while (true) {
|
||||
delay(1000);
|
||||
if(motor_light){
|
||||
digitalWrite(A_LED_PIN, HIGH);
|
||||
digitalWrite(B_LED_PIN, HIGH);
|
||||
digitalWrite(C_LED_PIN, HIGH);
|
||||
digitalWrite(A_LED_PIN, LED_ON);
|
||||
digitalWrite(B_LED_PIN, LED_ON);
|
||||
digitalWrite(C_LED_PIN, LED_ON);
|
||||
}else{
|
||||
digitalWrite(A_LED_PIN, LOW);
|
||||
digitalWrite(B_LED_PIN, LOW);
|
||||
digitalWrite(C_LED_PIN, LOW);
|
||||
digitalWrite(A_LED_PIN, LED_OFF);
|
||||
digitalWrite(B_LED_PIN, LED_OFF);
|
||||
digitalWrite(C_LED_PIN, LED_OFF);
|
||||
}
|
||||
motor_light = !motor_light;
|
||||
}
|
||||
|
@ -236,7 +244,7 @@ static void init_ardupilot()
|
|||
// menu; they must reset in order to fly.
|
||||
//
|
||||
if (check_startup_for_CLI()) {
|
||||
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("\nCLI:\n\n"));
|
||||
run_cli();
|
||||
}
|
||||
|
|
|
@ -763,14 +763,14 @@ test_wp(uint8_t argc, const Menu::arg *argv)
|
|||
delay(1000);
|
||||
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);
|
||||
|
|
Loading…
Reference in New Issue