APM:Libraries
AP_BoardLED2.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 #include "AP_BoardLED2.h"
16 
17 #include "AP_Notify.h"
18 
19 
20 // show all status on only 2 leds
21 
22 #if defined(HAL_GPIO_A_LED_PIN) && defined(HAL_GPIO_B_LED_PIN)
23 
24 extern const AP_HAL::HAL& hal;
25 
26 bool AP_BoardLED2::init(void)
27 {
28  // setup the main LEDs as outputs
31 
32  // turn all lights off
35 
36  _sat_cnt=0;
38  arm_counter = 0;
39  return true;
40 }
41 
42 /*
43  main update function called at 50Hz
44  */
45 void AP_BoardLED2::update(void)
46 {
47  _counter++;
48 
49  // we never want to update LEDs at a higher than 16Hz rate
50  if (_counter % 3 != 0) {
51  return;
52  }
53 
54  // counter2 used to drop frequency down to 16hz
55  uint8_t counter2 = _counter / 3;
56 
57  // initialising
58  if (AP_Notify::flags.initialising) {
59  // blink LEDs A at 8Hz (full cycle) during initialisation
61  return;
62  }
63 
64  if ((counter2 & 0x2) == 0) {
66  }
67 
68  bool led_a_used=false;
69 
70  // save trim and ESC calibration
71  if (AP_Notify::flags.save_trim || AP_Notify::flags.esc_calibration) {
72  switch(save_trim_counter) {
73  case 0:
76  break;
77 
78  case 1:
81  break;
82 
83  default:
84  save_trim_counter = -1;
85  break;
86  }
87  return;
88  }
89 
90  if(AP_Notify::flags.compass_cal_running){ // compass calibration
91  switch(save_trim_counter) {
92  case 0:
93  hal.gpio->write(HAL_GPIO_A_LED_PIN, HAL_GPIO_LED_ON); // short blinks by both LEDs
95  break;
96  case 1:
97  case 2:
100  break;
101  case 3:
102  case 4:
103  case 5:
104  case 6:
105  case 7:
106  break;
107  default:
108  // reset counter to restart the sequence
109  save_trim_counter = -1;
110  break;
111  }
112  return;
113 
114  }
115 
116  if(AP_Notify::events.autotune_complete){
117  switch(save_trim_counter) {
118  case 0:
119  hal.gpio->write(HAL_GPIO_A_LED_PIN, HAL_GPIO_LED_ON); // short darkening
120  break;
121  case 1:
122  case 2:
123  case 3:
124  case 4:
125  case 5:
126  case 6:
128  break;
129  case 7:
130  break;
131  default:
132  // reset counter to restart the sequence
133  save_trim_counter = -1;
134  break;
135  }
136  led_a_used=true;
137  }
138 
139  if(AP_Notify::events.autotune_failed){
140  switch(save_trim_counter) {
141  case 0:
142  hal.gpio->write(HAL_GPIO_A_LED_PIN, HAL_GPIO_LED_ON); // short double darkening
143  break;
144  case 1:
146  break;
147  case 2:
148  case 3:
150  break;
151  case 4:
152  case 5:
153  case 6:
154  case 7:
156  break;
157  default:
158  // reset counter to restart the sequence
159  save_trim_counter = -1;
160  break;
161  }
162  led_a_used=true;
163  }
164 
165  // arming light
166  if(!led_a_used) {
167  if (AP_Notify::flags.armed) {
168  if(AP_Notify::flags.failsafe_battery){// blink slowly (around 2Hz)
169  if ((counter2 & 0x7) == 0) {
171  }
172  }else if(AP_Notify::flags.failsafe_radio){// blink fast (around 4Hz)
173  if ((counter2 & 0x3) == 0) {
175  }
176  } else {
177  // ARM led solid
179  }
180  }else{
181  if ((counter2 & 0x2) == 0) {
182  arm_counter++;
183  }
184 
185  if (AP_Notify::flags.pre_arm_check) {
186  // passed pre-arm checks so slower single flash
187  switch(arm_counter) {
188  case 0:
189  case 1:
190  case 2:
191  case 3:
193  break;
194  case 4:
195  case 5:
196  case 6:
197  case 7:
199  break;
200  default:
201  // reset counter to restart the sequence
202  arm_counter = -1;
203  break;
204  }
205  }else{
206  // failed pre-arm checks so double flash
207  switch(arm_counter) {
208  case 0:
209  case 1:
211  break;
212 
213  case 2:
215  break;
216 
217 
218  case 3:
219  case 4:
221  break;
222 
223  case 5:
224  case 6:
225  case 7: // add one tick to do period be a multiple of the second
227  break;
228 
229  default:
230  arm_counter = -1;
231  break;
232  }
233  }
234  }
235  }
236  // gps light
237  switch (AP_Notify::flags.gps_status) {
238  case 0:
239  case 1:
240  // no GPS attached or no lock - be dark
242  break;
243 
244  case 2: // 2d lock
245  case 3:// 3d lock
246  default: // show number of sats
247  if ((counter2 & 0x2) == 0) {
248  _sat_cnt++;
249  }
250  uint16_t sats = AP_Notify::flags.gps_num_sats;
251 
252  if(_sat_cnt<8) { // pause between pulses
254  } else if(_sat_cnt< (8 + (sats-6)*2) ) {
255  hal.gpio->toggle(HAL_GPIO_B_LED_PIN); // 2Hz
256  } else {
257  _sat_cnt=-1;
258  }
259  break;
260  }
261 }
262 #else
263 bool AP_BoardLED2::init(void) {return true;}
264 void AP_BoardLED2::update(void) {return;}
265 #endif
uint8_t save_trim_counter
Definition: AP_BoardLED2.h:40
#define HAL_GPIO_A_LED_PIN
Definition: chibios.h:9
const AP_HAL::HAL & hal
Definition: UARTDriver.cpp:37
uint16_t _sat_cnt
Definition: AP_BoardLED2.h:39
virtual void write(uint8_t pin, uint8_t value)=0
void update(void)
uint8_t arm_counter
Definition: AP_BoardLED2.h:41
virtual void pinMode(uint8_t pin, uint8_t output)=0
#define HAL_GPIO_LED_OFF
Definition: chibios.h:21
#define HAL_GPIO_OUTPUT
Definition: GPIO.h:8
virtual void toggle(uint8_t pin)=0
static struct notify_flags_and_values_type flags
Definition: AP_Notify.h:117
AP_HAL::GPIO * gpio
Definition: HAL.h:111
#define HAL_GPIO_LED_ON
Definition: chibios.h:18
bool init(void)
#define HAL_GPIO_B_LED_PIN
Definition: chibios.h:12
uint8_t _counter
Definition: AP_BoardLED2.h:38
static struct notify_events_type events
Definition: AP_Notify.h:118