Rev 388 | Rev 400 | Go to most recent revision | Only display areas with differences | Ignore whitespace | Details | Blame | Last modification | View Log | RSS feed
Rev 388 | Rev 389 | ||
---|---|---|---|
1 | /**************************************************************************** |
1 | /**************************************************************************** |
2 | * Copyright (C) 2009 by Claas Anders "CaScAdE" Rathje * |
2 | * Copyright (C) 2009 by Claas Anders "CaScAdE" Rathje * |
3 | * admiralcascade@gmail.com * |
3 | * admiralcascade@gmail.com * |
4 | * Project-URL: http://www.mylifesucks.de/oss/c-osd/ * |
4 | * Project-URL: http://www.mylifesucks.de/oss/c-osd/ * |
5 | * * |
5 | * * |
6 | * This program is free software; you can redistribute it and/or modify * |
6 | * This program is free software; you can redistribute it and/or modify * |
7 | * it under the terms of the GNU General Public License as published by * |
7 | * it under the terms of the GNU General Public License as published by * |
8 | * the Free Software Foundation; either version 2 of the License. * |
8 | * the Free Software Foundation; either version 2 of the License. * |
9 | * * |
9 | * * |
10 | * This program is distributed in the hope that it will be useful, * |
10 | * This program is distributed in the hope that it will be useful, * |
11 | * but WITHOUT ANY WARRANTY; without even the implied warranty of * |
11 | * but WITHOUT ANY WARRANTY; without even the implied warranty of * |
12 | * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * |
12 | * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * |
13 | * GNU General Public License for more details. * |
13 | * GNU General Public License for more details. * |
14 | * * |
14 | * * |
15 | * You should have received a copy of the GNU General Public License * |
15 | * You should have received a copy of the GNU General Public License * |
16 | * along with this program; if not, write to the * |
16 | * along with this program; if not, write to the * |
17 | * Free Software Foundation, Inc., * |
17 | * Free Software Foundation, Inc., * |
18 | * 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. * |
18 | * 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. * |
19 | * * |
19 | * * |
20 | * * |
20 | * * |
21 | * Credits to: * |
21 | * Credits to: * |
22 | * Holger Buss & Ingo Busker from mikrokopter.de for the MK project * |
22 | * Holger Buss & Ingo Busker from mikrokopter.de for the MK project * |
23 | * Gregor "killagreg" Stobrawa for making the MK code readable * |
23 | * Gregor "killagreg" Stobrawa for making the MK code readable * |
24 | * Klaus "akku" Buettner for the hardware * |
24 | * Klaus "akku" Buettner for the hardware * |
25 | * Manuel "KeyOz" Schrape for explaining the MK protocol to me * |
25 | * Manuel "KeyOz" Schrape for explaining the MK protocol to me * |
26 | ****************************************************************************/ |
26 | ****************************************************************************/ |
27 | 27 | ||
28 | #include <avr/io.h> |
28 | #include <avr/io.h> |
29 | #include <avr/interrupt.h> |
29 | #include <avr/interrupt.h> |
30 | #include <util/delay.h> |
30 | #include <util/delay.h> |
31 | #include <avr/pgmspace.h> |
31 | #include <avr/pgmspace.h> |
32 | #include "main.h" |
32 | #include "main.h" |
33 | #include "max7456_software_spi.h" |
33 | #include "max7456_software_spi.h" |
34 | #include "usart1.h" |
34 | #include "usart1.h" |
- | 35 | #include "osd_helpers.h" |
|
35 | 36 | ||
36 | /* TODO: |
37 | /* TODO: |
37 | * - verifiy correctness of values |
38 | * - verifiy correctness of values |
38 | * - clean up code :) |
39 | * - clean up code :) |
39 | */ |
40 | */ |
40 | 41 | ||
41 | #if !(ALLCHARSDEBUG|(WRITECHARS != -1)) |
42 | #if !(ALLCHARSDEBUG|(WRITECHARS != -1)) |
42 | // data structs not needed for character flashin |
43 | // data structs not needed for character flashin |
43 | #include "mk-data-structs.h" |
44 | #include "mk-data-structs.h" |
44 | 45 | ||
45 | /* ########################################################################## |
46 | /* ########################################################################## |
46 | * global definitions and global vars |
47 | * global definitions and global vars |
47 | * ##########################################################################*/ |
48 | * ##########################################################################*/ |
48 | 49 | ||
49 | volatile uint16_t setsReceived = 0; |
50 | volatile uint16_t setsReceived = 0; |
50 | 51 | ||
51 | volatile NaviData_t naviData; |
52 | volatile NaviData_t naviData; |
52 | volatile DebugOut_t debugData; |
53 | volatile DebugOut_t debugData; |
53 | 54 | ||
54 | // cache old vars for blinking attribute, checkup is faster than full |
55 | // cache old vars for blinking attribute, checkup is faster than full |
55 | // attribute write each time |
56 | // attribute write each time |
56 | volatile uint8_t last_UBat = 255; |
57 | volatile uint8_t last_UBat = 255; |
57 | volatile uint8_t last_RC_Quality = 255; |
58 | volatile uint8_t last_RC_Quality = 255; |
58 | 59 | ||
59 | // 16bit should be enough, normal LiPos don't last that long |
60 | // 16bit should be enough, normal LiPos don't last that long |
60 | volatile uint16_t uptime = 0; |
61 | volatile uint16_t uptime = 0; |
61 | volatile uint16_t timer = 0; |
62 | volatile uint16_t timer = 0; |
62 | 63 | ||
63 | // remember last time data was received |
64 | // remember last time data was received |
64 | volatile uint8_t seconds_since_last_data = 0; |
65 | volatile uint8_t seconds_since_last_data = 0; |
65 | 66 | ||
66 | // store stats description in progmem to save space |
67 | // store stats description in progmem to save space |
67 | char stats_item_0[] PROGMEM = "max Altitude:"; |
68 | char stats_item_0[] PROGMEM = "max Altitude:"; |
68 | char stats_item_1[] PROGMEM = "max Speed :"; |
69 | char stats_item_1[] PROGMEM = "max Speed :"; |
69 | char stats_item_2[] PROGMEM = "max Distance:"; |
70 | char stats_item_2[] PROGMEM = "max Distance:"; |
70 | char stats_item_3[] PROGMEM = "min voltage :"; |
71 | char stats_item_3[] PROGMEM = "min voltage :"; |
71 | char stats_item_4[] PROGMEM = "max time :"; |
72 | char stats_item_4[] PROGMEM = "max time :"; |
72 | char* stats_item_pointers[] PROGMEM = {stats_item_0, stats_item_1, stats_item_2, |
73 | char* stats_item_pointers[] PROGMEM = {stats_item_0, stats_item_1, stats_item_2, |
73 | stats_item_3, stats_item_4}; |
74 | stats_item_3, stats_item_4}; |
74 | 75 | ||
75 | // store more fixed strings in progmen |
76 | // store more fixed strings in progmen |
76 | char ON[] PROGMEM = "ON "; |
77 | char ON[] PROGMEM = "ON "; |
77 | char OFF[] PROGMEM = "OFF"; |
78 | char OFF[] PROGMEM = "OFF"; |
78 | - | ||
79 | // big vario arrays |
- | |
80 | char vario_00[5] PROGMEM = {0x00, 0x00, 0xc2, 0xff, 0xff}; |
- | |
81 | char vario_01[5] PROGMEM = {0x00, 0x00, 0xc2, 0xff, 0xc0}; |
- | |
82 | char vario_02[5] PROGMEM = {0x00, 0x00, 0xc2, 0xff, 0xc1}; |
- | |
83 | char vario_03[5] PROGMEM = {0x00, 0x00, 0xc2, 0xff, 0x00}; |
- | |
84 | char vario_04[5] PROGMEM = {0x00, 0x00, 0xc2, 0xc0, 0x00}; |
- | |
85 | char vario_05[5] PROGMEM = {0x00, 0x00, 0xc2, 0xc1, 0x00}; |
- | |
86 | char vario_06[5] PROGMEM = {0x00, 0x00, 0xc2, 0x00, 0x00}; |
- | |
87 | char vario_07[5] PROGMEM = {0x00, 0x00, 0xbb, 0x00, 0x00}; |
- | |
88 | char vario_08[5] PROGMEM = {0x00, 0x00, 0xc3, 0x00, 0x00}; |
- | |
89 | char vario_09[5] PROGMEM = {0x00, 0xc4, 0xc3, 0x00, 0x00}; |
- | |
90 | char vario_10[5] PROGMEM = {0x00, 0xc5, 0xc3, 0x00, 0x00}; |
- | |
91 | char vario_11[5] PROGMEM = {0x00, 0xff, 0xc3, 0x00, 0x00}; |
- | |
92 | char vario_12[5] PROGMEM = {0xc4, 0xff, 0xc3, 0x00, 0x00}; |
- | |
93 | char vario_13[5] PROGMEM = {0xc5, 0xff, 0xc3, 0x00, 0x00}; |
- | |
94 | char vario_14[5] PROGMEM = {0xff, 0xff, 0xc3, 0x00, 0x00}; |
- | |
95 | char* vario_pnt[15] PROGMEM = {vario_00, vario_01, vario_02, vario_03, vario_04, |
- | |
96 | vario_05, vario_06, vario_07, vario_08, |
- | |
97 | vario_09, vario_10, vario_11, vario_12, |
- | |
98 | vario_13, vario_14}; |
- | |
99 | 79 | ||
100 | #endif // ends !(ALLCHARSDEBUG|(WRITECHARS != -1)) |
80 | #endif // ends !(ALLCHARSDEBUG|(WRITECHARS != -1)) |
101 | 81 | ||
102 | // general PAL|NTSC distingiusch stuff |
82 | // general PAL|NTSC distingiusch stuff |
103 | uint8_t top_line = 1; |
83 | uint8_t top_line = 1; |
104 | uint8_t bottom_line = 14; |
84 | uint8_t bottom_line = 14; |
105 | 85 | ||
106 | // Flags |
86 | // Flags |
107 | uint8_t COSD_FLAGS = 0; |
87 | uint8_t COSD_FLAGS = 0; |
108 | 88 | ||
109 | /* ########################################################################## |
89 | /* ########################################################################## |
110 | * debounce buttons |
90 | * debounce buttons |
111 | * ##########################################################################*/ |
91 | * ##########################################################################*/ |
112 | int s1_pressed() { |
92 | int s1_pressed() { |
113 | if (S1_PRESSED) { |
93 | if (S1_PRESSED) { |
114 | _delay_ms(25); |
94 | _delay_ms(25); |
115 | if (S1_PRESSED) return 1; |
95 | if (S1_PRESSED) return 1; |
116 | } |
96 | } |
117 | return 0; |
97 | return 0; |
118 | } |
98 | } |
119 | 99 | ||
120 | int s2_pressed() { |
100 | int s2_pressed() { |
121 | if (S2_PRESSED) { |
101 | if (S2_PRESSED) { |
122 | _delay_ms(25); |
102 | _delay_ms(25); |
123 | if (S2_PRESSED) return 1; |
103 | if (S2_PRESSED) return 1; |
124 | } |
104 | } |
125 | return 0; |
105 | return 0; |
126 | } |
106 | } |
127 | - | ||
- | 107 | ||
128 | 108 | /* ########################################################################## |
|
129 | #if !(ALLCHARSDEBUG|(WRITECHARS != -1)) |
- | |
- | 109 | * Interrupt handler |
|
130 | 110 | * ##########################################################################*/ |
|
131 | /** |
111 | /** |
- | 112 | * handler for undefined Interrupts |
|
132 | * serial support |
113 | * if not defined AVR will reset in case any unhandled interrupts occur |
133 | */ |
114 | */ |
- | 115 | ISR(__vector_default) { |
|
134 | //#include "usart1.c" |
116 | asm("nop"); |
- | 117 | } |
|
135 | 118 | ||
136 | 119 | #if !(ALLCHARSDEBUG|(WRITECHARS != -1)) |
|
137 | /* ########################################################################## |
120 | /* ########################################################################## |
138 | * timer stuff |
121 | * timer stuff |
139 | * ##########################################################################*/ |
122 | * ##########################################################################*/ |
140 | - | ||
141 | /** |
123 | /** |
142 | * timer kicks in every 1000uS ^= 1ms |
124 | * timer kicks in every 1000uS ^= 1ms |
143 | */ |
125 | */ |
144 | ISR(TIMER0_OVF_vect) { |
126 | ISR(TIMER0_OVF_vect) { |
145 | OCR0 = 15; // preload |
127 | OCR0 = 15; // preload |
146 | if (!timer--) { |
128 | if (!timer--) { |
147 | uptime++; |
129 | uptime++; |
148 | timer = 999; |
130 | timer = 999; |
149 | seconds_since_last_data++; |
131 | seconds_since_last_data++; |
150 | } |
132 | } |
151 | } |
133 | } |
152 | - | ||
153 | /* ########################################################################## |
- | |
154 | * compass stuff |
- | |
155 | * ##########################################################################*/ |
- | |
156 | - | ||
157 | /** |
- | |
158 | * convert the <heading> gotton from NC into an index |
- | |
159 | */ |
- | |
160 | uint8_t heading_conv(uint16_t heading) { |
- | |
161 | if (heading > 23 && heading < 68) { |
- | |
162 | //direction = "NE"; |
- | |
163 | return 0; |
- | |
164 | } else if (heading > 67 && heading < 113) { |
- | |
165 | //direction = "E "; |
- | |
166 | return 1; |
- | |
167 | } else if (heading > 112 && heading < 158) { |
- | |
168 | //direction = "SE"; |
- | |
169 | return 2; |
- | |
170 | } else if (heading > 157 && heading < 203) { |
- | |
171 | //direction = "S "; |
- | |
172 | return 3; |
- | |
173 | } else if (heading > 202 && heading < 248) { |
- | |
174 | //direction = "SW"; |
- | |
175 | return 4; |
- | |
176 | } else if (heading > 247 && heading < 293) { |
- | |
177 | //direction = "W "; |
- | |
178 | return 5; |
- | |
179 | } else if (heading > 292 && heading < 338) { |
- | |
180 | //direction = "NW"; |
- | |
181 | return 6; |
- | |
182 | } |
- | |
183 | //direction = "N "; |
- | |
184 | return 7; |
- | |
185 | } |
- | |
186 | - | ||
187 | /** |
- | |
188 | * convert the <heading> gotton from NC into a more |
- | |
189 | * precise index |
- | |
190 | */ |
- | |
191 | uint8_t heading_fine_conv(uint16_t heading) { |
- | |
192 | heading = ((heading * 10) + 113) % 3600; |
- | |
193 | return (heading / 225); |
- | |
194 | } |
- | |
195 | - | ||
196 | /** |
- | |
197 | * draw a compass rose at <x>/<y> for <heading> |
- | |
198 | */ |
- | |
199 | void draw_compass(uint8_t x, uint8_t y, uint16_t heading) { |
- | |
200 | //char* rose = "---N---O---S---W---N---O---S---W---N---O---S---W"; |
- | |
201 | char rose[48] = {216, 215, 216, 211, 216, 215, 216, 213, 216, 215, 216, 212, |
- | |
202 | 216, 215, 216, 214, 216, 215, 216, 211, 216, 215, 216, 213, |
- | |
203 | 216, 215, 216, 212, 216, 215, 216, 214, 216, 215, 216, 211, |
- | |
204 | 216, 215, 216, 213, 216, 215, 216, 212, 216, 215, 216, 214}; |
- | |
205 | // the center is char 19 (north), we add the current heading in 8th |
- | |
206 | // which would be 22.5 degrees, but float would bloat up the code |
- | |
207 | // and *10 / 225 would take ages... so we take the uncorrect way |
- | |
208 | uint8_t front = 19 + (heading / 22); |
- | |
209 | for (uint8_t i = 0; i < 9; i++) { |
- | |
210 | write_char_xy(x++, y, rose[front - 4 + i]); |
- | |
211 | } |
- | |
212 | } |
- | |
213 | - | ||
214 | /* ########################################################################## |
- | |
215 | * battery index |
- | |
216 | * ##########################################################################*/ |
- | |
217 | /** |
- | |
218 | * draw a battery symbol at <x>/<y> according to <voltage> |
- | |
219 | */ |
- | |
220 | void draw_battery(uint8_t x, uint8_t y, uint16_t voltage) { |
- | |
221 | uint8_t percent = (100* (voltage - UBAT_WRN) / (UBAT_MAX - UBAT_WRN)); |
- | |
222 | if (percent > 100) percent = 100; |
- | |
223 | if (voltage < UBAT_WRN) percent = 0; |
- | |
224 | write_char_xy(x, y, 0x9d - (percent * 13 / 100)); |
- | |
225 | //write_ndigit_number_u(x, y-1, percent * 13 / 100, 100, 0); |
- | |
226 | } |
- | |
227 | - | ||
228 | /* ########################################################################## |
- | |
229 | * variometer |
- | |
230 | * ##########################################################################*/ |
- | |
231 | /** |
- | |
232 | * draw variometer arrows at <x>/<y> according to <variometer> |
- | |
233 | */ |
- | |
234 | void draw_variometer(uint8_t x, uint8_t y, int16_t variometer) { |
- | |
235 | if (variometer == 0) { |
- | |
236 | write_char_xy(x, y, 0xbb); // plain line |
- | |
237 | } else if (variometer > 0) { // gain height |
- | |
238 | switch (variometer / 5){ |
- | |
239 | case 0: |
- | |
240 | //write_char_xy(x, y, 0xba); // smallest arrow up |
- | |
241 | write_char_xy(x, y, 0x70); // one arrow up |
- | |
242 | break; |
- | |
243 | case 1: |
- | |
244 | //write_char_xy(x, y, 0xb9); // small arrow up |
- | |
245 | write_char_xy(x, y, 0x71); // two arrows up |
- | |
246 | break; |
- | |
247 | case 2: |
- | |
248 | //write_char_xy(x, y, 0xb8); // large arrow up |
- | |
249 | write_char_xy(x, y, 0x72); // three arrows up |
- | |
250 | break; |
- | |
251 | default: |
- | |
252 | //write_char_xy(x, y, 0xb7); // largest arrow up |
- | |
253 | write_char_xy(x, y, 0x73); // three black arrows up |
- | |
254 | } |
- | |
255 | } else { // sink |
- | |
256 | switch (variometer / -5){ |
- | |
257 | case 0: |
- | |
258 | //write_char_xy(x, y, 0xbc); // smallest arrow down |
- | |
259 | write_char_xy(x, y, 0x77); // one arrow down |
- | |
260 | break; |
- | |
261 | case 1: |
- | |
262 | //write_char_xy(x, y, 0xbd); // small arrow down |
- | |
263 | write_char_xy(x, y, 0x76); // two arrows down |
- | |
264 | break; |
- | |
265 | case 2: |
- | |
266 | //write_char_xy(x, y, 0xbe); // large arrow down |
- | |
267 | write_char_xy(x, y, 0x75); // three arrows down |
- | |
268 | break; |
- | |
269 | default: |
- | |
270 | //write_char_xy(x, y, 0xbf); // largest arrow down |
- | |
271 | write_char_xy(x, y, 0x74); // three black arrows down |
- | |
272 | } |
- | |
273 | } |
- | |
274 | } |
- | |
275 | - | ||
276 | /** |
- | |
277 | * draw a bigger vario with middle at <x>/<y> acording to <variometer> |
- | |
278 | */ |
- | |
279 | void draw_big_variometer(uint8_t x, uint8_t y, int16_t variometer) { |
- | |
280 | int16_t index = 7 + variometer; |
- | |
281 | if (index > 14) index = 14; |
- | |
282 | else if (index < 0) index = 0; |
- | |
283 | - | ||
284 | // TODO: why does write_string_pgm_down(x, y-2, vario_pnt[index], 5); |
- | |
285 | // not work??? WTF?! |
- | |
286 | switch (index) { |
- | |
287 | case 0: write_string_pgm_down(x, y-2, vario_pnt[0], 5); |
- | |
288 | break; |
- | |
289 | case 1: write_string_pgm_down(x, y-2, vario_pnt[1], 5); |
- | |
290 | break; |
- | |
291 | case 2: write_string_pgm_down(x, y-2, vario_pnt[2], 5); |
- | |
292 | break; |
- | |
293 | case 3: write_string_pgm_down(x, y-2, vario_pnt[3], 5); |
- | |
294 | break; |
- | |
295 | case 4: write_string_pgm_down(x, y-2, vario_pnt[4], 5); |
- | |
296 | break; |
- | |
297 | case 5: write_string_pgm_down(x, y-2, vario_pnt[5], 5); |
- | |
298 | break; |
- | |
299 | case 6: write_string_pgm_down(x, y-2, vario_pnt[6], 5); |
- | |
300 | break; |
- | |
301 | case 7: write_string_pgm_down(x, y-2, vario_pnt[7], 5); |
- | |
302 | break; |
- | |
303 | case 8: write_string_pgm_down(x, y-2, vario_pnt[8], 5); |
- | |
304 | break; |
- | |
305 | case 9: write_string_pgm_down(x, y-2, vario_pnt[9], 5); |
- | |
306 | break; |
- | |
307 | case 10: write_string_pgm_down(x, y-2, vario_pnt[10], 5); |
- | |
308 | break; |
- | |
309 | case 11: write_string_pgm_down(x, y-2, vario_pnt[11], 5); |
- | |
310 | break; |
- | |
311 | case 12: write_string_pgm_down(x, y-2, vario_pnt[12], 5); |
- | |
312 | break; |
- | |
313 | case 13: write_string_pgm_down(x, y-2, vario_pnt[13], 5); |
- | |
314 | break; |
- | |
315 | default: write_string_pgm_down(x, y-2, vario_pnt[14], 5); |
- | |
316 | } |
- | |
317 | } |
- | |
318 | - | ||
319 | /* ########################################################################## |
- | |
320 | * artificial horizon |
- | |
321 | * ##########################################################################*/ |
- | |
322 | // remember last time displayed values |
- | |
323 | int8_t old_af_x = -1, old_af_y = -1; |
- | |
324 | - | ||
325 | /** |
- | |
326 | * draw roll und nick indicators (could be enhanced to full artificial horizon) |
- | |
327 | * from line <firstline> to <listlines> for given <nick> and <roll> values |
- | |
328 | */ |
- | |
329 | void draw_artificial_horizon(uint8_t firstline, uint8_t lastline, int16_t nick, int16_t roll) { |
- | |
330 | char noodle[5] = {225, 225, 226, 227, 227}; |
- | |
331 | uint8_t center_x = 15; |
- | |
332 | uint8_t center_y = lastline - firstline; |
- | |
333 | center_y = 7; |
- | |
334 | write_char_xy(center_x,center_y,228); |
- | |
335 | uint8_t cpos, nicky, rollx; |
- | |
336 | - | ||
337 | // which line |
- | |
338 | int8_t ypos = nick / 20; |
- | |
339 | // which character from the array? |
- | |
340 | if (nick < 0) { |
- | |
341 | cpos = -1*((nick - (ypos * 20))/4); |
- | |
342 | ypos--; |
- | |
343 | } else cpos = 4-((nick - (ypos * 20))/4); |
- | |
344 | if (cpos > 4) cpos = 4; |
- | |
345 | - | ||
346 | nicky = center_y - ypos; |
- | |
347 | if (nicky > lastline) nicky = lastline; |
- | |
348 | else if (nicky < firstline) nicky = firstline; |
- | |
349 | - | ||
350 | // ensure roll-borders |
- | |
351 | rollx = (roll / 8)+15; |
- | |
352 | if (rollx < 2) rollx = 2; |
- | |
353 | else if (rollx > 28) rollx = 28; |
- | |
354 | - | ||
355 | - | ||
356 | // clear roll |
- | |
357 | if (old_af_x != rollx && old_af_x >= 0) { |
- | |
358 | write_char_xy(old_af_x,13,0); |
- | |
359 | } |
- | |
360 | - | ||
361 | // clear nick |
- | |
362 | if (old_af_y != nicky && old_af_y >= 0) { |
- | |
363 | write_char_xy(center_x-1,old_af_y,0); |
- | |
364 | write_char_xy(center_x+1,old_af_y,0); |
- | |
365 | } |
- | |
366 | - | ||
367 | - | ||
368 | // draw nick |
- | |
369 | write_char_xy(center_x-1,nicky,noodle[cpos]); |
- | |
370 | write_char_xy(center_x+1,nicky,noodle[cpos]); |
- | |
371 | - | ||
372 | // draw roll |
- | |
373 | write_char_xy(rollx,lastline,229); |
- | |
374 | - | ||
375 | // update old vars |
- | |
376 | old_af_x = rollx; |
- | |
377 | old_af_y = nicky; |
- | |
378 | - | ||
379 | // debug numbers |
- | |
380 | //write_3digit_number_u(20,6,cpos); |
- | |
381 | //write_number_s(20,7,ypos); |
- | |
382 | //write_number_s(0,7,nick); |
- | |
383 | //write_number_s(18,11,roll); |
- | |
384 | } |
134 | |
385 | 135 | ||
386 | /* ########################################################################## |
136 | /* ########################################################################## |
387 | * A simple config menu for the flags |
137 | * A simple config menu for the flags |
388 | * ##########################################################################*/ |
138 | * ##########################################################################*/ |
389 | 139 | ||
390 | /** |
140 | /** |
391 | * helper function for menu updating |
141 | * helper function for menu updating |
392 | */ |
142 | */ |
393 | void config_menu_drawings(uint8_t chosen) { |
143 | void config_menu_drawings(uint8_t chosen) { |
394 | // clear prevoius _cursor_ |
144 | // clear prevoius _cursor_ |
395 | write_ascii_string(3, (chosen + 5) % 8, " "); |
145 | write_ascii_string(3, (chosen + 5) % 8, " "); |
396 | // draw current _cursor_ |
146 | // draw current _cursor_ |
397 | write_ascii_string(3, chosen + 5, ">"); |
147 | write_ascii_string(3, chosen + 5, ">"); |
398 | if (COSD_FLAGS & COSD_FLAG_HUD) { |
148 | if (COSD_FLAGS & COSD_FLAG_HUD) { |
399 | write_ascii_string_pgm(23, 5, ON); |
149 | write_ascii_string_pgm(23, 5, ON); |
400 | } else { |
150 | } else { |
401 | write_ascii_string_pgm(23, 5, OFF); |
151 | write_ascii_string_pgm(23, 5, OFF); |
402 | } |
152 | } |
403 | if (COSD_FLAGS & COSD_FLAG_ARTHORIZON) { |
153 | if (COSD_FLAGS & COSD_FLAG_ARTHORIZON) { |
404 | write_ascii_string_pgm(23, 6, ON); |
154 | write_ascii_string_pgm(23, 6, ON); |
405 | } else { |
155 | } else { |
406 | write_ascii_string_pgm(23, 6, OFF); |
156 | write_ascii_string_pgm(23, 6, OFF); |
407 | } |
157 | } |
408 | if (COSD_FLAGS & COSD_FLAG_BIGVARIO) { |
158 | if (COSD_FLAGS & COSD_FLAG_BIGVARIO) { |
409 | write_ascii_string_pgm(23, 7, ON); |
159 | write_ascii_string_pgm(23, 7, ON); |
410 | } else { |
160 | } else { |
411 | write_ascii_string_pgm(23, 7, OFF); |
161 | write_ascii_string_pgm(23, 7, OFF); |
412 | } |
162 | } |
413 | if (COSD_FLAGS & COSD_FLAG_STATS) { |
163 | if (COSD_FLAGS & COSD_FLAG_STATS) { |
414 | write_ascii_string_pgm(23, 8, ON); |
164 | write_ascii_string_pgm(23, 8, ON); |
415 | } else { |
165 | } else { |
416 | write_ascii_string_pgm(23, 8, OFF); |
166 | write_ascii_string_pgm(23, 8, OFF); |
417 | } |
167 | } |
418 | if (COSD_FLAGS & COSD_FLAG_WARNINGS) { |
168 | if (COSD_FLAGS & COSD_FLAG_WARNINGS) { |
419 | write_ascii_string_pgm(23, 9, ON); |
169 | write_ascii_string_pgm(23, 9, ON); |
420 | } else { |
170 | } else { |
421 | write_ascii_string_pgm(23, 9, OFF); |
171 | write_ascii_string_pgm(23, 9, OFF); |
422 | } |
172 | } |
423 | } |
173 | } |
424 | 174 | ||
425 | /** |
175 | /** |
426 | * some sort of clicking response in the menu |
176 | * some sort of clicking response in the menu |
427 | */ |
177 | */ |
428 | void config_menu_doclick(uint8_t chosen, char** menu) { |
178 | void config_menu_doclick(uint8_t chosen, char** menu) { |
429 | write_ascii_string(4, chosen + 5, "DONE "); |
179 | write_ascii_string(4, chosen + 5, "DONE "); |
430 | _delay_ms(1000); |
180 | _delay_ms(1000); |
431 | write_ascii_string(4, chosen + 5, menu[chosen]); |
181 | write_ascii_string(4, chosen + 5, menu[chosen]); |
432 | } |
182 | } |
433 | 183 | ||
434 | /** |
184 | /** |
435 | * a simple config menu tryout |
185 | * a simple config menu tryout |
436 | */ |
186 | */ |
437 | void config_menu(void) { |
187 | void config_menu(void) { |
438 | // disable interrupts (makes the menu more smoothely) |
188 | // disable interrupts (makes the menu more smoothely) |
439 | cli(); |
189 | cli(); |
440 | 190 | ||
441 | // clear screen |
191 | // clear screen |
442 | clear(); |
192 | clear(); |
443 | 193 | ||
444 | char* menu[9] = {"Full HUD", |
194 | char* menu[9] = {"Full HUD", |
445 | "Art.Horizon in HUD", |
195 | "Art.Horizon in HUD", |
446 | "Big Vario bar", |
196 | "Big Vario bar", |
447 | "Statistics", |
197 | "Statistics", |
448 | "Warnings", // TODO: do it! |
198 | "Warnings", // TODO: do it! |
449 | "Reset uptime", |
199 | "Reset uptime", |
450 | "Request OSD-data", |
200 | "Request OSD-data", |
451 | "Disable Debug-data", |
201 | "Disable Debug-data", |
452 | "EXIT"}; |
202 | "EXIT"}; |
453 | 203 | ||
454 | uint8_t inmenu = 1; |
204 | uint8_t inmenu = 1; |
455 | uint8_t chosen = 0; |
205 | uint8_t chosen = 0; |
456 | write_ascii_string(6, 2, "C-OSD Config Menu"); |
206 | write_ascii_string(6, 2, "C-OSD Config Menu"); |
457 | 207 | ||
458 | // wait a bit before doing stuff so user has chance to release button |
208 | // wait a bit before doing stuff so user has chance to release button |
459 | _delay_ms(250); |
209 | _delay_ms(250); |
460 | 210 | ||
461 | write_ascii_string(4, 5, menu[0]); |
211 | write_ascii_string(4, 5, menu[0]); |
462 | write_ascii_string(4, 6, menu[1]); |
212 | write_ascii_string(4, 6, menu[1]); |
463 | write_ascii_string(4, 7, menu[2]); |
213 | write_ascii_string(4, 7, menu[2]); |
464 | write_ascii_string(4, 8, menu[3]); |
214 | write_ascii_string(4, 8, menu[3]); |
465 | write_ascii_string(4, 9, menu[4]); |
215 | write_ascii_string(4, 9, menu[4]); |
466 | write_ascii_string(4, 10, menu[5]); |
216 | write_ascii_string(4, 10, menu[5]); |
467 | write_ascii_string(4, 11, menu[6]); |
217 | write_ascii_string(4, 11, menu[6]); |
468 | write_ascii_string(4, 12, menu[7]); |
218 | write_ascii_string(4, 12, menu[7]); |
469 | write_ascii_string(4, 13, menu[8]); |
219 | write_ascii_string(4, 13, menu[8]); |
470 | 220 | ||
471 | config_menu_drawings(chosen); |
221 | config_menu_drawings(chosen); |
472 | 222 | ||
473 | while (inmenu) { |
223 | while (inmenu) { |
474 | if (s2_pressed()) { |
224 | if (s2_pressed()) { |
475 | write_ascii_string(3, chosen+5, " "); |
225 | write_ascii_string(3, chosen+5, " "); |
476 | chosen = (chosen + 1) % 9; |
226 | chosen = (chosen + 1) % 9; |
477 | write_ascii_string(3, chosen+5, ">"); |
227 | write_ascii_string(3, chosen+5, ">"); |
478 | _delay_ms(500); |
228 | _delay_ms(500); |
479 | } else if (s1_pressed()) { |
229 | } else if (s1_pressed()) { |
480 | switch (chosen) { |
230 | switch (chosen) { |
481 | case 0: // full HUD |
231 | case 0: // full HUD |
482 | COSD_FLAGS ^= COSD_FLAG_HUD; |
232 | COSD_FLAGS ^= COSD_FLAG_HUD; |
483 | config_menu_drawings(chosen); |
233 | config_menu_drawings(chosen); |
484 | break; |
234 | break; |
485 | case 1: // art horizon |
235 | case 1: // art horizon |
486 | COSD_FLAGS ^= COSD_FLAG_ARTHORIZON; |
236 | COSD_FLAGS ^= COSD_FLAG_ARTHORIZON; |
487 | config_menu_drawings(chosen); |
237 | config_menu_drawings(chosen); |
488 | break; |
238 | break; |
489 | case 2: // big vario |
239 | case 2: // big vario |
490 | COSD_FLAGS ^= COSD_FLAG_BIGVARIO; |
240 | COSD_FLAGS ^= COSD_FLAG_BIGVARIO; |
491 | config_menu_drawings(chosen); |
241 | config_menu_drawings(chosen); |
492 | break; |
242 | break; |
493 | case 3: // statistics |
243 | case 3: // statistics |
494 | COSD_FLAGS ^= COSD_FLAG_STATS; |
244 | COSD_FLAGS ^= COSD_FLAG_STATS; |
495 | config_menu_drawings(chosen); |
245 | config_menu_drawings(chosen); |
496 | break; |
246 | break; |
497 | case 4: // warnings |
247 | case 4: // warnings |
498 | COSD_FLAGS ^= COSD_FLAG_WARNINGS; |
248 | COSD_FLAGS ^= COSD_FLAG_WARNINGS; |
499 | config_menu_drawings(chosen); |
249 | config_menu_drawings(chosen); |
500 | break; |
250 | break; |
501 | case 5: // reset uptime |
251 | case 5: // reset uptime |
502 | uptime = 0; |
252 | uptime = 0; |
503 | config_menu_doclick(chosen, menu); |
253 | config_menu_doclick(chosen, menu); |
504 | break; |
254 | break; |
505 | case 6: // re-request OSD data |
255 | case 6: // re-request OSD data |
506 | // request OSD Data from NC every 100ms |
256 | // request OSD Data from NC every 100ms |
507 | usart1_request_mk_data(1, 'o', 100); |
257 | usart1_request_mk_data(1, 'o', 100); |
508 | config_menu_doclick(chosen, menu); |
258 | config_menu_doclick(chosen, menu); |
509 | break; |
259 | break; |
510 | case 7: // disable debug data |
260 | case 7: // disable debug data |
511 | // disable sending of debug data |
261 | // disable sending of debug data |
512 | // may result in smoother ddata display |
262 | // may result in smoother ddata display |
513 | usart1_request_mk_data(0, 'd', 0); |
263 | usart1_request_mk_data(0, 'd', 0); |
514 | config_menu_doclick(chosen, menu); |
264 | config_menu_doclick(chosen, menu); |
515 | break; |
265 | break; |
516 | case 8: // exit |
266 | case 8: // exit |
517 | inmenu = 0; |
267 | inmenu = 0; |
518 | break; |
268 | break; |
519 | } |
269 | } |
520 | _delay_ms(250); |
270 | _delay_ms(250); |
521 | } |
271 | } |
522 | } |
272 | } |
523 | 273 | ||
524 | // clear screen up again |
274 | // clear screen up again |
525 | clear(); |
275 | clear(); |
526 | 276 | ||
527 | // update flags to paint display again if needed |
277 | // update flags to paint display again if needed |
528 | COSD_FLAGS &= ~COSD_ICONS_WRITTEN; |
278 | COSD_FLAGS &= ~COSD_ICONS_WRITTEN; |
529 | 279 | ||
530 | // enable interrupts again |
280 | // enable interrupts again |
531 | sei(); |
281 | sei(); |
532 | } |
282 | } |
533 | 283 | ||
534 | #endif // ends !(ALLCHARSDEBUG|(WRITECHARS != -1)) |
284 | #endif // ends !(ALLCHARSDEBUG|(WRITECHARS != -1)) |
535 | /* ########################################################################## |
285 | /* ########################################################################## |
536 | * MAIN |
286 | * MAIN |
537 | * ##########################################################################*/ |
287 | * ##########################################################################*/ |
538 | int main(void) { |
288 | int main(void) { |
539 | // set up FLAGS, compiler should flatten this one |
289 | // set up FLAGS, compiler should flatten this one |
540 | COSD_FLAGS = (NTSC << 0); |
290 | COSD_FLAGS = (NTSC << 0); |
541 | COSD_FLAGS |= (HUD << 1); |
291 | COSD_FLAGS |= (HUD << 1); |
542 | COSD_FLAGS |= (ARTHORIZON << 2); |
292 | COSD_FLAGS |= (ARTHORIZON << 2); |
543 | COSD_FLAGS |= (BIGVARIO << 3); |
293 | COSD_FLAGS |= (BIGVARIO << 3); |
544 | COSD_FLAGS |= (STATS << 4); |
294 | COSD_FLAGS |= (STATS << 4); |
545 | COSD_FLAGS |= (WARNINGS << 5); |
295 | COSD_FLAGS |= (WARNINGS << 5); |
546 | 296 | ||
547 | // set up Atmega162 Ports |
297 | // set up Atmega162 Ports |
548 | DDRA |= (1 << PA1); // PA1 output (/CS) |
298 | DDRA |= (1 << PA1); // PA1 output (/CS) |
549 | MAX_CS_HIGH |
299 | MAX_CS_HIGH |
550 | DDRA |= (1 << PA2); // PA2 output (SDIN) |
300 | DDRA |= (1 << PA2); // PA2 output (SDIN) |
551 | MAX_SDIN_LOW |
301 | MAX_SDIN_LOW |
552 | DDRA |= (1 << PA3); // PA3 output (SCLK) |
302 | DDRA |= (1 << PA3); // PA3 output (SCLK) |
553 | MAX_SCLK_LOW |
303 | MAX_SCLK_LOW |
554 | DDRA |= (1 << PA5); // PA5 output (RESET) |
304 | DDRA |= (1 << PA5); // PA5 output (RESET) |
555 | MAX_RESET_HIGH |
305 | MAX_RESET_HIGH |
556 | 306 | ||
557 | DDRC |= (1 << PC0); // PC0 output (LED1 gn) |
307 | DDRC |= (1 << PC0); // PC0 output (LED1 gn) |
558 | LED1_OFF |
308 | LED1_OFF |
559 | DDRC |= (1 << PC1); // PC1 output (LED2 rt) |
309 | DDRC |= (1 << PC1); // PC1 output (LED2 rt) |
560 | LED2_OFF |
310 | LED2_OFF |
561 | DDRC |= (1 << PC2); // PC2 output (LED3 gn) |
311 | DDRC |= (1 << PC2); // PC2 output (LED3 gn) |
562 | LED3_OFF |
312 | LED3_OFF |
563 | DDRC |= (1 << PC3); // PC3 output (LED4 rt) |
313 | DDRC |= (1 << PC3); // PC3 output (LED4 rt) |
564 | LED4_OFF |
314 | LED4_OFF |
565 | 315 | ||
566 | DDRC &= ~(1 << PC4); // PC4 input (MODE) |
316 | DDRC &= ~(1 << PC4); // PC4 input (MODE) |
567 | PORTC |= (1 << PC4); // pullup |
317 | PORTC |= (1 << PC4); // pullup |
568 | DDRC &= ~(1 << PC5); // PC5 input (SET) |
318 | DDRC &= ~(1 << PC5); // PC5 input (SET) |
569 | PORTC |= (1 << PC5); // pullup |
319 | PORTC |= (1 << PC5); // pullup |
570 | 320 | ||
571 | // set up top and bottom lines |
321 | // set up top and bottom lines |
572 | if (COSD_FLAGS & COSD_FLAG_NTSC) { |
322 | if (COSD_FLAGS & COSD_FLAG_NTSC) { |
573 | bottom_line = 12; |
323 | bottom_line = 12; |
574 | } else { |
324 | } else { |
575 | bottom_line = 14; |
325 | bottom_line = 14; |
576 | } |
326 | } |
577 | 327 | ||
578 | // reset the MAX7456 to be sure any undefined states do no harm |
328 | // reset the MAX7456 to be sure any undefined states do no harm |
579 | MAX_RESET_LOW |
329 | MAX_RESET_LOW |
580 | MAX_RESET_HIGH |
330 | MAX_RESET_HIGH |
581 | 331 | ||
582 | // give the FC/NC and the maxim time to come up |
332 | // give the FC/NC and the maxim time to come up |
583 | LED4_ON |
333 | LED4_ON |
584 | _delay_ms(2000); |
334 | _delay_ms(2000); |
585 | 335 | ||
586 | LED4_OFF |
336 | LED4_OFF |
587 | 337 | ||
588 | 338 | ||
589 | //Pushing NEW chars to the MAX7456 |
339 | //Pushing NEW chars to the MAX7456 |
590 | #if (WRITECHARS != -1) |
340 | #if (WRITECHARS != -1) |
591 | // DISABLE display (VM0) |
341 | // DISABLE display (VM0) |
592 | spi_send_byte(0x00, 0b00000000); |
342 | spi_send_byte(0x00, 0b00000000); |
593 | #include "characters.c" |
343 | #include "characters.c" |
594 | 344 | ||
595 | #endif |
345 | #endif |
596 | 346 | ||
597 | // Setup Video Mode |
347 | // Setup Video Mode |
598 | if (COSD_FLAGS & COSD_FLAG_NTSC) { |
348 | if (COSD_FLAGS & COSD_FLAG_NTSC) { |
599 | // NTSC + enable display immediately (VM0) |
349 | // NTSC + enable display immediately (VM0) |
600 | spi_send_byte(0x00, 0b00001000); |
350 | spi_send_byte(0x00, 0b00001000); |
601 | } else { |
351 | } else { |
602 | // PAL + enable display immediately (VM0) |
352 | // PAL + enable display immediately (VM0) |
603 | spi_send_byte(0x00, 0b01001000); |
353 | spi_send_byte(0x00, 0b01001000); |
604 | } |
354 | } |
605 | 355 | ||
606 | // clear all display-mem (DMM) |
356 | // clear all display-mem (DMM) |
607 | spi_send_byte(0x04, 0b00000100); |
357 | spi_send_byte(0x04, 0b00000100); |
608 | 358 | ||
609 | // clearing takes 12uS according to maxim so lets wait longer |
359 | // clearing takes 12uS according to maxim so lets wait longer |
610 | _delay_us(120); |
360 | _delay_us(120); |
611 | 361 | ||
612 | // 8bit mode |
362 | // 8bit mode |
613 | spi_send_byte(0x04, 0b01000000); |
363 | spi_send_byte(0x04, 0b01000000); |
614 | 364 | ||
615 | // write blank chars to whole screen |
365 | // write blank chars to whole screen |
616 | clear(); |
366 | clear(); |
617 | 367 | ||
618 | #if !(ALLCHARSDEBUG|(WRITECHARS != -1)) |
368 | #if !(ALLCHARSDEBUG|(WRITECHARS != -1)) |
619 | // init usart |
369 | // init usart |
620 | usart1_init(); |
370 | usart1_init(); |
621 | 371 | ||
622 | // set up timer |
372 | // set up timer |
623 | TCCR0 |= (1 << CS00) | (1 << CS01); // timer0 prescaler 64 |
373 | TCCR0 |= (1 << CS00) | (1 << CS01); // timer0 prescaler 64 |
624 | OCR0 = 15; // preload |
374 | OCR0 = 15; // preload |
625 | TIMSK |= (1 << TOIE0); // enable overflow timer0 |
375 | TIMSK |= (1 << TOIE0); // enable overflow timer0 |
626 | 376 | ||
627 | // enable interrupts |
377 | // enable interrupts |
628 | sei(); |
378 | sei(); |
629 | #endif |
379 | #endif |
630 | 380 | ||
631 | //write_ascii_string(2, 7, " CaScAdE "); |
381 | //write_ascii_string(2, 7, " CaScAdE "); |
632 | //write_ascii_string(2, 8, "is TESTING his open source"); |
382 | //write_ascii_string(2, 8, "is TESTING his open source"); |
633 | //write_ascii_string(2, 9, " EPi OSD Firmware"); |
383 | //write_ascii_string(2, 9, " EPi OSD Firmware"); |
634 | - | ||
635 | // custom char preview |
- | |
636 | /*write_char_xy( 2, 7, 200); |
- | |
637 | write_char_xy( 3, 7, 201); |
- | |
638 | write_char_xy( 4, 7, 202); |
- | |
639 | write_char_xy( 5, 7, 203); |
- | |
640 | write_char_xy( 6, 7, 204); |
- | |
641 | write_char_xy( 7, 7, 205); |
- | |
642 | write_char_xy( 8, 7, 206); |
- | |
643 | write_char_xy( 9, 7, 207); |
- | |
644 | write_char_xy(10, 7, 208); |
- | |
645 | write_char_xy(11, 7, 209); |
- | |
646 | write_char_xy(12, 7, 210); |
- | |
647 | write_char_xy(13, 7, 211); |
- | |
648 | write_char_xy(14, 7, 212); |
- | |
649 | write_char_xy(15, 7, 213); |
- | |
650 | write_char_xy(16, 7, 214); |
- | |
651 | write_char_xy(17, 7, 215);*/ |
- | |
652 | 384 | ||
653 | // we are ready |
385 | // we are ready |
654 | LED3_ON |
386 | LED3_ON |
655 | - | ||
656 | - | ||
657 | 387 | ||
658 | #if ALLCHARSDEBUG | (WRITECHARS != -1) |
388 | #if ALLCHARSDEBUG | (WRITECHARS != -1) |
659 | clear(); |
389 | clear(); |
660 | write_all_chars(); |
390 | write_all_chars(); |
661 | #else |
391 | #else |
662 | // clear serial screen |
392 | // clear serial screen |
663 | //usart1_puts("\x1B[2J\x1B[H"); |
393 | //usart1_puts("\x1B[2J\x1B[H"); |
664 | //usart1_puts("hello world!\r\n"); |
394 | //usart1_puts("hello world!\r\n"); |
665 | 395 | ||
666 | 396 | ||
667 | // request data ever 100ms from FC; |
397 | // request data ever 100ms from FC; |
668 | //usart1_request_mk_data(0, 'd', 100); |
398 | //usart1_request_mk_data(0, 'd', 100); |
669 | 399 | ||
670 | // request OSD Data from NC every 100ms |
400 | // request OSD Data from NC every 100ms |
671 | usart1_request_mk_data(1, 'o', 100); |
401 | usart1_request_mk_data(1, 'o', 100); |
672 | 402 | ||
673 | // and disable debug... |
403 | // and disable debug... |
674 | usart1_request_mk_data(0, 'd', 0); |
404 | usart1_request_mk_data(0, 'd', 0); |
675 | - | ||
676 | // disable TXD-pin |
- | |
677 | //usart1_DisableTXD(); |
- | |
678 | 405 | ||
679 | // stats for after flight |
406 | // stats for after flight |
680 | int16_t max_Altimeter = 0; |
407 | int16_t max_Altimeter = 0; |
681 | uint16_t max_GroundSpeed = 0; |
408 | uint16_t max_GroundSpeed = 0; |
682 | int16_t max_Distance = 0; |
409 | int16_t max_Distance = 0; |
683 | uint8_t min_UBat = 255; |
410 | uint8_t min_UBat = 255; |
684 | uint16_t max_FlyingTime = 0; |
411 | uint16_t max_FlyingTime = 0; |
685 | 412 | ||
686 | // flags from last round to check for changes |
413 | // flags from last round to check for changes |
687 | uint8_t old_MKFlags = 0; |
414 | uint8_t old_MKFlags = 0; |
688 | 415 | ||
689 | char* directions[8] = {"NE", "E ", "SE", "S ", "SW", "W ", "NW", "N "}; |
416 | char* directions[8] = {"NE", "E ", "SE", "S ", "SW", "W ", "NW", "N "}; |
690 | //char arrowdir[8] = {218, 217, 224, 223, 222, 221, 220, 219}; |
417 | //char arrowdir[8] = {218, 217, 224, 223, 222, 221, 220, 219}; |
691 | - | ||
692 | /*write_ndigit_number_s_10th(5, 10, 1, 100, 0); |
- | |
693 | write_ndigit_number_s_10th(5, 11, -1, 100, 0); |
- | |
694 | write_ndigit_number_s_10th(5, 12, -11, 100, 0);*/ |
- | |
695 | - | ||
696 | //write_ndigit_number_u(2,2, heading_fine_conv(34), 100, 0); |
- | |
697 | //write_char_xy(1, 2, 0xa0 + heading_fine_conv(34)); |
- | |
698 | 418 | ||
699 | while (1) { |
419 | while (1) { |
700 | // write icons at init or after menu/mode-switch |
420 | // write icons at init or after menu/mode-switch |
701 | if (!(COSD_FLAGS & COSD_ICONS_WRITTEN) && (COSD_FLAGS & COSD_FLAG_HUD)) { |
421 | if (!(COSD_FLAGS & COSD_ICONS_WRITTEN) && (COSD_FLAGS & COSD_FLAG_HUD)) { |
702 | write_char_xy(5, top_line, 0xCB); // km/h |
422 | write_char_xy(5, top_line, 0xCB); // km/h |
703 | write_char_xy(10, top_line, 0xCA); // RC-transmitter |
423 | write_char_xy(10, top_line, 0xCA); // RC-transmitter |
704 | write_char_xy(16, top_line, 0xD0); // degree symbol |
424 | write_char_xy(16, top_line, 0xD0); // degree symbol |
705 | write_char_xy(27, top_line, 0xCC); // small meters m height |
425 | write_char_xy(27, top_line, 0xCC); // small meters m height |
706 | write_char_xy(20, top_line+1, 0xB0); // left circle |
426 | write_char_xy(20, top_line+1, 0xB0); // left circle |
707 | write_char_xy(22, top_line+1, 0xB2); // right circle |
427 | write_char_xy(22, top_line+1, 0xB2); // right circle |
708 | write_char_xy(27, top_line+1, 0xCC); // small meters m home |
428 | write_char_xy(27, top_line+1, 0xCC); // small meters m home |
709 | write_char_xy(7, bottom_line, 0x9E); // small v |
429 | write_char_xy(7, bottom_line, 0x9E); // small v |
710 | write_char_xy(14, bottom_line, 0xD1); // on clock |
430 | write_char_xy(14, bottom_line, 0xD1); // on clock |
711 | write_char_xy(22, bottom_line, 0xD2); // fly clock |
431 | write_char_xy(22, bottom_line, 0xD2); // fly clock |
712 | write_char_xy(26, bottom_line, 0xC8); // sat1 |
432 | write_char_xy(26, bottom_line, 0xC8); // sat1 |
713 | write_char_xy(27, bottom_line, 0xC9); // sat2 |
433 | write_char_xy(27, bottom_line, 0xC9); // sat2 |
714 | COSD_FLAGS |= COSD_ICONS_WRITTEN; |
434 | COSD_FLAGS |= COSD_ICONS_WRITTEN; |
715 | } |
435 | } |
716 | if (rxd_buffer_locked) { |
436 | if (rxd_buffer_locked) { |
717 | if (COSD_FLAGS & COSD_FLAG_HUD) { |
437 | if (COSD_FLAGS & COSD_FLAG_HUD) { |
718 | if (rxd_buffer[2] == 'D') { // FC Data |
438 | if (rxd_buffer[2] == 'D') { // FC Data |
719 | /*Decode64(); |
439 | /*Decode64(); |
720 | debugData = *((DebugOut_t*) pRxData); |
440 | debugData = *((DebugOut_t*) pRxData); |
721 | write_number_s(12, 2, RxDataLen); |
441 | write_number_s(12, 2, RxDataLen); |
722 | write_number_s(20, 2, setsReceived++); |
442 | write_number_s(20, 2, setsReceived++); |
723 | write_number_s(12, 3, debugData.Analog[0]); // AngleNick |
443 | write_number_s(12, 3, debugData.Analog[0]); // AngleNick |
724 | write_number_s(12, 4, debugData.Analog[1]); // AngleRoll |
444 | write_number_s(12, 4, debugData.Analog[1]); // AngleRoll |
725 | write_number_s(12, 5, debugData.Analog[5]); // Height |
445 | write_number_s(12, 5, debugData.Analog[5]); // Height |
726 | write_number_s(12, 6, debugData.Analog[9]); // Voltage |
446 | write_number_s(12, 6, debugData.Analog[9]); // Voltage |
727 | write_number_s(12, 7, debugData.Analog[10]);// RC Signal |
447 | write_number_s(12, 7, debugData.Analog[10]);// RC Signal |
728 | write_number_s(12, 8, debugData.Analog[11]);// Gyro compass |
448 | write_number_s(12, 8, debugData.Analog[11]);// Gyro compass |
729 | seconds_since_last_data = 0;*/ |
449 | seconds_since_last_data = 0;*/ |
730 | } else if (rxd_buffer[2] == 'O') { // NC OSD Data |
450 | } else if (rxd_buffer[2] == 'O') { // NC OSD Data |
731 | Decode64(); |
451 | Decode64(); |
732 | naviData = *((NaviData_t*) pRxData); |
452 | naviData = *((NaviData_t*) pRxData); |
733 | 453 | ||
734 | // first line |
454 | // first line |
735 | write_ndigit_number_u(2, top_line, (uint16_t) (((uint32_t) naviData.GroundSpeed * (uint32_t)9) / (uint32_t)250), 100, 0); |
455 | write_ndigit_number_u(2, top_line, (uint16_t) (((uint32_t) naviData.GroundSpeed * (uint32_t)9) / (uint32_t)250), 100, 0); |
736 | 456 | ||
737 | write_ndigit_number_u(7, top_line, naviData.RC_Quality, 100, 0); |
457 | write_ndigit_number_u(7, top_line, naviData.RC_Quality, 100, 0); |
738 | if (naviData.RC_Quality <= RCLVL_WRN && last_RC_Quality > RCLVL_WRN) { |
458 | if (naviData.RC_Quality <= RCLVL_WRN && last_RC_Quality > RCLVL_WRN) { |
739 | for (uint8_t x = 0; x < 4; x++) |
459 | for (uint8_t x = 0; x < 4; x++) |
740 | write_char_att_xy(7 + x, top_line, BLINK); |
460 | write_char_att_xy(7 + x, top_line, BLINK); |
741 | } else if (naviData.RC_Quality > RCLVL_WRN && last_RC_Quality <= RCLVL_WRN) { |
461 | } else if (naviData.RC_Quality > RCLVL_WRN && last_RC_Quality <= RCLVL_WRN) { |
742 | for (uint8_t x = 0; x < 4; x++) |
462 | for (uint8_t x = 0; x < 4; x++) |
743 | write_char_att_xy(7 + x, top_line, 0); |
463 | write_char_att_xy(7 + x, top_line, 0); |
744 | } |
464 | } |
745 | last_RC_Quality = naviData.RC_Quality; |
465 | last_RC_Quality = naviData.RC_Quality; |
746 | 466 | ||
747 | write_ndigit_number_u(13, top_line, naviData.CompassHeading, 100, 0); |
467 | write_ndigit_number_u(13, top_line, naviData.CompassHeading, 100, 0); |
748 | 468 | ||
749 | write_ascii_string(17, top_line, directions[heading_conv(naviData.CompassHeading)]); |
469 | write_ascii_string(17, top_line, directions[heading_conv(naviData.CompassHeading)]); |
750 | 470 | ||
751 | draw_variometer(21, top_line, naviData.Variometer); |
471 | draw_variometer(21, top_line, naviData.Variometer); |
752 | 472 | ||
753 | //note:lephisto:according to several sources it's /30 |
473 | //note:lephisto:according to several sources it's /30 |
754 | if (naviData.Altimeter > 300 || naviData.Altimeter < -300) { |
474 | if (naviData.Altimeter > 300 || naviData.Altimeter < -300) { |
755 | // above 10m only write full meters |
475 | // above 10m only write full meters |
756 | write_ndigit_number_s(23, top_line, naviData.Altimeter / 30, 1000, 0); |
476 | write_ndigit_number_s(23, top_line, naviData.Altimeter / 30, 1000, 0); |
757 | } else { |
477 | } else { |
758 | // up to 10m write meters.dm |
478 | // up to 10m write meters.dm |
759 | //write_number_u_10th(21, top_line, naviData.Altimeter / 3); |
479 | //write_number_u_10th(21, top_line, naviData.Altimeter / 3); |
760 | write_ndigit_number_s_10th(23, top_line, naviData.Altimeter / 3, 100, 0); |
480 | write_ndigit_number_s_10th(23, top_line, naviData.Altimeter / 3, 100, 0); |
761 | } |
481 | } |
762 | 482 | ||
763 | // seccond line |
483 | // seccond line |
764 | draw_compass(11, top_line + 1, naviData.CompassHeading); |
484 | draw_compass(11, top_line + 1, naviData.CompassHeading); |
765 | 485 | ||
766 | // TODO: verify correctness |
486 | // TODO: verify correctness |
767 | uint16_t heading_home = (naviData.HomePositionDeviation.Bearing + 360 - naviData.CompassHeading) % 360; |
487 | uint16_t heading_home = (naviData.HomePositionDeviation.Bearing + 360 - naviData.CompassHeading) % 360; |
768 | //write_char_xy(21, top_line + 1, arrowdir[heading_conv(heading_home)]); |
488 | //write_char_xy(21, top_line + 1, arrowdir[heading_conv(heading_home)]); |
769 | // finer resolution, 0xa0 is first character and we add the index 0 <= index < 16 |
489 | // finer resolution, 0xa0 is first character and we add the index 0 <= index < 16 |
770 | write_char_xy(21, top_line + 1, 0xa0 + heading_fine_conv(heading_home)); |
490 | write_char_xy(21, top_line + 1, 0xa0 + heading_fine_conv(heading_home)); |
771 | 491 | ||
772 | write_ndigit_number_u(24, top_line + 1, naviData.HomePositionDeviation.Distance / 10, 100, 0); |
492 | write_ndigit_number_u(24, top_line + 1, naviData.HomePositionDeviation.Distance / 10, 100, 0); |
773 | 493 | ||
774 | // center |
494 | // center |
775 | if (naviData.MKFlags & FLAG_MOTOR_RUN) { // should be engines running |
495 | if (naviData.MKFlags & FLAG_MOTOR_RUN) { // should be engines running |
776 | if (!(old_MKFlags & FLAG_MOTOR_RUN)) { // motors just started, clear middle |
496 | if (!(old_MKFlags & FLAG_MOTOR_RUN)) { // motors just started, clear middle |
777 | clear(); |
497 | clear(); |
778 | // update flags to paint display again if needed |
498 | // update flags to paint display again if needed |
779 | COSD_FLAGS &= ~COSD_ICONS_WRITTEN; |
499 | COSD_FLAGS &= ~COSD_ICONS_WRITTEN; |
780 | } |
500 | } |
781 | if (COSD_FLAGS & COSD_FLAG_ARTHORIZON) { |
501 | if (COSD_FLAGS & COSD_FLAG_ARTHORIZON) { |
782 | draw_artificial_horizon(top_line + 2, bottom_line - 1, naviData.AngleNick, naviData.AngleRoll); |
502 | draw_artificial_horizon(top_line + 2, bottom_line - 1, naviData.AngleNick, naviData.AngleRoll); |
783 | } |
503 | } |
784 | } else { |
504 | } else { |
785 | // stats |
505 | // stats |
786 | if (COSD_FLAGS & COSD_FLAG_STATS) { |
506 | if (COSD_FLAGS & COSD_FLAG_STATS) { |
787 | write_ascii_string_pgm(2, 5, stats_item_pointers[0]); // max Altitude |
507 | write_ascii_string_pgm(2, 5, stats_item_pointers[0]); // max Altitude |
788 | write_ndigit_number_s(18, 5, max_Altimeter / 30, 1000, 0); |
508 | write_ndigit_number_s(18, 5, max_Altimeter / 30, 1000, 0); |
789 | write_char_xy(22, 5, 204); // small meters m |
509 | write_char_xy(22, 5, 204); // small meters m |
790 | write_ascii_string_pgm(2, 6, stats_item_pointers[1]); // max Speed |
510 | write_ascii_string_pgm(2, 6, stats_item_pointers[1]); // max Speed |
791 | write_ndigit_number_u(19, 6, (uint16_t) (((uint32_t) max_GroundSpeed * 36) / 1000), 100, 0); |
511 | write_ndigit_number_u(19, 6, (uint16_t) (((uint32_t) max_GroundSpeed * 36) / 1000), 100, 0); |
792 | write_char_xy(22, 6, 203); // km/h |
512 | write_char_xy(22, 6, 203); // km/h |
793 | write_ascii_string_pgm(2, 7, stats_item_pointers[2]); // max Distance |
513 | write_ascii_string_pgm(2, 7, stats_item_pointers[2]); // max Distance |
794 | write_ndigit_number_u(19, 7, max_Distance / 100, 100, 0); |
514 | write_ndigit_number_u(19, 7, max_Distance / 100, 100, 0); |
795 | write_char_xy(22, 7, 204); // small meters m |
515 | write_char_xy(22, 7, 204); // small meters m |
796 | write_ascii_string_pgm(2, 8, stats_item_pointers[3]); // min voltage |
516 | write_ascii_string_pgm(2, 8, stats_item_pointers[3]); // min voltage |
797 | write_ndigit_number_u_10th(18, 8, min_UBat, 100, 0); |
517 | write_ndigit_number_u_10th(18, 8, min_UBat, 100, 0); |
798 | write_char_xy(22, 8, 0x9E); // small v |
518 | write_char_xy(22, 8, 0x9E); // small v |
799 | write_ascii_string_pgm(2, 9, stats_item_pointers[4]); // max time |
519 | write_ascii_string_pgm(2, 9, stats_item_pointers[4]); // max time |
800 | write_time(16, 9, max_FlyingTime); |
520 | write_time(16, 9, max_FlyingTime); |
801 | write_char_xy(22, 9, 210); // fly clock |
521 | write_char_xy(22, 9, 210); // fly clock |
802 | } else if (COSD_FLAGS & COSD_FLAG_ARTHORIZON) { // if no stats there is space horizon |
522 | } else if (COSD_FLAGS & COSD_FLAG_ARTHORIZON) { // if no stats there is space horizon |
803 | draw_artificial_horizon(top_line + 2, bottom_line - 1, naviData.AngleNick, naviData.AngleRoll); |
523 | draw_artificial_horizon(top_line + 2, bottom_line - 1, naviData.AngleNick, naviData.AngleRoll); |
804 | } |
524 | } |
805 | } |
525 | } |
806 | if (COSD_FLAGS & COSD_FLAG_BIGVARIO) { |
526 | if (COSD_FLAGS & COSD_FLAG_BIGVARIO) { |
807 | draw_big_variometer(27, 8, naviData.Variometer); |
527 | draw_big_variometer(27, 8, naviData.Variometer); |
808 | } |
528 | } |
809 | 529 | ||
810 | // bottom line |
530 | // bottom line |
811 | draw_battery(2, bottom_line, naviData.UBat); |
531 | draw_battery(2, bottom_line, naviData.UBat); |
812 | write_ndigit_number_u_10th(3, bottom_line, naviData.UBat, 100, 0); |
532 | write_ndigit_number_u_10th(3, bottom_line, naviData.UBat, 100, 0); |
813 | if (naviData.UBat <= UBAT_WRN && last_UBat > UBAT_WRN) { |
533 | if (naviData.UBat <= UBAT_WRN && last_UBat > UBAT_WRN) { |
814 | for (uint8_t x = 2; x < 8; x++) |
534 | for (uint8_t x = 2; x < 8; x++) |
815 | write_char_att_xy(x, bottom_line, BLINK); |
535 | write_char_att_xy(x, bottom_line, BLINK); |
816 | } else { |
536 | } else { |
817 | for (uint8_t x = 2; x < 8; x++) |
537 | for (uint8_t x = 2; x < 8; x++) |
818 | write_char_att_xy(x, bottom_line, 0); |
538 | write_char_att_xy(x, bottom_line, 0); |
819 | } |
539 | } |
820 | 540 | ||
821 | 541 | ||
822 | write_time(8, bottom_line, uptime); |
542 | write_time(8, bottom_line, uptime); |
823 | write_time(16, bottom_line, naviData.FlyingTime); |
543 | write_time(16, bottom_line, naviData.FlyingTime); |
824 | 544 | ||
825 | write_ndigit_number_u(24, bottom_line, naviData.SatsInUse, 10, 0); |
545 | write_ndigit_number_u(24, bottom_line, naviData.SatsInUse, 10, 0); |
826 | 546 | ||
827 | if (naviData.NCFlags & NC_FLAG_CH) { |
547 | if (naviData.NCFlags & NC_FLAG_CH) { |
828 | write_char_xy(27, bottom_line, 231); // gps ch |
548 | write_char_xy(27, bottom_line, 231); // gps ch |
829 | } else if (naviData.NCFlags & NC_FLAG_PH) { |
549 | } else if (naviData.NCFlags & NC_FLAG_PH) { |
830 | write_char_xy(27, bottom_line, 230); // gps ph |
550 | write_char_xy(27, bottom_line, 230); // gps ph |
831 | } else { // (naviData.NCFlags & NC_FLAG_FREE) |
551 | } else { // (naviData.NCFlags & NC_FLAG_FREE) |
832 | write_char_xy(27, bottom_line, 201); // sat2 (free) |
552 | write_char_xy(27, bottom_line, 201); // sat2 (free) |
833 | } |
553 | } |
834 | 554 | ||
835 | //write_number_s(8, 5, RxDataLen); |
555 | //write_number_s(8, 5, RxDataLen); |
836 | //write_number_s(16, 5, setsReceived++); |
556 | //write_number_s(16, 5, setsReceived++); |
837 | 557 | ||
838 | // remember statistics |
558 | // remember statistics |
839 | if (naviData.Altimeter > max_Altimeter) max_Altimeter = naviData.Altimeter; |
559 | if (naviData.Altimeter > max_Altimeter) max_Altimeter = naviData.Altimeter; |
840 | if (naviData.GroundSpeed > max_GroundSpeed) max_GroundSpeed = naviData.GroundSpeed; |
560 | if (naviData.GroundSpeed > max_GroundSpeed) max_GroundSpeed = naviData.GroundSpeed; |
841 | if (naviData.HomePositionDeviation.Distance > max_Distance) { |
561 | if (naviData.HomePositionDeviation.Distance > max_Distance) { |
842 | max_Distance = naviData.HomePositionDeviation.Distance; |
562 | max_Distance = naviData.HomePositionDeviation.Distance; |
843 | } |
563 | } |
844 | if (naviData.UBat < min_UBat) min_UBat = naviData.UBat; |
564 | if (naviData.UBat < min_UBat) min_UBat = naviData.UBat; |
845 | if (naviData.FlyingTime > max_FlyingTime) max_FlyingTime = naviData.FlyingTime; |
565 | if (naviData.FlyingTime > max_FlyingTime) max_FlyingTime = naviData.FlyingTime; |
846 | 566 | ||
847 | old_MKFlags = naviData.MKFlags; |
567 | old_MKFlags = naviData.MKFlags; |
848 | seconds_since_last_data = 0; |
568 | seconds_since_last_data = 0; |
849 | } |
569 | } |
850 | } |
570 | } |
851 | rxd_buffer_locked = 0; |
571 | rxd_buffer_locked = 0; |
852 | } |
572 | } |
853 | // handle keypress |
573 | // handle keypress |
854 | if (s1_pressed()) { |
574 | if (s1_pressed()) { |
855 | config_menu(); |
575 | config_menu(); |
856 | } |
576 | } |
857 | if (seconds_since_last_data > 2) { |
577 | if (seconds_since_last_data > 2) { |
858 | /*if (COSD_FLAGS & COSD_FLAG_HUD) { |
- | |
859 | write_ascii_string(2, 3, "ERROR: NO DATA for"); |
- | |
860 | write_time(21, 3, seconds_since_last_data); |
- | |
861 | }*/ |
- | |
862 | // request OSD Data from NC every 100ms |
578 | // request OSD Data from NC every 100ms |
863 | usart1_request_mk_data(1, 'o', 100); |
579 | usart1_request_mk_data(1, 'o', 100); |
864 | _delay_ms(200); |
- | |
865 | //seconds_since_last_data = 0; |
580 | seconds_since_last_data = 0; |
866 | } |
581 | } |
867 | } |
582 | } |
868 | #endif |
583 | #endif |
869 | return 0; |
584 | return 0; |
870 | } |
585 | } |
871 | 586 |