mirror of https://github.com/ArduPilot/ardupilot
uncrustify ArduCopter/leds.pde
This commit is contained in:
parent
2d398aa663
commit
b6dd8aa592
|
@ -1,6 +1,6 @@
|
|||
static void update_lights()
|
||||
{
|
||||
switch(led_mode){
|
||||
switch(led_mode) {
|
||||
case NORMAL_LEDS:
|
||||
update_motor_light();
|
||||
update_GPS_light();
|
||||
|
@ -16,9 +16,9 @@ static void update_GPS_light(void)
|
|||
{
|
||||
// GPS LED on if we have a fix or Blink GPS LED if we are receiving data
|
||||
// ---------------------------------------------------------------------
|
||||
switch (g_gps->status()){
|
||||
switch (g_gps->status()) {
|
||||
|
||||
case(2):
|
||||
case (2):
|
||||
if(home_is_set) { // JLN update
|
||||
digitalWrite(C_LED_PIN, LED_ON); //Turn LED C on when gps has valid fix AND home is set.
|
||||
} else {
|
||||
|
@ -26,10 +26,10 @@ static void update_GPS_light(void)
|
|||
}
|
||||
break;
|
||||
|
||||
case(1):
|
||||
if (g_gps->valid_read == true){
|
||||
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){
|
||||
if (GPS_light) {
|
||||
digitalWrite(C_LED_PIN, LED_OFF);
|
||||
}else{
|
||||
digitalWrite(C_LED_PIN, LED_ON);
|
||||
|
@ -46,17 +46,17 @@ static void update_GPS_light(void)
|
|||
|
||||
static void update_motor_light(void)
|
||||
{
|
||||
if(motors.armed() == false){
|
||||
if(motors.armed() == false) {
|
||||
motor_light = !motor_light;
|
||||
|
||||
// blink
|
||||
if(motor_light){
|
||||
if(motor_light) {
|
||||
digitalWrite(A_LED_PIN, LED_ON);
|
||||
}else{
|
||||
digitalWrite(A_LED_PIN, LED_OFF);
|
||||
}
|
||||
}else{
|
||||
if(!motor_light){
|
||||
if(!motor_light) {
|
||||
motor_light = true;
|
||||
digitalWrite(A_LED_PIN, LED_ON);
|
||||
}
|
||||
|
@ -146,13 +146,13 @@ static void update_copter_leds(void)
|
|||
}
|
||||
}
|
||||
|
||||
if ( bitRead(g.copter_leds_mode, 1) ){
|
||||
if ( bitRead(g.copter_leds_mode, 1) ) {
|
||||
|
||||
// GPS LED on if we have a fix or Blink GPS LED if we are receiving data
|
||||
// ---------------------------------------------------------------------
|
||||
switch (g_gps->status()){
|
||||
switch (g_gps->status()) {
|
||||
|
||||
case(2):
|
||||
case (2):
|
||||
if(home_is_set) {
|
||||
if ( !bitRead(g.copter_leds_mode, 6 ) ) {
|
||||
copter_leds_GPS_on(); //Turn GPS LEDs on when gps has valid fix AND home is set
|
||||
|
@ -168,7 +168,7 @@ static void update_copter_leds(void)
|
|||
}
|
||||
break;
|
||||
|
||||
case(1):
|
||||
case (1):
|
||||
|
||||
copter_leds_GPS_slow_blink(); //if GPS has valid reads, but no fix, blink GPS LED slow
|
||||
|
||||
|
@ -202,17 +202,17 @@ static void copter_leds_reset(void) {
|
|||
}
|
||||
|
||||
static void copter_leds_on(void) {
|
||||
if ( !bitRead(g.copter_leds_mode, 2) ){
|
||||
if ( !bitRead(g.copter_leds_mode, 2) ) {
|
||||
digitalWrite(COPTER_LED_1, COPTER_LED_ON);
|
||||
}
|
||||
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
|
||||
if ( !bitRead(g.copter_leds_mode, 3) ){
|
||||
if ( !bitRead(g.copter_leds_mode, 3) ) {
|
||||
digitalWrite(COPTER_LED_2, COPTER_LED_ON);
|
||||
}
|
||||
#else
|
||||
digitalWrite(COPTER_LED_2, COPTER_LED_ON);
|
||||
#endif
|
||||
if ( !bitRead(g.copter_leds_mode, 1) ){
|
||||
if ( !bitRead(g.copter_leds_mode, 1) ) {
|
||||
digitalWrite(COPTER_LED_3, COPTER_LED_ON);
|
||||
}
|
||||
digitalWrite(COPTER_LED_4, COPTER_LED_ON);
|
||||
|
@ -223,17 +223,17 @@ static void copter_leds_on(void) {
|
|||
}
|
||||
|
||||
static void copter_leds_off(void) {
|
||||
if ( !bitRead(g.copter_leds_mode, 2) ){
|
||||
if ( !bitRead(g.copter_leds_mode, 2) ) {
|
||||
digitalWrite(COPTER_LED_1, COPTER_LED_OFF);
|
||||
}
|
||||
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
|
||||
if ( !bitRead(g.copter_leds_mode, 3) ){
|
||||
if ( !bitRead(g.copter_leds_mode, 3) ) {
|
||||
digitalWrite(COPTER_LED_2, COPTER_LED_OFF);
|
||||
}
|
||||
#else
|
||||
digitalWrite(COPTER_LED_2, COPTER_LED_OFF);
|
||||
#endif
|
||||
if ( !bitRead(g.copter_leds_mode, 1) ){
|
||||
if ( !bitRead(g.copter_leds_mode, 1) ) {
|
||||
digitalWrite(COPTER_LED_3, COPTER_LED_OFF);
|
||||
}
|
||||
digitalWrite(COPTER_LED_4, COPTER_LED_OFF);
|
||||
|
@ -245,12 +245,12 @@ static void copter_leds_off(void) {
|
|||
|
||||
static void copter_leds_slow_blink(void) {
|
||||
copter_leds_motor_blink++; // this increments once every 1/10 second because it is in the 10hz loop
|
||||
if ( 0 < copter_leds_motor_blink && copter_leds_motor_blink < 6 ){ // when the counter reaches 5 (1/2 sec), then toggle the leds
|
||||
if ( 0 < copter_leds_motor_blink && copter_leds_motor_blink < 6 ) { // when the counter reaches 5 (1/2 sec), then toggle the leds
|
||||
copter_leds_off();
|
||||
if ( bitRead(g.copter_leds_mode, 5 ) && !bitRead(g.copter_leds_mode, 6 ) && copter_leds_nav_blink >0 ) { // if blinking is called by the Nav Blinker...
|
||||
copter_leds_nav_blink--; // decrement the Nav Blink counter
|
||||
}
|
||||
}else if (5 < copter_leds_motor_blink && copter_leds_motor_blink < 11){
|
||||
}else if (5 < copter_leds_motor_blink && copter_leds_motor_blink < 11) {
|
||||
copter_leds_on();
|
||||
}
|
||||
else copter_leds_motor_blink = 0; // start blink cycle again
|
||||
|
@ -258,9 +258,9 @@ static void copter_leds_slow_blink(void) {
|
|||
|
||||
static void copter_leds_fast_blink(void) {
|
||||
copter_leds_motor_blink++; // this increments once every 1/10 second because it is in the 10hz loop
|
||||
if ( 0 < copter_leds_motor_blink && copter_leds_motor_blink < 3 ){ // when the counter reaches 3 (1/5 sec), then toggle the leds
|
||||
if ( 0 < copter_leds_motor_blink && copter_leds_motor_blink < 3 ) { // when the counter reaches 3 (1/5 sec), then toggle the leds
|
||||
copter_leds_on();
|
||||
}else if (2 < copter_leds_motor_blink && copter_leds_motor_blink < 5){
|
||||
}else if (2 < copter_leds_motor_blink && copter_leds_motor_blink < 5) {
|
||||
copter_leds_off();
|
||||
}
|
||||
else copter_leds_motor_blink = 0; // start blink cycle again
|
||||
|
@ -270,17 +270,17 @@ static void copter_leds_fast_blink(void) {
|
|||
static void copter_leds_oscillate(void) {
|
||||
copter_leds_motor_blink++; // this increments once every 1/10 second because it is in the 10hz loop
|
||||
if ( 0 < copter_leds_motor_blink && copter_leds_motor_blink < 3 ) { // when the counter reaches 3 (1/5 sec), then toggle the leds
|
||||
if ( !bitRead(g.copter_leds_mode, 2) ){
|
||||
if ( !bitRead(g.copter_leds_mode, 2) ) {
|
||||
digitalWrite(COPTER_LED_1, COPTER_LED_ON);
|
||||
}
|
||||
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
|
||||
if ( !bitRead(g.copter_leds_mode, 3) ){
|
||||
if ( !bitRead(g.copter_leds_mode, 3) ) {
|
||||
digitalWrite(COPTER_LED_2, COPTER_LED_ON);
|
||||
}
|
||||
#else
|
||||
digitalWrite(COPTER_LED_2, COPTER_LED_ON);
|
||||
#endif
|
||||
if ( !bitRead(g.copter_leds_mode, 1) ){
|
||||
if ( !bitRead(g.copter_leds_mode, 1) ) {
|
||||
digitalWrite(COPTER_LED_3, COPTER_LED_OFF);
|
||||
}
|
||||
digitalWrite(COPTER_LED_4, COPTER_LED_OFF);
|
||||
|
@ -289,17 +289,17 @@ static void copter_leds_oscillate(void) {
|
|||
digitalWrite(COPTER_LED_7, COPTER_LED_OFF);
|
||||
digitalWrite(COPTER_LED_8, COPTER_LED_OFF);
|
||||
}else if (2 < copter_leds_motor_blink && copter_leds_motor_blink < 5) {
|
||||
if ( !bitRead(g.copter_leds_mode, 2) ){
|
||||
if ( !bitRead(g.copter_leds_mode, 2) ) {
|
||||
digitalWrite(COPTER_LED_1, COPTER_LED_OFF);
|
||||
}
|
||||
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
|
||||
if ( !bitRead(g.copter_leds_mode, 3) ){
|
||||
if ( !bitRead(g.copter_leds_mode, 3) ) {
|
||||
digitalWrite(COPTER_LED_2, COPTER_LED_OFF);
|
||||
}
|
||||
#else
|
||||
digitalWrite(COPTER_LED_2, COPTER_LED_OFF);
|
||||
#endif
|
||||
if ( !bitRead(g.copter_leds_mode, 1) ){
|
||||
if ( !bitRead(g.copter_leds_mode, 1) ) {
|
||||
digitalWrite(COPTER_LED_3, COPTER_LED_ON);
|
||||
}
|
||||
digitalWrite(COPTER_LED_4, COPTER_LED_ON);
|
||||
|
@ -323,12 +323,12 @@ static void copter_leds_GPS_off(void) {
|
|||
|
||||
static void copter_leds_GPS_slow_blink(void) {
|
||||
copter_leds_GPS_blink++; // this increments once every 1/10 second because it is in the 10hz loop
|
||||
if ( 0 < copter_leds_GPS_blink && copter_leds_GPS_blink < 6 ){ // when the counter reaches 5 (1/2 sec), then toggle the leds
|
||||
if ( 0 < copter_leds_GPS_blink && copter_leds_GPS_blink < 6 ) { // when the counter reaches 5 (1/2 sec), then toggle the leds
|
||||
copter_leds_GPS_off();
|
||||
if ( bitRead(g.copter_leds_mode, 6 ) && copter_leds_nav_blink >0 ) { // if blinking is called by the Nav Blinker...
|
||||
copter_leds_nav_blink--; // decrement the Nav Blink counter
|
||||
}
|
||||
}else if (5 < copter_leds_GPS_blink && copter_leds_GPS_blink < 11){
|
||||
}else if (5 < copter_leds_GPS_blink && copter_leds_GPS_blink < 11) {
|
||||
copter_leds_GPS_on();
|
||||
}
|
||||
else copter_leds_GPS_blink = 0; // start blink cycle again
|
||||
|
@ -338,7 +338,7 @@ static void copter_leds_GPS_fast_blink(void) {
|
|||
copter_leds_GPS_blink++; // this increments once every 1/10 second because it is in the 10hz loop
|
||||
if ( 0 < copter_leds_GPS_blink && copter_leds_GPS_blink < 3 ) { // when the counter reaches 3 (1/5 sec), then toggle the leds
|
||||
copter_leds_GPS_off();
|
||||
}else if (2 < copter_leds_GPS_blink && copter_leds_GPS_blink < 5){
|
||||
}else if (2 < copter_leds_GPS_blink && copter_leds_GPS_blink < 5) {
|
||||
copter_leds_GPS_on();
|
||||
}
|
||||
else copter_leds_GPS_blink = 0; // start blink cycle again
|
||||
|
|
Loading…
Reference in New Issue