APM:Libraries
osd.cpp
Go to the documentation of this file.
1 /*
2  wrapper for OSD code (https://github.com/night-ghost/minimosd-extra) to run in the HAL as independent process
3 
4  (c) night_ghost@ykoctpa.ru 2017
5 
6 */
7 
8 #include <AP_HAL/AP_HAL.h>
9 
10 #ifdef BOARD_OSD_CS_PIN
11 
12 #include <utility>
13 
14 #include "osd_core/compat.h"
15 
16 
17 
18 using namespace F4Light;
19 
20 #include <AP_Common/AP_Common.h>
21 #include <stdio.h>
22 
23 #include <hal.h>
24 #include "ring_buffer.h"
25 
26 #include <inttypes.h>
30 
31 #define SLAVE_BUILD
32 
33 // remove some things defined in AP_HAL
34 #undef round
35 #define round(x) roundf(x)
36 
37 #include "osd_core/Defs.h"
38 
39 #include "osd.h"
40 
41 
42 #include "osd_eeprom.h"
43 #include "osd_core/eeprom.h"
44 #include "osd_core/version.h"
45 #include <sd/SD.h>
46 
47 
48 namespace OSDns {
49 
50 #include "osd_core/GCS_MAVLink.h"
51 
52 #include "osd_core/OSD_Max7456.h"
53 OSD osd; //OSD object
54 
55 #include "osd_core/prototypes.h"
56 #include "osd_core/Vars.h"
57 
58 
59 
60 #include "osd_core/Config_Func.h"
61 #include "osd_core/Config.h"
62 #include "osd_core/Func.h"
63 #include "osd_core/protocols.h"
64 #include "osd_core/misc.h"
65 
66 #include "osd_core/Params.h"
67 #include "osd_core/Panels.h"
68 
69 
70 // TODO: чтение конфига и еепром с карты памяти, чтобы закинуть .mcm и .osd и все
71 static const char * const words[] = {
72  "Air Speed", // 1
73  "Altitude", // 2
74  "Auto Mode", // 3
75  "Auto Screen Switch", // 4
76  "batt_a_k", // 5
77  "BattB", // 6
78  "batt_b_k", // 7
79  "Battery", // 8
80  "Battery A", // 9
81  "Battery B", // 10
82  "Battery Percent", // 11
83  "Battery Warning Level", // 12
84  "Call Sign", // 13
85  "Chanel Rotation Switching", // 14
86  "Channel Raw", // 15
87  "Channel Scale", // 16
88  "Channel state", // 17
89  "Channel Value", // 18
90 
91  "Configuration", // 19
92  "Current", // 20
93  "curr_k", // 21
94  "Efficiency", // 22
95  "fBattA", // 23
96  "fBattB", // 24
97  "fCurr", // 25
98  "fILS", // 26
99  "flgHUD", // 27
100  "flgOnce", // 28
101  "flgTrack", // 29
102  "Flight Data", // 30
103  "Flight Mode", // 31
104  "fRussianHUD", // 32
105  "GPS Coord", // 33
106  "GPS HDOP", // 34
107  "Heading", // 35
108  "Heading Rose", // 36
109  "Home Altitude", // 37
110  "Home Direction", // 38
111  "Home Distance", // 39
112  "Horizon", // 40
113  "HOS", // 41
114  "Message", // 42
115  "Model Type", // 43
116  "NSCREENS", // 44
117  "OSD Brightness", // 45
118  "Overspeed", // 46
119 
120  "Panel", // 47
121  "Pitch", // 48
122  "pitch_k", // 49
123  "pitch_kn", // 50
124  "PWMDST", // 51
125  "PWMSRC", // 52
126  "Radar Scale", // 53
127  "Real heading", // 54
128  "Roll", // 55
129  "roll_k", // 56
130  "roll_kn", // 57
131  "RSSI", // 58
132  "RSSI Enable Raw", // 59
133  "RSSI High", // 60
134  "rssi_k", // 61
135  "RSSI Low", // 62
136  "RSSI Warning Level", // 63
137  "SAdd1", // 64
138  "SAdd2", // 65
139  "SAdd3", // 66
140  "SAdd4", // 67
141  "Sensor 1", // 68
142  "Sensor 2", // 69
143  "Sensor 3", // 70
144  "Sensor 4", // 71
145  "SFactor1", // 72
146  "SFactor2", // 73
147  "SFactor3", // 74
148  "SFactor4", // 75
149  "SFormat1", // 76
150  "SFormat2", // 77
151  "SFormat3", // 78
152  "SFormat4", // 79
153  "Stall", // 80
154  "Temperature", // 81
155  "Throttle", // 82
156  "Time", // 83
157  "Toggle Channel", // 84
158  "Trip Distance", // 85
159  "Tune", // 86
160  "txtTime0", // 87
161  "txtTime1", // 88
162  "txtTime2", // 89
163  "txtTime3", // 90
164  "Units", // 91
165  "Velocity", // 92
166  "Vertical Speed", // 93
167  "Video Mode", // 94
168  "Visible Sats", // 95
169  "VOS", // 96
170  "Warnings", // 97
171  "Wind Speed", // 98
172  "WP Direction", // 99
173  "WP Distance", // 100
174  "#", // 101
175  "Power", // 102
176  "Date", // 103
177  "Time of day", // 104
178  "Motors", // 105
179  "Vibrations", // 106
180  "Variometer", // 107
181  "GPS Coord Lat", // 108
182  "GPS Coord Lon", // 109
183 };
184 
185 typedef struct OSD_PAN {
186  uint8_t dst;
187  uint8_t size;
188  char fmt;
189  uint8_t pan_n;
190 } OSD_pan;
191 
192 #define m1 ((uint8_t)-1)
193 
194 static const OSD_pan pan_tbl[]={
195  { 0, 0, 0, 0, },
196  { 0, 0, 0, ID_of(airSpeed), }, // "Air Speed", // 1
197  { 0, 0, 0, ID_of(alt), }, // "Altitude", // 2
198  { 9, m1, 0, 0, }, // "Auto Mode", // 3 - bit in flags
199  { 7, m1, 0, 0, }, // "Auto Screen Switch", // 4
200  { offsetof(Settings,evBattA_koef), sizeof(sets.evBattA_koef), 'f', 0, }, // "batt_a_k",
201  { offsetof(Settings,battBv), sizeof(sets.battBv), 'b', 0, }, // "BattB",
202  { offsetof(Settings,evBattB_koef), sizeof(sets.evBattB_koef), 'f', 0, }, // "batt_b_k",
203  { offsetof(Settings,battv), sizeof(sets.battv), 'b', 0, }, // "Battery",
204  { 0, 0, 0, ID_of(batt_A), }, // "Battery A", // 9
205  { 0, 0, 0, ID_of(batt_B), }, // "Battery B", // 10
206  { 0, 0, 0, ID_of(batteryPercent), },// "Battery Percent", // 11
207  { offsetof(Settings,batt_warn_level), sizeof(sets.batt_warn_level),'b', 0, }, // "Battery Warning Level", // 12
208  { offsetof(Settings,OSD_CALL_SIGN), sizeof(sets.OSD_CALL_SIGN), 'c', 0, }, // "Call Sign", // 13
209  { offsetof(Settings,switch_mode), sizeof(sets.switch_mode), 'b', 0, }, // "Chanel Rotation Switching", // 14
210  { 0, 0, 0, ID_of(ch), }, // "Channel Raw", // 15
211  { 0, 0, 0, ID_of(Scale), }, // "Channel Scale", // 16
212  { 0, 0, 0, ID_of(State), }, // "Channel state", // 17
213  { 0, 0, 0, ID_of(CValue), }, // "Channel Value", // 18
214 
215  { 0, 0, 0, 0, }, // "Configuration", // 19
216  { 0, 0, 0, ID_of(curr_A), }, // "Current", // 20
217  { offsetof(Settings,eCurrent_koef), sizeof(sets.eCurrent_koef), 'f', 0, }, // "curr_k", // 21
218  { 0, 0, 0, ID_of(eff), }, // "Efficiency", // 22
219  { 4, m1, 0, 0, }, // "fBattA", // 23
220  { 5, m1, 0, 0, }, // "fBattB", // 24
221  { 6, m1, 0, 0, }, // "fCurr", // 25
222  { 0, 0, 0, 0, }, // 26
223  { 0, 0, 0, 0, }, // 27
224  { 0, m1, 0, 0, }, // "flgOnce", // 28
225  { 0, 0, 0, 0, }, //29
226  { 0, 0, 0, ID_of(Fdata), }, // "Flight Data", // 30
227  { 0, 0, 0, ID_of(FMod), }, // "Flight Mode", // 31
228  { 0, 0, 0, 0, }, // "fRussianHUD", // 32
229  { 0, 0, 0, ID_of(GPS), }, // "GPS Coord", // 33
230  { 0, 0, 0, ID_of(Hdop), }, // "GPS HDOP", // 34
231  { 0, 0, 0, ID_of(heading), }, // "Heading", // 35
232  { 0, 0, 0, ID_of(rose), }, // "Heading Rose", // 36
233  { 0, 0, 0, ID_of(homeAlt), }, // "Home Altitude", // 37
234  { 0, 0, 0, ID_of(homeDir), }, // "Home Direction", // 38
235  { 0, 0, 0, ID_of(homeDist), }, // "Home Distance", // 39
236  { 0, 0, 0, ID_of(horizon), }, // "Horizon", // 40
237  { offsetof(Settings,horiz_offs), sizeof(sets.horiz_offs), 'b', 0, }, // "HOS", // 41
238  { 0, 0, 0, ID_of(message), }, // "Message", // 42
239  { offsetof(Settings,model_type), sizeof(sets.model_type), 'b', 0, }, // "Model Type", // 43
240  { offsetof(Settings,n_screens), sizeof(sets.n_screens), 'b', 0, }, // "NSCREENS", // 44
241  { offsetof(Settings,OSD_BRIGHTNESS), sizeof(sets.OSD_BRIGHTNESS),'b', 0, }, // "OSD Brightness", // 45
242  { offsetof(Settings,overspeed), sizeof(sets.overspeed), 'b', 0, }, // "Overspeed", // 46
243 
244  { 0, 0, 0, 0, }, // "Panel", // 47
245  { 0, 0, 0, ID_of(pitch), }, // "Pitch", // 48
246  { offsetof(Settings,horiz_kPitch), sizeof(sets.horiz_kPitch), 'f', 0, }, // "pitch_k", // 49
247  { offsetof(Settings,horiz_kPitch_a), sizeof(sets.horiz_kPitch_a),'f', 0, }, // "pitch_kn", // 50
248  { offsetof(Settings,pwm_dst), sizeof(sets.pwm_dst), 'b', 0, }, // "PWMDST", // 51
249  { offsetof(Settings,pwm_src), sizeof(sets.pwm_src), 'b', 0, }, // "PWMSRC", // 52
250  { 0, 0, 0, ID_of(RadarScale), }, // "Radar Scale", // 53
251  { 0, 0, 0, ID_of(COG), }, // "Real heading", // 54
252  { 0, 0, 0, ID_of(roll), }, // "Roll", // 55
253  { offsetof(Settings,horiz_kRoll), sizeof(sets.horiz_kRoll), 'f', 0, }, // "roll_k", // 56
254  { offsetof(Settings,horiz_kRoll_a), sizeof(sets.horiz_kRoll_a), 'f', 0, }, // "roll_kn", // 57
255  { 0, 0, 0, ID_of(RSSI), }, // "RSSI", // 58
256  { offsetof(Settings,RSSI_raw), sizeof(sets.RSSI_raw), 'b', 0, }, // "RSSI Enable Raw", // 59
257  { offsetof(Settings,RSSI_16_high), sizeof(sets.RSSI_16_high), 'w', 0, }, // "RSSI High", // 60
258  { offsetof(Settings,eRSSI_koef), sizeof(sets.eRSSI_koef), 'f', 0, }, // "rssi_k", // 61
259  { offsetof(Settings,RSSI_16_low), sizeof(sets.RSSI_16_low), 'w', 0, }, // "RSSI Low", // 62
260  { offsetof(Settings,rssi_warn_level),sizeof(sets.rssi_warn_level),'b', 0, }, // "RSSI Warning Level", // 63
261  { 0, 0, 0, 0, }, // "SAdd1", // 64 // sensors not supported
262  { 0, 0, 0, 0, }, // "SAdd2", // 65
263  { 0, 0, 0, 0, }, // "SAdd3", // 66
264  { 0, 0, 0, 0, }, // "SAdd4", // 67
265  { 0, 0, 0, ID_of(sensor1), }, // "Sensor 1", // 68
266  { 0, 0, 0, ID_of(sensor2), }, // "Sensor 2", // 69
267  { 0, 0, 0, ID_of(sensor3), }, // "Sensor 3", // 70
268  { 0, 0, 0, ID_of(sensor4), }, // "Sensor 4", // 71
269  { 0, 0, 0, 0, }, // "SFactor1", // 72
270  { 0, 0, 0, 0, }, // "SFactor2", // 73
271  { 0, 0, 0, 0, }, // "SFactor3", // 74
272  { 0, 0, 0, 0, }, // "SFactor4", // 75
273  { 0, 0, 0, 0, }, // "SFormat1", // 76
274  { 0, 0, 0, 0, }, // "SFormat2", // 77
275  { 0, 0, 0, 0, }, // "SFormat3", // 78
276  { 0, 0, 0, 0, }, // "SFormat4", // 79
277  { offsetof(Settings,stall), sizeof(sets.stall), 'b', 0, }, // "Stall", // 80
278  { 0, 0, 0, ID_of(temp), }, // "Temperature", // 81
279  { 0, 0, 0, ID_of(throttle), }, // "Throttle", // 82
280  { 0, 0, 0, ID_of(time), }, // "Time", // 83
281  { offsetof(Settings,ch_toggle), sizeof(sets.ch_toggle), 'b', 0, }, // "Toggle Channel", // 84
282  { 0, 0, 0, ID_of(distance), }, // "Trip Distance", // 85
283  { 0, 0, 0, ID_of(tune), }, // "Tune", // 86
284  { 0, 0, 0, 0, }, // "txtTime0", // 87
285  { 0, 0, 0, 0, }, // "txtTime1", // 88
286  { 0, 0, 0, 0, }, // "txtTime2", // 89
287  { 0, 0, 0, 0, }, // "txtTime3", // 90
288  { 1, m1, 0, 0, }, // "Units", // 91
289  { 0, 0, 0, ID_of(vel), }, // "Velocity", // 92
290  { 0, 0, 0, ID_of(climb), }, // "Vertical Speed", // 93
291  { 3, m1, 0, 0, }, // "Video Mode", // 94
292  { 0, 0, 0, ID_of(GPS_sats), }, // "Visible Sats", // 95
293  { offsetof(Settings,vert_offs), sizeof(sets.vert_offs), 'b', 0, }, // "VOS", // 96
294  { 0, 0, 0, ID_of(warn), }, // "Warnings", // 97
295  { 0, 0, 0, ID_of(windSpeed), }, // "Wind Speed", // 98
296  { 0, 0, 0, ID_of(WP_dir), }, // "WP Direction", // 99
297  { 0, 0, 0, ID_of(WP_dist), }, // "WP Distance", // 100
298  { 0, 0, 0, 0, }, // #
299  { 0, 0, 0, ID_of(Power), }, // "Power", // 102
300  { 0, 0, 0, ID_of(fDate), }, // "Date", // 103
301  { 0, 0, 0, ID_of(dayTime), }, // "Time of day", // 104
302  { 0, 0, 0, ID_of(pMotor), }, // "Motors", // 105
303  { 0, 0, 0, ID_of(fVibe), }, // "Vibrations", // 106
304  { 0, 0, 0, ID_of(fVario), }, // "Variometer", // 107
305  { 0, 0, 0, ID_of(coordLat), }, // "GPS Coord Lat", // 108
306  { 0, 0, 0, ID_of(coordLon), }, // "GPS Coord Lon", // 109
307 
308 };
309 
310 static ring_buffer osd_rxrb IN_CCM;
311 static uint8_t osd_rx_buf[OSD_RX_BUF_SIZE] IN_CCM;
312 
313 static ring_buffer osd_txrb IN_CCM;
314 static uint8_t osd_tx_buf[OSD_TX_BUF_SIZE] IN_CCM;
315 
317 AP_HAL::Semaphore *osd_spi_sem;
318 
319 //static volatile byte vas_vsync=false;
320 
321 mavlink_system_t mavlink_system = {12,1}; // sysid, compid
322 
323 
324 #ifdef OSD_DMA_TRANSFER
325  #define DMA_BUFFER_SIZE 510
326  static uint8_t dma_buffer[DMA_BUFFER_SIZE+1]; // in RAM for DMA
327  static uint16_t dma_transfer_length IN_CCM;
328 
329 static uint8_t shadowbuf[sizeof(OSD::osdbuf)] IN_CCM;
330 
331 #endif
332 
333 static bool diff_done;
334 
335 
336 extern void heartBeat();
337 extern void writePanels();
338 
339 void On100ms();
340 void On20ms() {}
341 void osd_loop();
342 void vsync_ISR();
343 void max_do_transfer(const char *buffer, uint16_t len);
344 
345 static void max7456_cs_off(){
346  osd_spi->wait_busy(); // wait for transfer complete
347 
350 
351  delay_ns100(3);
352 }
353 
354 static void max7456_cs_on(){
357  delay_ns100(1);
358 }
359 
360 
361 static uint32_t sem_count=0;
362 
363 void max7456_on(){
364 
365  max7456_cs_on();
366 
368 }
369 
370 static void max7456_sem_on(){
371 
372  if(osd_spi_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
373  max7456_on();
374  }
375 }
376 
377 void max7456_off(){
378  max7456_cs_off();
379 }
380 
381 static void max7456_sem_off(){
382  max7456_off();
383  osd_spi_sem->give(); // give sem on last count
384 }
385 
386 void MAX_write(byte addr, byte data){
387  max7456_cs_on();
388  osd_spi->transfer(addr); // this transfer don't controls CS
389  osd_spi->transfer(data);
390  max7456_cs_off();
391 }
392 
393 byte MAX_read(byte addr){
394  max7456_cs_on();
395  osd_spi->transfer(addr); // this transfer don't controls CS
396  uint8_t ret = osd_spi->transfer(0xff);
397  max7456_cs_off();
398  return ret;
399 }
400 
401 byte MAX_rw(byte b){
402  max7456_cs_on();
403  uint8_t ret=osd_spi->transfer(b);
404  max7456_cs_off();
405  return ret;
406 }
407 
408 static uint16_t rdb_ptr IN_CCM;
409 
410 
411 #ifdef OSD_DMA_TRANSFER
412 static void prepare_dma_buffer(){
413  uint16_t rp;
414  uint16_t wp=0;
415 
416  uint8_t last_h=0xff;
417 
418 // MAX_write(MAX7456_DMM_reg, 0);
419 // MAX_write(MAX7456_VM1_reg, B01000111);
420 
421  memset(dma_buffer,0xff,sizeof(dma_buffer));
422 
423  dma_buffer[wp++] = MAX7456_DMM_reg; dma_buffer[wp++] = 0;
424  dma_buffer[wp++] = MAX7456_VM1_reg; dma_buffer[wp++] = B01000111;
425 
426 
427  // сначала все изменения
428  for(rp=0; rp<MAX7456_screen_size ; rp++){
429  uint8_t c = OSD::osdbuf[rp];
430  if(c != shadowbuf[rp] ){
431  if(wp>=DMA_BUFFER_SIZE-6) break;
432  uint8_t h = rp>>8;
433  if(last_h != h){
434  last_h = h;
435  dma_buffer[wp++] = MAX7456_DMAH_reg; dma_buffer[wp++] = h;
436  if(wp>=DMA_BUFFER_SIZE-6) break;
437  }
438 
439  dma_buffer[wp++] = MAX7456_DMAL_reg; dma_buffer[wp++] = rp&0xFF;
440  dma_buffer[wp++] = MAX7456_DMDI_reg; dma_buffer[wp++] = c;
441  shadowbuf[rp] = c;
442  }
443  }
444 
445  // а в оставшееся место все остальное по кольцу. таким образом пересылка у нас всегда 500 байт, и на частоте 4.5МГц занимает ~1ms.
446  // длинные пересылки имеют низкий приоритет, и никому не мешают
447  while(wp<DMA_BUFFER_SIZE-6){
448  uint8_t c = OSD::osdbuf[rdb_ptr];
449  uint8_t h = rdb_ptr>>8;
450  if(last_h != h){
451  last_h = h;
452  dma_buffer[wp++] = MAX7456_DMAH_reg; dma_buffer[wp++] = h;
453  if(wp>=DMA_BUFFER_SIZE-6) break;
454  }
455 
456  dma_buffer[wp++] = MAX7456_DMAL_reg; dma_buffer[wp++] = rdb_ptr&0xFF;
457  dma_buffer[wp++] = MAX7456_DMDI_reg; dma_buffer[wp++] = c;
458  shadowbuf[rdb_ptr] = c;
459  rdb_ptr++;
460  if(rdb_ptr >= MAX7456_screen_size) rdb_ptr=0; // loop
461  }
462 
463 // dma_buffer[wp++] = MAX7456_VM0_reg; dma_buffer[wp++] = MAX7456_ENABLE_display | MAX7456_SYNC_autosync | OSD::video_mode;
464 
465  dma_transfer_length = wp;
466  diff_done = true;
467 }
468 #endif
469 
470 
471 uint32_t get_word(char *buf, char * &ptr){
472  uint32_t sel_len=0;
473  uint8_t sel_id=0;
474 
475  for(uint32_t i=0; i<ARRAY_SIZE(words); i++){
476  uint32_t len=strlen(words[i]);
477  if(strncmp(buf, words[i],len)==0){
478  if(len > sel_len) { // longest match
479  sel_len = len;
480  sel_id = i+1;
481  }
482  }
483  }
484  ptr=buf+sel_len;
485  return sel_id;
486 }
487 
488 char * get_lex(char * &ptro){
489  char *ptr;
490  char *buf = ptro;
491  while(*buf && (*buf=='\t' || *buf == ' ')) buf++;
492  ptr=buf;
493  while(*ptr && *ptr!='\t') ptr++;
494  if(*ptr==0) {
495  ptro=NULL;
496  } else {
497  *ptr=0;
498  ptro=ptr+1;
499  }
500  return buf;
501 
502 }
503 
504 static bool get_flag(char *p) {
505  if(!p) return false;
506 
507  if(*p=='T' || *p=='t' || *p=='1') return true;
508  return false;
509 }
510 
511 // x, y, vis, sign, Altf, Alt2, Alt3, Alt4, strings
512 // 30 15 False 0 1 1 1 1 A||||
513 static point create_point(char *px, char *py, char *pVis, char *pSign, char *pAlt, char *pAlt2, char *pAlt3, char *pAlt4, char *ps ){
514  point p;
515  p.x = strtoul(px, nullptr, 10);
516  p.y = strtoul(py, nullptr, 10);
517  p = do_on(p, get_flag(pVis));
518  p = do_sign(p, get_flag(pSign));
519  if(get_flag(pAlt)) p=do_alt(p);
520  if(get_flag(pAlt2)) p=do_alt2(p);
521  if(get_flag(pAlt3)) p=do_alt3(p);
522  if(get_flag(pAlt4)) p=do_alt4(p);
523 
524 // if(ps) collect_strings(ps); not supported
525  return p;
526 }
527 
528 #define write_point(n,p) eeprom_write_len((byte *)&p, OffsetBITpanel * (int)panel_num + n * sizeof(Point), sizeof(Point) );
529 
530 static void load_config(){
531  File fd = SD.open("eeprom.osd", FILE_READ);
532  if (fd) {
533  printf("\nLoading OSD config\n");
534  char buf[80];
535 // memset(buf, 0, sizeof(buf));
536  uint32_t panel_num=-1;
537  bool is_config=false;
538 
539  while(fd.gets(buf, sizeof(buf)-1) > 0) {
540  // we readed one line
541  char *ptr;
542  char *p[10];
543 
544  uint8_t word=get_word(buf,ptr);
545  switch(word) {
546  case 0: // not found
547  case 101: // #
548  continue;
549 
550  case 47: { // panel
551  char *p2 = get_lex(ptr);
552  panel_num=strtoul(p2, nullptr, 10);
553  uint16_t flags=strtoul(ptr, nullptr, 10);
554  write_point(0,flags);
555  }break;
556 
557  case 19: // config
558  is_config=true;
559  break;
560 
561  default:
562  char **pp = p;
563  memset(p,0,sizeof(p));
564  do {
565  *pp++ = get_lex(ptr);
566  }while(ptr);
567 
568 
569  if(is_config){
570  if(pan_tbl[word].size == (uint8_t)-1){ // bit flags
571  uint32_t flags = sets.flags.dw;
572  if(get_flag(p[0])) flags |= (1<<pan_tbl[word].dst);
573  else flags &= ~(1<<pan_tbl[word].dst);
574  sets.flags.dw=flags;
575  } else {
576  union {
577  float f;
578  uint8_t b;
579  char buf[8];
580  uint16_t w;
581  } val;
582 
583  switch(pan_tbl[word].fmt){
584  case 'f': // float
585  val.f = atof(p[0]);
586  break;
587  case 'b': // byte
588  val.b=(uint8_t)strtoul(p[0], nullptr, 10);
589  break;
590  case 'c': // char
591  strncpy(val.buf, p[0], 8);
592  break;
593  case 'w':
594  val.w=(uint16_t)strtoul(p[0], nullptr, 10);
595  break;
596  default:
597  continue; // ignore this line
598  }
599  memmove( ((uint8_t*)(&sets)) + pan_tbl[word].dst, &val, pan_tbl[word].size);
600  eeprom_write_len(((uint8_t*)(&sets)) + pan_tbl[word].dst, EEPROM_offs(sets) + pan_tbl[word].dst, pan_tbl[word].size);
601  }
602  }else{ // panel
603  uint8_t id = pan_tbl[word].pan_n;
604  if(id) {
605  // 30 15 False 0 1 1 1 1 A||||
606  point po=create_point(p[0], p[1], p[2], p[3], p[4], p[5], p[6], p[7], p[8] );
607 
608  write_point(id, po); // save to eeprom
609  }
610  }
611 
612  break;
613  }
614 
615  }
616  fd.close();
617 
618  // we don't save flags when parsing so lets do it now
619  eeprom_write_len( &sets.flags.pad[0], EEPROM_offs(sets) + ((byte *)&sets.flags.pad - (byte *)&sets), sizeof(sets.flags.pad));
620 
621  readSettings(); // re-read new values back, for settings that not in config.osd get all-1 state
622 
623  sets.CHK1_VERSION = VER; // set version - EEPROM OK
624  sets.CHK2_VERSION = (VER ^ 0x55);
625  eeprom_write_len( &sets.CHK1_VERSION, EEPROM_offs(sets) + ((byte *)&sets.CHK1_VERSION - (byte *)&sets), 2 );
626  }
627 }
628 
629 static void load_font(){
630  const char font[]="font.mcm";
631  File fd = SD.open(font, FILE_READ);
632  if (fd) {
633  char buf[80];
634 
635  if(fd.gets(buf, sizeof(buf)-1)){
636  printf("\nLoading OSD font\n");
637 
638  OSD::setPanel(5, 5);
639  osd_print_S(PSTR("font uploading "));
640  OSD::update();// Show it
641 
642  char patt[]="MAX7456";
643 
644  if(strncmp(buf,patt,strlen(patt))==0){
645  uint8_t character_bitmap[0x40];
646 
647  uint16_t font_count = 0;
648  byte byte_count = 0;
649  byte bit_count=0;
650 
651  uint8_t chk=0;
652  uint8_t c=0;
653  uint8_t last_c;
654 
655  uint8_t b=0;
656 
657  uint8_t cnt=0;
658  while(font_count < 256) {
659  last_c = c;
660  if(fd.read(&c,1)<=0) break; // get a char
661 
662  switch(c){ // parse and decode mcm file
663  case 0x0A: // line feed - skip
664  if(last_c == 0x0d) continue;
665  // lf without cr cause line end
666 
667  case 0x0d: // carridge return, end of line
668  if (bit_count == 8) {
669  chk ^= b;
670  character_bitmap[byte_count] = b;
671  b = 0;
672  byte_count++;
673  }
674  bit_count = 0;
675  break;
676 
677  case 0x30: // ascii '0'
678  case 0x31: // ascii '1'
679  b <<= 1;
680  if(c == 0x31)
681  b += 1;
682  bit_count++;
683 
684  break;
685 
686  default:
687  break;
688  }
689 
690  // we have one completed character
691  // write the character to NVM
692  if(byte_count == 64) {
693  osd.write_NVM(font_count, character_bitmap);
694  byte_count = 0;
695  font_count++;
696  printf(".");
697  chk=0;
698  }
699  }
700  printf("done\n");
701  }
702  }
703 
704  fd.close();
705 //* not in debug mode
706  SD.remove(font); // once!
707 //*/
708  }
709 
710 }
711 
712 static bool osd_need_redraw = false;
713 static void * task_handle;
714 
715 // slowly write all buffer
716 static void write_buff_to_MAX(bool all){
717 
718  max7456_on();
719  MAX_write(MAX7456_DMM_reg, 0);
720 
721  // clear internal memory
722  uint8_t old_h=0xff;
723  for(uint16_t len = MAX7456_screen_size, cnt=0;len--; cnt++){
724  uint8_t c= OSD::osdbuf[cnt];
725  if(all || c!=0x20) {
726  max7456_cs_on();
727  uint8_t h = cnt>>8;
728  if(old_h!=h){
729  MAX_write(MAX7456_DMAH_reg, h);
730  old_h = h;
731  }
732  MAX_write(MAX7456_DMAL_reg, cnt&0xFF);
733  MAX_write(MAX7456_DMDI_reg, c);
734  max7456_cs_off();
735  }
736 #ifdef OSD_DMA_TRANSFER
737  shadowbuf[cnt] = c;
738 #endif
739  }
740  max7456_off();
741 }
742 
743 
744 
746 
747  osd_spi = std::move(spi);
748 
749  osd_spi_sem = osd_spi->get_semaphore(); // bus semaphore
750  {
755  }
756 
757 #ifdef BOARD_OSD_RESET_PIN
758  {
763  delayMicroseconds(50);
765  delayMicroseconds(120);
766  }
767 #endif
768 
769 
770  rb_init(&osd_rxrb, OSD_RX_BUF_SIZE, osd_rx_buf);
771  rb_init(&osd_txrb, OSD_TX_BUF_SIZE, osd_tx_buf);
772 
774 
775  // clear memory
776  memset(OSD::osdbuf,0x20, sizeof(OSD::osdbuf));
777 #ifdef OSD_DMA_TRANSFER
778  memset(shadowbuf, 0x20, sizeof(shadowbuf));
779 #endif
780 
781 /*
782  lets try to load settings from SD card
783 */
784  load_config();
785 
786  readSettings();
787 
788  doScreenSwitch(); // set vars for startup screen
789 
790  if( sets.CHK1_VERSION != VER || sets.CHK2_VERSION != (VER ^ 0x55)) { // wrong version
791  lflags.bad_config=1;
792 
793  // some useful defaults
794  sets.OSD_BRIGHTNESS = 2;
795  sets.horiz_offs = 0x20;
796  sets.vert_offs = 0x10;
797 
798  }
799 
800  while(millis()<1000) { // delay initialization until video stabilizes
801  hal_yield(1000);
802  }
803 
804  max7456_sem_on();
805 
806  write_buff_to_MAX(true);
807 
808 
809  for(uint8_t i=0; i<100; i++) {
810  osd.init(); // Start display
811 
812  max7456_on();
813  uint8_t vm0 = MAX_read(MAX7456_VM0_reg | MAX7456_reg_read); // check register
814  max7456_off();
815 
816  uint8_t patt = MAX7456_ENABLE_display | MAX7456_SYNC_autosync | OSD::video_mode;
817 
818  if(vm0==patt) break;
819  }
820 
821  max7456_off();
822 
823  load_font();
824 
825  max7456_sem_off();
826 
827 #define REL_1 int(RELEASE_NUM/100)
828 #define REL_2 int((RELEASE_NUM - REL_1*100 )/10)
829 #define REL_3 int((RELEASE_NUM - REL_1*100 - REL_2*10 ))
830 
831  if(sets.FW_VERSION[0]!=(REL_1 + '0') || sets.FW_VERSION[1]!=(REL_2 + '0') || sets.FW_VERSION[2]!=(REL_3 + '0') ){
832  sets.FW_VERSION[0]=REL_1 + '0';
833  sets.FW_VERSION[1]=REL_2 + '0';
834  sets.FW_VERSION[2]=REL_3 + '0';
835 
836  eeprom_write_len( sets.FW_VERSION, EEPROM_offs(sets) + ((uint8_t *)sets.FW_VERSION - (uint8_t *)&sets), sizeof(sets.FW_VERSION) );
837  }
838 
839  logo();
840 
841 
842 #ifdef BOARD_OSD_VSYNC_PIN
843  Revo_hal_handler h = { .vp = vsync_ISR };
844 
846 #endif
847 
849  Scheduler::set_task_priority(task_handle, OSD_LOW_PRIORITY); // less than main task
850  Scheduler::set_task_period(task_handle, 10000); // 100Hz
851 }
852 
853 // all task is in one thread so no sync required
854 
855 void osd_loop() {
856  if(osd_need_redraw){ // если была отложенная передача
857  osd_need_redraw=false;
858 
859  OSD::update();
860  Scheduler::set_task_priority(task_handle, OSD_LOW_PRIORITY); // restore priority to low
861  }
862 
863  uint32_t pt=millis();
864 
865  seconds = pt / 1000;
866 
867  osd_dequeue(); // we MUST parse input even in case of bad config because it is the only way to communicate
868 
869  if(pt < BOOTTIME || lflags.bad_config){ // startup delay for fonts or EEPROM error
870  logo();
871  return;
872  }
873 
874 #if defined(MAV_REQUEST) && (defined(USE_MAVLINK) || defined(USE_MAVLINKPX4))
875  if(apm_mav_system && !lflags.mav_request_done){ // we got HEARTBEAT packet and still don't send requests
876  for(uint8_t n = 3; n >0; n--){
877  request_mavlink_rates(); //Three times to certify it will be readed
878  delay_150();
879  }
880  lflags.mav_request_done=1;
881  }
882 #endif
883 
884  if(lflags.got_data){ // if new data comes
885 
886  pan_toggle(); // check for screen toggle
887 
888  if(!lflags.need_redraw) {
889  lflags.need_redraw=1;
890  vsync_wait=1; // will wait for interrupt
891  }
892 
893  lflags.got_data=0; // data parsed
894  }
895 
896  if( lflags.need_redraw) {
897  lflags.need_redraw=0; // screen drawn
898 
899  setHomeVars(); // calculate and set Distance from home and Direction to home
900 
901  setFdataVars(); // statistics and min/max
902 
903  writePanels(); // writing enabled panels (check OSD_Panels Tab)
904 
905 #ifdef OSD_DMA_TRANSFER
906  prepare_dma_buffer(); // prepare diff with addresses
907 #endif
908 
909  update_screen = 1; // data comes, wee need to redraw screen
910  }
911 
912  if(pt > timer_20ms){
913  timer_20ms+=20;
914  On20ms();
915 
916  if(update_screen && vsync_wait && (millis() - vsync_time)>50){ // interrupts stopped - more than 50 ms passed from the last one
917  vsync_wait=0; // хватит ждать
918  Scheduler::set_task_priority(task_handle, OSD_HIGH_PRIORITY); // equal to main
919  OSD::update(); // update compulsorily (and then update every 20ms)
920  update_screen = 0;
921  Scheduler::set_task_priority(task_handle, OSD_LOW_PRIORITY);
922  }
923  }
924 
925  if(pt > timer_100ms){
926  timer_100ms+= 100;
927  On100ms();
928 
929  lflags.flag_01s = !lflags.flag_01s;
930 
931  if(lflags.flag_01s) {
932 
933  if(skip_inc) {
934  skip_inc++;
935 
936  if(skip_inc >=3){
937  count02s++;
938  skip_inc=0; // we go again
939  }
940 
941  } else
942  count02s++;
943  }
944 // count01s++;
945  }
946 
947  if(pt > timer_500ms){
948  timer_500ms+= 500;
949  lflags.got_data=1; // every half second forcibly
950  update_screen = 1;
951 
952  lflags.flag_05s = 1;
953 
954  count05s++;
955 
956  lflags.blinker = !lflags.blinker;
957  if(lflags.blinker) {
958  // seconds++;
959  lflags.one_sec_timer_switch = 1; // for warnings
960 
961  if(lflags.got_date) day_seconds++; // if we has GPS time - let it ticks
962 
963  if( vas_vsync && vsync_count < 5) { // at a frame rate they should be 25 or 50
964  // but there are boards where this pin is not connected. China...
965  max7456_err_count++;
966  if(max7456_err_count>3) { // 3 seconds bad sync
967 #ifdef DEBUG
968  printf(PSTR("restart MAX! vsync_count=%d\n"),vsync_count);
969 #endif
970  osd.reset(); // restart MAX7456
971  }
972  } else max7456_err_count=0;
973 
974  vsync_count=0;
975 
976  heartBeat();
977  }
978  }
979 }
980 
981 float avgRSSI(uint16_t d){
982  static uint8_t ind = -1;
983  static uint16_t RSSI_rawArray[8];
984 
985  RSSI_rawArray[(++ind)%8] = d;
986  d=0;
987  for (uint8_t i=8;i!=0;)
988  d += RSSI_rawArray[--i];
989 
990  return d/8.0;
991 }
992 
993 void On100ms() {
994 
995  byte ch = sets.RSSI_raw / 2;
996 
997  uint16_t d;
998 
999 
1000 //DBG_PRINTF("\n RSSI ch=%d ", ch);
1001 
1002  switch(ch) {
1003 
1004  case 1: // analog RSSI from pin
1005  case 2: // digital RSSI from pin
1006 
1007  case 0:
1008  d=osd_rssi; // mavlink
1009  goto case_4;
1010 
1011  case 3: // 3dr modem rssi
1012  d=telem_rssi;
1013  goto case_4;
1014 
1015  case 4:
1016  default:
1017  d = chan_raw[7]; // ch 8
1018 
1019 //DBG_PRINTF("ch8_rssi=%d\n", d );
1020 
1021 case_4:
1022  rssi_in = avgRSSI(d);
1023 
1024 // RSSI source is not pin so we can read it for sensor
1025 #if defined(USE_SENSORS)
1026  if(SENSOR4_ON) {
1027  if(fPulseSensor[3])
1028  d=pulseIn(RssiPin,HIGH,10000);
1029  else
1030  d=analogRead(RssiPin);
1031 
1032  sensorData[3] = (sensorData[3]*7 + d) /8;
1033  }
1034 #endif
1035  break;
1036  }
1037 }
1038 
1039 
1040 void vsync_ISR(){
1041  vas_vsync=true;
1042  vsync_wait=0; // note its presence
1043 
1044  vsync_count++; // count VSYNC interrupts
1045  vsync_time=millis(); // and note a time
1046 
1047  if(update_screen) { // there is data for screen
1048  osd_need_redraw=true;
1049  Scheduler::set_task_priority(task_handle, OSD_HIGH_PRIORITY); // higher than all drivers so it will be scheduled just after semaphore release
1050  Scheduler::task_resume(task_handle); // task should be finished at this time so resume it
1051  update_screen = 0;
1052  }
1053 }
1054 
1055 
1056 
1057 // is there any chars in ring buffer?
1058 int16_t osd_available(){
1059  return rb_full_count(&osd_rxrb);
1060 }
1061 
1062 void osd_queue(uint8_t c) { // push bytes from OSD to FC around in the ring buffer
1063  uint8_t cnt=10;
1064  while(rb_is_full(&osd_rxrb)) {
1065  hal_yield(0);
1066  if(--cnt == 0) return; // destination don't listen
1067  }
1068  rb_push_insert(&osd_rxrb, c);
1069 }
1070 
1071 
1072 int16_t osd_getc(){ // get char from ring buffer
1073  return rb_remove(&osd_rxrb);
1074 }
1075 
1076 uint32_t osd_txspace() {
1077  return osd_txrb.size - rb_full_count(&osd_txrb);
1078 }
1079 
1080 
1081 void osd_putc(uint8_t c){
1082  uint8_t cnt=10;
1083  while(rb_is_full(&osd_txrb)) {
1084  Scheduler::set_task_priority(task_handle, OSD_HIGH_PRIORITY); // to run in time of yield()
1085  hal_yield(0);
1086  if(--cnt == 0) break; // destination don't listen
1087  }
1088  rb_push_insert(&osd_txrb, c);
1089  Scheduler::set_task_priority(task_handle, OSD_LOW_PRIORITY); // restore priority to low
1090 }
1091 
1092 void osd_dequeue() {
1093  Scheduler::set_task_priority(task_handle, 100); // equal to main to not overflow buffers on packet decode
1094 
1095  while(!rb_is_empty(&osd_txrb)) {
1096  extern bool mavlink_one_byte(char c);
1097  char c = rb_remove(&osd_txrb);
1098 
1099  if(mavlink_one_byte(c)) lflags.got_data=true;
1100  }
1101  Scheduler::set_task_priority(task_handle, OSD_LOW_PRIORITY); // restore priority to low
1102 
1103 }
1104 
1105 
1106 static uint8_t max_err_cnt=0;
1107 
1108 void update_max_buffer(const uint8_t *buffer, uint16_t len){
1109  max7456_sem_on();
1110 
1111  uint16_t cnt=0;
1112 
1113 
1114 #if 1
1115  uint8_t patt = MAX7456_ENABLE_display | MAX7456_SYNC_autosync | OSD::video_mode;
1116  max7456_cs_on();
1117  uint8_t vm0 = MAX_read(MAX7456_VM0_reg | MAX7456_reg_read);
1118 
1119  if(vm0 != patt) {
1120  max_err_cnt++;
1121  if(max_err_cnt<3) {
1122  OSD::hw_init(); // first try without reset
1123  } else {
1124  // 3 errors together - nothing helps :(
1125 #ifdef BOARD_OSD_RESET_PIN
1126  {
1129  delayMicroseconds(50);
1131  delayMicroseconds(120);
1132  }
1133 #endif
1134  OSD::init();
1135  max_err_cnt=0;
1136  }
1137  } else {
1138  max_err_cnt=0;
1139  }
1140 
1141  MAX_write(MAX7456_DMAH_reg, 0);
1142  MAX_write(MAX7456_DMAL_reg, 0);
1143  MAX_write(MAX7456_DMM_reg, 1); // set address auto-increment
1144 
1145  max7456_cs_off();
1146 
1147  if(osd_spi->send_strobe(buffer, len)!=len) {
1148  /*/// for debug - mark last written char
1149  MAX_rw(0x86); // finish transfer
1150  //*///
1151  MAX_rw(0xff); // finish transfer
1152  }
1153 
1154 #elif 0
1155  MAX_write(MAX7456_DMAH_reg, 0);
1156  MAX_write(MAX7456_DMAL_reg, 0);
1157  MAX_write(MAX7456_DMM_reg, 0);
1158 
1159 // try to send just diffenence - don't clears last chars
1160  uint8_t last_h=0;
1161  while(len--){
1162  if(*buffer != shadowbuf[cnt]){
1163  uint8_t h = cnt>>8 ;
1164  if(last_h != h){
1165  MAX_write(MAX7456_DMAH_reg, h);
1166  last_h = h;
1167  }
1168  MAX_write(MAX7456_DMAL_reg, cnt&0xFF);
1169  MAX_write(MAX7456_DMDI_reg, *buffer);
1170  shadowbuf[cnt] = *buffer;
1171  }
1172  buffer++;
1173  cnt++;
1174  }
1175 
1176 #elif 0
1177 
1178 // a try to do writes in software strobe mode
1179  MAX_write(MAX7456_DMAH_reg, 0);
1180  MAX_write(MAX7456_DMAL_reg, 0);
1181  MAX_write(MAX7456_DMM_reg, 1); // set address auto-increment
1182  max7456_cs_off();
1183  while(len--){
1184  max7456_cs_on();
1185  // osd_spi->transfer(*buffer++); MAX7456
1186  MAX_rw(*buffer++);
1187  buffer++;
1188  cnt++;
1189  osd_spi->wait_busy();
1190  max7456_cs_off();
1191  }
1192  max7456_cs_on();
1193  MAX_write(MAX7456_DMM_reg, 0); // clear address auto-increment
1194 #else
1195 // just write all to MAX
1196  MAX_write(MAX7456_DMAH_reg, 0);
1197  MAX_write(MAX7456_DMAL_reg, 0);
1198  MAX_write(MAX7456_DMM_reg, 0);
1199 
1200  uint8_t last_h=0;
1201  while(len--){
1202  uint8_t h = cnt>>8 ;
1203  if(last_h != h){
1204  MAX_write(MAX7456_DMAH_reg, h);
1205  last_h = h;
1206  }
1207 
1208  MAX_write(MAX7456_DMAL_reg, cnt&0xFF);
1209  MAX_write(MAX7456_DMDI_reg, *buffer);
1210  buffer++;
1211  cnt++;
1212  }
1213 
1214 #endif
1215 
1216  max7456_sem_off();
1217 }
1218 
1219 
1220 
1221 } // namespace
1222 
1223 
1224 #endif
void osd_putc(uint8_t c)
int printf(const char *fmt,...)
Definition: stdio.c:113
void osd_dequeue()
void setFdataVars()
#define PSTR(x)
Definition: compat.h:27
F4Light::Semaphore * get_semaphore()
Definition: SPIDevice.h:143
#define BOOTTIME
Definition: Config.h:38
void osd_queue(uint8_t c)
static void osd_print_S(PGM_P f)
Definition: Config_Func.h:46
static void delayMicroseconds(uint16_t us)
Definition: compat.h:82
#define BOARD_OSD_RESET_PIN
Definition: board.h:149
void max7456_on()
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
static int rb_is_empty(ring_buffer *rb)
Returns true if and only if the ring buffer is empty.
Definition: ring_buffer.h:109
uint16_t send_strobe(const uint8_t *buffer, uint16_t len)
Definition: SPIDevice.cpp:847
static void set_task_priority(void *h, uint8_t prio)
Definition: Scheduler.h:282
void heartBeat()
const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS]
static uint16_t rb_full_count(ring_buffer *rb)
Return the number of elements stored in the ring buffer.
Definition: ring_buffer.h:84
static uint8_t rb_remove(ring_buffer *rb)
Remove and return the first item from a ring buffer.
Definition: ring_buffer.h:128
#define BOARD_OSD_VSYNC_PIN
Definition: board.h:148
static void task_resume(void *h)
Definition: Scheduler.h:321
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
void update_max_buffer(const uint8_t *buffer, uint16_t len)
voidFuncPtr vp
Definition: hal_types.h:23
float distance
Definition: location.cpp:94
int16_t osd_getc()
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: GPIO.h:100
void gpio_set_mode(const gpio_dev *const dev, uint8_t pin, gpio_pin_mode mode)
Definition: gpio_hal.c:125
#define VSI_INT_PRIORITY
Definition: Config.h:49
#define VER
Definition: Config.h:9
#define HIGH
Definition: board.h:34
bool set_speed(AP_HAL::Device::Speed speed) override
Definition: SPIDevice.cpp:742
Simple circular buffer.
void osd_loop()
static int rb_is_full(ring_buffer *rb)
Returns true if and only if the ring buffer is full.
Definition: ring_buffer.h:99
static void * task_handle
void delay_150()
#define f(i)
static void rb_init(ring_buffer *rb, uint16_t size, uint8_t *buf)
Definition: ring_buffer.h:73
const char * fmt
Definition: Printf.cpp:14
void request_mavlink_rates()
static void init()
Definition: osd_eeprom.cpp:27
NOINLINE void eeprom_write_len(byte *p, uint16_t e, uint16_t l)
Definition: Config_Func.h:14
#define IN_CCM
Definition: AP_HAL_F4Light.h:9
uint32_t millis()
Definition: system.cpp:157
static void set_task_period(void *h, uint32_t period)
Definition: Scheduler.cpp:914
#define LOW
Definition: board.h:31
virtual bool give()=0
uint8_t byte
Definition: compat.h:8
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
NOINLINE void logo()
bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override
Definition: SPIDevice.cpp:188
#define NULL
Definition: hal_types.h:59
Common definitions and utility routines for the ArduPilot libraries.
void On20ms()
void max_do_transfer(const uint8_t *buffer, uint16_t len)
T x
Definition: vector2.h:37
#define SMALL_TASK_STACK
Definition: Scheduler.h:35
static bool _attach_interrupt(uint8_t pin, Handler h, uint8_t mode, uint8_t priority)
Definition: GPIO.cpp:123
int16_t osd_available()
void On100ms()
uint32_t osd_txspace()
void max7456_off()
void init()
Generic board initialization function.
Definition: system.cpp:136
static void gpio_set_speed(const gpio_dev *const dev, uint8_t pin, GPIOSpeed_t gpio_speed)
Definition: gpio_hal.h:161
static void delay_ns100(uint32_t us)
Definition: delay.h:36
#define B01000111
Definition: binary.h:292
static int rb_push_insert(ring_buffer *rb, uint8_t element)
Append an item onto the end of a non-full ring buffer.
Definition: ring_buffer.h:173
void doScreenSwitch()
uint8_t gpio_bit
Definition: boards.h:92
Stores STM32-specific information related to a given Maple pin.
Definition: boards.h:88
#define BOARD_OSD_CS_PIN
Definition: board.h:147
const gpio_dev *const gpio_device
Definition: boards.h:89
Vector2l point
Definition: polygon.cpp:34
void osd_begin(AP_HAL::OwnPtr< F4Light::SPIDevice > spi)
static void * start_task(voidFuncPtr taskLoop, size_t stackSize=DEFAULT_STACK_SIZE)
Definition: Scheduler.h:266
void hal_yield(uint16_t ttw)
Definition: Scheduler.cpp:1430
static INLINE void gpio_write_bit(const gpio_dev *const dev, uint8_t pin, uint8_t val)
Definition: gpio_hal.h:115