Rev 453 | Rev 455 | Go to most recent revision | Only display areas with differences | Ignore whitespace | Details | Blame | Last modification | View Log | RSS feed
Rev 453 | Rev 454 | ||
---|---|---|---|
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 | #include "osd_helpers.h" |
36 | 36 | ||
37 | /* TODO: |
37 | /* TODO: |
38 | * - verifiy correctness of values |
38 | * - verifiy correctness of values |
39 | * - clean up code :) |
39 | * - clean up code :) |
40 | */ |
40 | */ |
41 | 41 | ||
42 | #if !(ALLCHARSDEBUG|(WRITECHARS != -1)) |
42 | #if !(ALLCHARSDEBUG|(WRITECHARS != -1)) |
43 | // data structs not needed for character flashin |
43 | // data structs not needed for character flashin |
44 | #include "mk-data-structs.h" |
44 | #include "mk-data-structs.h" |
45 | 45 | ||
46 | /* ########################################################################## |
46 | /* ########################################################################## |
47 | * global definitions and global vars |
47 | * global definitions and global vars |
48 | * ##########################################################################*/ |
48 | * ##########################################################################*/ |
49 | 49 | ||
50 | volatile uint16_t setsReceived = 0; |
50 | volatile uint16_t setsReceived = 0; |
51 | 51 | ||
52 | volatile NaviData_t naviData; |
52 | volatile NaviData_t naviData; |
53 | volatile DebugOut_t debugData; |
53 | volatile DebugOut_t debugData; |
54 | 54 | ||
55 | // cache old vars for blinking attribute, checkup is faster than full |
55 | // cache old vars for blinking attribute, checkup is faster than full |
56 | // attribute write each time |
56 | // attribute write each time |
57 | volatile uint8_t last_UBat = 255; |
57 | volatile uint8_t last_UBat = 255; |
58 | volatile uint8_t last_RC_Quality = 255; |
58 | volatile uint8_t last_RC_Quality = 255; |
59 | 59 | ||
60 | // 16bit should be enough, normal LiPos don't last that long |
60 | // 16bit should be enough, normal LiPos don't last that long |
61 | volatile uint16_t uptime = 0; |
61 | volatile uint16_t uptime = 0; |
62 | volatile uint16_t timer = 0; |
62 | volatile uint16_t timer = 0; |
63 | 63 | ||
64 | // remember last time data was received |
64 | // remember last time data was received |
65 | volatile uint8_t seconds_since_last_data = 0; |
65 | volatile uint8_t seconds_since_last_data = 0; |
66 | 66 | ||
67 | // store stats description in progmem to save space |
67 | // store stats description in progmem to save space |
68 | char stats_item_0[] PROGMEM = "max Altitude:"; |
68 | char stats_item_0[] PROGMEM = "max Altitude:"; |
69 | char stats_item_1[] PROGMEM = "max Speed :"; |
69 | char stats_item_1[] PROGMEM = "max Speed :"; |
70 | char stats_item_2[] PROGMEM = "max Distance:"; |
70 | char stats_item_2[] PROGMEM = "max Distance:"; |
71 | char stats_item_3[] PROGMEM = "min voltage :"; |
71 | char stats_item_3[] PROGMEM = "min voltage :"; |
72 | char stats_item_4[] PROGMEM = "max time :"; |
72 | char stats_item_4[] PROGMEM = "max time :"; |
73 | char stats_item_5[] PROGMEM = "longitude :"; |
73 | char stats_item_5[] PROGMEM = "longitude :"; |
74 | char stats_item_6[] PROGMEM = "latitude :"; |
74 | char stats_item_6[] PROGMEM = "latitude :"; |
75 | char* stats_item_pointers[] PROGMEM = {stats_item_0, stats_item_1, stats_item_2, |
75 | char* stats_item_pointers[] PROGMEM = {stats_item_0, stats_item_1, stats_item_2, |
76 | stats_item_3, stats_item_4, stats_item_5, stats_item_6}; |
76 | stats_item_3, stats_item_4, stats_item_5, stats_item_6}; |
77 | 77 | ||
78 | // store more fixed strings in progmen |
78 | // store more fixed strings in progmen |
79 | char ON[] PROGMEM = "ON "; |
79 | char ON[] PROGMEM = "ON "; |
80 | char OFF[] PROGMEM = "OFF"; |
80 | char OFF[] PROGMEM = "OFF"; |
81 | 81 | ||
82 | #endif // ends !(ALLCHARSDEBUG|(WRITECHARS != -1)) |
82 | #endif // ends !(ALLCHARSDEBUG|(WRITECHARS != -1)) |
83 | 83 | ||
84 | // general PAL|NTSC distingiusch stuff |
84 | // general PAL|NTSC distingiusch stuff |
85 | uint8_t top_line = 1; |
85 | uint8_t top_line = 1; |
86 | uint8_t bottom_line = 14; |
86 | uint8_t bottom_line = 14; |
87 | 87 | ||
88 | // battery voltages |
88 | // battery voltages |
89 | uint8_t min_voltage = 0; |
89 | uint8_t min_voltage = 0; |
90 | uint8_t max_voltage = 0; |
90 | uint8_t max_voltage = 0; |
91 | 91 | ||
92 | // Flags |
92 | // Flags |
93 | uint8_t COSD_FLAGS = 0; |
93 | uint8_t COSD_FLAGS = 0; |
94 | 94 | ||
95 | /* ########################################################################## |
95 | /* ########################################################################## |
96 | * debounce buttons |
96 | * debounce buttons |
97 | * ##########################################################################*/ |
97 | * ##########################################################################*/ |
98 | int s1_pressed() { |
98 | int s1_pressed() { |
99 | if (S1_PRESSED) { |
99 | if (S1_PRESSED) { |
100 | _delay_ms(25); |
100 | _delay_ms(25); |
101 | if (S1_PRESSED) return 1; |
101 | if (S1_PRESSED) return 1; |
102 | } |
102 | } |
103 | return 0; |
103 | return 0; |
104 | } |
104 | } |
105 | 105 | ||
106 | int s2_pressed() { |
106 | int s2_pressed() { |
107 | if (S2_PRESSED) { |
107 | if (S2_PRESSED) { |
108 | _delay_ms(25); |
108 | _delay_ms(25); |
109 | if (S2_PRESSED) return 1; |
109 | if (S2_PRESSED) return 1; |
110 | } |
110 | } |
111 | return 0; |
111 | return 0; |
112 | } |
112 | } |
113 | 113 | ||
114 | /* ########################################################################## |
114 | /* ########################################################################## |
115 | * Interrupt handler |
115 | * Interrupt handler |
116 | * ##########################################################################*/ |
116 | * ##########################################################################*/ |
117 | /** |
117 | /** |
118 | * handler for undefined Interrupts |
118 | * handler for undefined Interrupts |
119 | * if not defined AVR will reset in case any unhandled interrupts occur |
119 | * if not defined AVR will reset in case any unhandled interrupts occur |
120 | */ |
120 | */ |
121 | ISR(__vector_default) { |
121 | ISR(__vector_default) { |
122 | asm("nop"); |
122 | asm("nop"); |
123 | } |
123 | } |
124 | 124 | ||
125 | #if !(ALLCHARSDEBUG|(WRITECHARS != -1)) |
125 | #if !(ALLCHARSDEBUG|(WRITECHARS != -1)) |
126 | /* ########################################################################## |
126 | /* ########################################################################## |
127 | * timer stuff |
127 | * timer stuff |
128 | * ##########################################################################*/ |
128 | * ##########################################################################*/ |
129 | /** |
129 | /** |
130 | * timer kicks in every 1000uS ^= 1ms |
130 | * timer kicks in every 1000uS ^= 1ms |
131 | */ |
131 | */ |
132 | ISR(TIMER0_OVF_vect) { |
132 | ISR(TIMER0_OVF_vect) { |
133 | OCR0 = 15; // preload |
133 | OCR0 = 15; // preload |
134 | if (!timer--) { |
134 | if (!timer--) { |
135 | uptime++; |
135 | uptime++; |
136 | timer = 999; |
136 | timer = 999; |
137 | seconds_since_last_data++; |
137 | seconds_since_last_data++; |
138 | } |
138 | } |
139 | } |
139 | } |
140 | 140 | ||
141 | 141 | ||
142 | /* ########################################################################## |
142 | /* ########################################################################## |
143 | * A simple config menu for the flags |
143 | * A simple config menu for the flags |
144 | * ##########################################################################*/ |
144 | * ##########################################################################*/ |
145 | 145 | ||
146 | /** |
146 | /** |
147 | * helper function for menu updating |
147 | * helper function for menu updating |
148 | */ |
148 | */ |
149 | void config_menu_drawings(uint8_t chosen) { |
149 | void config_menu_drawings(uint8_t chosen) { |
150 | // clear prevoius _cursor_ |
150 | // clear prevoius _cursor_ |
151 | write_ascii_string(3, (chosen + 5) % 8, " "); |
151 | write_ascii_string(3, (chosen + 5) % 8, " "); |
152 | // draw current _cursor_ |
152 | // draw current _cursor_ |
153 | write_ascii_string(3, chosen + 5, ">"); |
153 | write_ascii_string(3, chosen + 5, ">"); |
154 | if (COSD_FLAGS & COSD_FLAG_HUD) { |
154 | if (COSD_FLAGS & COSD_FLAG_HUD) { |
155 | write_ascii_string_pgm(23, 5, ON); |
155 | write_ascii_string_pgm(23, 5, ON); |
156 | } else { |
156 | } else { |
157 | write_ascii_string_pgm(23, 5, OFF); |
157 | write_ascii_string_pgm(23, 5, OFF); |
158 | } |
158 | } |
159 | if (COSD_FLAGS & COSD_FLAG_ARTHORIZON) { |
159 | if (COSD_FLAGS & COSD_FLAG_ARTHORIZON) { |
160 | write_ascii_string_pgm(23, 6, ON); |
160 | write_ascii_string_pgm(23, 6, ON); |
161 | } else { |
161 | } else { |
162 | write_ascii_string_pgm(23, 6, OFF); |
162 | write_ascii_string_pgm(23, 6, OFF); |
163 | } |
163 | } |
164 | if (COSD_FLAGS & COSD_FLAG_BIGVARIO) { |
164 | if (COSD_FLAGS & COSD_FLAG_BIGVARIO) { |
165 | write_ascii_string_pgm(23, 7, ON); |
165 | write_ascii_string_pgm(23, 7, ON); |
166 | } else { |
166 | } else { |
167 | write_ascii_string_pgm(23, 7, OFF); |
167 | write_ascii_string_pgm(23, 7, OFF); |
168 | } |
168 | } |
169 | if (COSD_FLAGS & COSD_FLAG_STATS) { |
169 | if (COSD_FLAGS & COSD_FLAG_STATS) { |
170 | write_ascii_string_pgm(23, 8, ON); |
170 | write_ascii_string_pgm(23, 8, ON); |
171 | } else { |
171 | } else { |
172 | write_ascii_string_pgm(23, 8, OFF); |
172 | write_ascii_string_pgm(23, 8, OFF); |
173 | } |
173 | } |
174 | if (COSD_FLAGS & COSD_FLAG_WARNINGS) { |
174 | if (COSD_FLAGS & COSD_FLAG_WARNINGS) { |
175 | write_ascii_string_pgm(23, 9, ON); |
175 | write_ascii_string_pgm(23, 9, ON); |
176 | } else { |
176 | } else { |
177 | write_ascii_string_pgm(23, 9, OFF); |
177 | write_ascii_string_pgm(23, 9, OFF); |
178 | } |
178 | } |
179 | } |
179 | } |
180 | 180 | ||
181 | /** |
181 | /** |
182 | * some sort of clicking response in the menu |
182 | * some sort of clicking response in the menu |
183 | */ |
183 | */ |
184 | void config_menu_doclick(uint8_t chosen, char** menu) { |
184 | void config_menu_doclick(uint8_t chosen, char** menu) { |
185 | write_ascii_string(4, chosen + 5, "DONE "); |
185 | write_ascii_string(4, chosen + 5, "DONE "); |
186 | _delay_ms(1000); |
186 | _delay_ms(1000); |
187 | write_ascii_string(4, chosen + 5, menu[chosen]); |
187 | write_ascii_string(4, chosen + 5, menu[chosen]); |
188 | } |
188 | } |
189 | 189 | ||
190 | /** |
190 | /** |
191 | * a simple config menu tryout |
191 | * a simple config menu tryout |
192 | */ |
192 | */ |
193 | void config_menu(void) { |
193 | void config_menu(void) { |
194 | // disable interrupts (makes the menu more smoothely) |
194 | // disable interrupts (makes the menu more smoothely) |
195 | cli(); |
195 | cli(); |
196 | 196 | ||
197 | // clear screen |
197 | // clear screen |
198 | clear(); |
198 | clear(); |
199 | 199 | ||
200 | char* menu[9] = {"Full HUD", |
200 | char* menu[9] = {"Full HUD", |
201 | "Art.Horizon in HUD", |
201 | "Art.Horizon in HUD", |
202 | "Big Vario bar", |
202 | "Big Vario bar", |
203 | "Statistics", |
203 | "Statistics", |
204 | "Warnings", // TODO: do it! |
204 | "Warnings", // TODO: do it! |
205 | "Reset uptime", |
205 | "Reset uptime", |
206 | "Request OSD-data", |
206 | "Request OSD-data", |
207 | "Disable Debug-data", |
207 | "Disable Debug-data", |
208 | "EXIT"}; |
208 | "EXIT"}; |
209 | 209 | ||
210 | uint8_t inmenu = 1; |
210 | uint8_t inmenu = 1; |
211 | uint8_t chosen = 0; |
211 | uint8_t chosen = 0; |
212 | write_ascii_string(6, 2, "C-OSD Config Menu"); |
212 | write_ascii_string(6, 2, "C-OSD Config Menu"); |
213 | 213 | ||
214 | // wait a bit before doing stuff so user has chance to release button |
214 | // wait a bit before doing stuff so user has chance to release button |
215 | _delay_ms(250); |
215 | _delay_ms(250); |
216 | 216 | ||
217 | write_ascii_string(4, 5, menu[0]); |
217 | write_ascii_string(4, 5, menu[0]); |
218 | write_ascii_string(4, 6, menu[1]); |
218 | write_ascii_string(4, 6, menu[1]); |
219 | write_ascii_string(4, 7, menu[2]); |
219 | write_ascii_string(4, 7, menu[2]); |
220 | write_ascii_string(4, 8, menu[3]); |
220 | write_ascii_string(4, 8, menu[3]); |
221 | write_ascii_string(4, 9, menu[4]); |
221 | write_ascii_string(4, 9, menu[4]); |
222 | write_ascii_string(4, 10, menu[5]); |
222 | write_ascii_string(4, 10, menu[5]); |
223 | write_ascii_string(4, 11, menu[6]); |
223 | write_ascii_string(4, 11, menu[6]); |
224 | write_ascii_string(4, 12, menu[7]); |
224 | write_ascii_string(4, 12, menu[7]); |
225 | write_ascii_string(4, 13, menu[8]); |
225 | write_ascii_string(4, 13, menu[8]); |
226 | 226 | ||
227 | config_menu_drawings(chosen); |
227 | config_menu_drawings(chosen); |
228 | 228 | ||
229 | while (inmenu) { |
229 | while (inmenu) { |
230 | if (s2_pressed()) { |
230 | if (s2_pressed()) { |
231 | write_ascii_string(3, chosen+5, " "); |
231 | write_ascii_string(3, chosen+5, " "); |
232 | chosen = (chosen + 1) % 9; |
232 | chosen = (chosen + 1) % 9; |
233 | write_ascii_string(3, chosen+5, ">"); |
233 | write_ascii_string(3, chosen+5, ">"); |
234 | _delay_ms(500); |
234 | _delay_ms(500); |
235 | } else if (s1_pressed()) { |
235 | } else if (s1_pressed()) { |
236 | switch (chosen) { |
236 | switch (chosen) { |
237 | case 0: // full HUD |
237 | case 0: // full HUD |
238 | COSD_FLAGS ^= COSD_FLAG_HUD; |
238 | COSD_FLAGS ^= COSD_FLAG_HUD; |
239 | config_menu_drawings(chosen); |
239 | config_menu_drawings(chosen); |
240 | break; |
240 | break; |
241 | case 1: // art horizon |
241 | case 1: // art horizon |
242 | COSD_FLAGS ^= COSD_FLAG_ARTHORIZON; |
242 | COSD_FLAGS ^= COSD_FLAG_ARTHORIZON; |
243 | config_menu_drawings(chosen); |
243 | config_menu_drawings(chosen); |
244 | break; |
244 | break; |
245 | case 2: // big vario |
245 | case 2: // big vario |
246 | COSD_FLAGS ^= COSD_FLAG_BIGVARIO; |
246 | COSD_FLAGS ^= COSD_FLAG_BIGVARIO; |
247 | config_menu_drawings(chosen); |
247 | config_menu_drawings(chosen); |
248 | break; |
248 | break; |
249 | case 3: // statistics |
249 | case 3: // statistics |
250 | COSD_FLAGS ^= COSD_FLAG_STATS; |
250 | COSD_FLAGS ^= COSD_FLAG_STATS; |
251 | config_menu_drawings(chosen); |
251 | config_menu_drawings(chosen); |
252 | break; |
252 | break; |
253 | case 4: // warnings |
253 | case 4: // warnings |
254 | COSD_FLAGS ^= COSD_FLAG_WARNINGS; |
254 | COSD_FLAGS ^= COSD_FLAG_WARNINGS; |
255 | config_menu_drawings(chosen); |
255 | config_menu_drawings(chosen); |
256 | break; |
256 | break; |
257 | case 5: // reset uptime |
257 | case 5: // reset uptime |
258 | uptime = 0; |
258 | uptime = 0; |
259 | config_menu_doclick(chosen, menu); |
259 | config_menu_doclick(chosen, menu); |
260 | break; |
260 | break; |
261 | case 6: // re-request OSD data |
261 | case 6: // re-request OSD data |
- | 262 | #if FCONLY |
|
- | 263 | // request data ever 100ms from FC; |
|
- | 264 | usart1_request_mk_data(0, 'd', 100); |
|
- | 265 | #else |
|
262 | // request OSD Data from NC every 100ms |
266 | // request OSD Data from NC every 100ms |
263 | usart1_request_mk_data(1, 'o', 100); |
267 | usart1_request_mk_data(1, 'o', 100); |
- | 268 | ||
- | 269 | // and disable debug... |
|
- | 270 | usart1_request_mk_data(0, 'd', 0); |
|
- | 271 | #endif |
|
264 | config_menu_doclick(chosen, menu); |
272 | config_menu_doclick(chosen, menu); |
265 | break; |
273 | break; |
266 | case 7: // disable debug data |
274 | case 7: // disable debug data |
267 | // disable sending of debug data |
275 | // disable sending of debug data |
268 | // may result in smoother ddata display |
276 | // may result in smoother ddata display |
269 | usart1_request_mk_data(0, 'd', 0); |
277 | usart1_request_mk_data(0, 'd', 0); |
270 | config_menu_doclick(chosen, menu); |
278 | config_menu_doclick(chosen, menu); |
271 | break; |
279 | break; |
272 | case 8: // exit |
280 | case 8: // exit |
273 | inmenu = 0; |
281 | inmenu = 0; |
274 | break; |
282 | break; |
275 | } |
283 | } |
276 | _delay_ms(250); |
284 | _delay_ms(250); |
277 | } |
285 | } |
278 | } |
286 | } |
279 | 287 | ||
280 | // clear screen up again |
288 | // clear screen up again |
281 | clear(); |
289 | clear(); |
282 | 290 | ||
283 | // update flags to paint display again if needed |
291 | // update flags to paint display again if needed |
284 | COSD_FLAGS &= ~COSD_ICONS_WRITTEN; |
292 | COSD_FLAGS &= ~COSD_ICONS_WRITTEN; |
285 | 293 | ||
286 | // enable interrupts again |
294 | // enable interrupts again |
287 | sei(); |
295 | sei(); |
288 | } |
296 | } |
289 | 297 | ||
290 | #endif // ends !(ALLCHARSDEBUG|(WRITECHARS != -1)) |
298 | #endif // ends !(ALLCHARSDEBUG|(WRITECHARS != -1)) |
291 | /* ########################################################################## |
299 | /* ########################################################################## |
292 | * MAIN |
300 | * MAIN |
293 | * ##########################################################################*/ |
301 | * ##########################################################################*/ |
294 | int main(void) { |
302 | int main(void) { |
295 | // set up FLAGS, compiler should flatten this one |
303 | // set up FLAGS, compiler should flatten this one |
296 | COSD_FLAGS = (NTSC << 0); |
304 | COSD_FLAGS = (NTSC << 0); |
297 | COSD_FLAGS |= (HUD << 1); |
305 | COSD_FLAGS |= (HUD << 1); |
298 | COSD_FLAGS |= (ARTHORIZON << 2); |
306 | COSD_FLAGS |= (ARTHORIZON << 2); |
299 | COSD_FLAGS |= (BIGVARIO << 3); |
307 | COSD_FLAGS |= (BIGVARIO << 3); |
300 | COSD_FLAGS |= (STATS << 4); |
308 | COSD_FLAGS |= (STATS << 4); |
301 | COSD_FLAGS |= (WARNINGS << 5); |
309 | COSD_FLAGS |= (WARNINGS << 5); |
302 | 310 | ||
303 | // set up Atmega162 Ports |
311 | // set up Atmega162 Ports |
304 | DDRA |= (1 << PA1); // PA1 output (/CS) |
312 | DDRA |= (1 << PA1); // PA1 output (/CS) |
305 | MAX_CS_HIGH |
313 | MAX_CS_HIGH |
306 | DDRA |= (1 << PA2); // PA2 output (SDIN) |
314 | DDRA |= (1 << PA2); // PA2 output (SDIN) |
307 | MAX_SDIN_LOW |
315 | MAX_SDIN_LOW |
308 | DDRA |= (1 << PA3); // PA3 output (SCLK) |
316 | DDRA |= (1 << PA3); // PA3 output (SCLK) |
309 | MAX_SCLK_LOW |
317 | MAX_SCLK_LOW |
310 | DDRA |= (1 << PA5); // PA5 output (RESET) |
318 | DDRA |= (1 << PA5); // PA5 output (RESET) |
311 | MAX_RESET_HIGH |
319 | MAX_RESET_HIGH |
312 | 320 | ||
313 | DDRC |= (1 << PC0); // PC0 output (LED1 gn) |
321 | DDRC |= (1 << PC0); // PC0 output (LED1 gn) |
314 | LED1_OFF |
322 | LED1_OFF |
315 | DDRC |= (1 << PC1); // PC1 output (LED2 rt) |
323 | DDRC |= (1 << PC1); // PC1 output (LED2 rt) |
316 | LED2_OFF |
324 | LED2_OFF |
317 | DDRC |= (1 << PC2); // PC2 output (LED3 gn) |
325 | DDRC |= (1 << PC2); // PC2 output (LED3 gn) |
318 | LED3_OFF |
326 | LED3_OFF |
319 | DDRC |= (1 << PC3); // PC3 output (LED4 rt) |
327 | DDRC |= (1 << PC3); // PC3 output (LED4 rt) |
320 | LED4_OFF |
328 | LED4_OFF |
321 | 329 | ||
322 | DDRC &= ~(1 << PC4); // PC4 input (MODE) |
330 | DDRC &= ~(1 << PC4); // PC4 input (MODE) |
323 | PORTC |= (1 << PC4); // pullup |
331 | PORTC |= (1 << PC4); // pullup |
324 | DDRC &= ~(1 << PC5); // PC5 input (SET) |
332 | DDRC &= ~(1 << PC5); // PC5 input (SET) |
325 | PORTC |= (1 << PC5); // pullup |
333 | PORTC |= (1 << PC5); // pullup |
326 | 334 | ||
327 | // set up top and bottom lines |
335 | // set up top and bottom lines |
328 | if (COSD_FLAGS & COSD_FLAG_NTSC) { |
336 | if (COSD_FLAGS & COSD_FLAG_NTSC) { |
329 | bottom_line = 12; |
337 | bottom_line = 12; |
330 | } else { |
338 | } else { |
331 | bottom_line = 14; |
339 | bottom_line = 14; |
332 | } |
340 | } |
333 | 341 | ||
334 | // reset the MAX7456 to be sure any undefined states do no harm |
342 | // reset the MAX7456 to be sure any undefined states do no harm |
335 | MAX_RESET_LOW |
343 | MAX_RESET_LOW |
336 | MAX_RESET_HIGH |
344 | MAX_RESET_HIGH |
337 | 345 | ||
338 | // give the FC/NC and the maxim time to come up |
346 | // give the FC/NC and the maxim time to come up |
339 | LED4_ON |
347 | LED4_ON |
340 | _delay_ms(2000); |
348 | _delay_ms(2000); |
341 | 349 | ||
342 | LED4_OFF |
350 | LED4_OFF |
343 | 351 | ||
344 | 352 | ||
345 | //Pushing NEW chars to the MAX7456 |
353 | //Pushing NEW chars to the MAX7456 |
346 | #if (WRITECHARS != -1) |
354 | #if (WRITECHARS != -1) |
347 | // DISABLE display (VM0) |
355 | // DISABLE display (VM0) |
348 | spi_send_byte(0x00, 0b00000000); |
356 | spi_send_byte(0x00, 0b00000000); |
349 | #include "characters.c" |
357 | #include "characters.c" |
350 | 358 | ||
351 | #endif |
359 | #endif |
352 | 360 | ||
353 | // Setup Video Mode |
361 | // Setup Video Mode |
354 | if (COSD_FLAGS & COSD_FLAG_NTSC) { |
362 | if (COSD_FLAGS & COSD_FLAG_NTSC) { |
355 | // NTSC + enable display immediately (VM0) |
363 | // NTSC + enable display immediately (VM0) |
356 | spi_send_byte(0x00, 0b00001000); |
364 | spi_send_byte(0x00, 0b00001000); |
357 | } else { |
365 | } else { |
358 | // PAL + enable display immediately (VM0) |
366 | // PAL + enable display immediately (VM0) |
359 | spi_send_byte(0x00, 0b01001000); |
367 | spi_send_byte(0x00, 0b01001000); |
360 | } |
368 | } |
361 | 369 | ||
362 | /*// clear all display-mem (DMM) |
370 | /*// clear all display-mem (DMM) |
363 | spi_send_byte(0x04, 0b00000100); |
371 | spi_send_byte(0x04, 0b00000100); |
364 | 372 | ||
365 | // clearing takes 12uS according to maxim so lets wait longer |
373 | // clearing takes 12uS according to maxim so lets wait longer |
366 | _delay_us(120); |
374 | _delay_us(120); |
367 | 375 | ||
368 | // 8bit mode |
376 | // 8bit mode |
369 | spi_send_byte(0x04, 0b01000000);*/ |
377 | spi_send_byte(0x04, 0b01000000);*/ |
370 | 378 | ||
371 | // clear display memory and set to 8bit mode |
379 | // clear display memory and set to 8bit mode |
372 | clear(); |
380 | clear(); |
373 | 381 | ||
374 | #if !(ALLCHARSDEBUG|(WRITECHARS != -1)) |
382 | #if !(ALLCHARSDEBUG|(WRITECHARS != -1)) |
375 | // init usart |
383 | // init usart |
376 | usart1_init(); |
384 | usart1_init(); |
377 | 385 | ||
378 | // set up timer |
386 | // set up timer |
379 | TCCR0 |= (1 << CS00) | (1 << CS01); // timer0 prescaler 64 |
387 | TCCR0 |= (1 << CS00) | (1 << CS01); // timer0 prescaler 64 |
380 | OCR0 = 15; // preload |
388 | OCR0 = 15; // preload |
381 | TIMSK |= (1 << TOIE0); // enable overflow timer0 |
389 | TIMSK |= (1 << TOIE0); // enable overflow timer0 |
382 | 390 | ||
383 | // enable interrupts |
391 | // enable interrupts |
384 | sei(); |
392 | sei(); |
385 | #endif |
393 | #endif |
386 | 394 | ||
387 | //write_ascii_string(2, 7, " CaScAdE "); |
395 | //write_ascii_string(2, 7, " CaScAdE "); |
388 | //write_ascii_string(2, 8, "is TESTING his open source"); |
396 | //write_ascii_string(2, 8, "is TESTING his open source"); |
389 | //write_ascii_string(2, 9, " EPi OSD Firmware"); |
397 | //write_ascii_string(2, 9, " EPi OSD Firmware"); |
390 | 398 | ||
391 | // we are ready |
399 | // we are ready |
392 | LED3_ON |
400 | LED3_ON |
393 | 401 | ||
394 | #if ALLCHARSDEBUG | (WRITECHARS != -1) |
402 | #if ALLCHARSDEBUG | (WRITECHARS != -1) |
395 | clear(); |
403 | clear(); |
396 | write_all_chars(); |
404 | write_all_chars(); |
397 | #else |
405 | #else |
398 | // clear serial screen |
406 | // clear serial screen |
399 | //usart1_puts("\x1B[2J\x1B[H"); |
407 | //usart1_puts("\x1B[2J\x1B[H"); |
400 | //usart1_puts("hello world!\r\n"); |
408 | //usart1_puts("hello world!\r\n"); |
401 | 409 | ||
402 | 410 | #if FCONLY |
|
403 | // request data ever 100ms from FC; |
411 | // request data ever 100ms from FC; |
404 | //usart1_request_mk_data(0, 'd', 100); |
412 | usart1_request_mk_data(0, 'd', 100); |
405 | 413 | #else |
|
406 | // request OSD Data from NC every 100ms |
414 | // request OSD Data from NC every 100ms |
407 | usart1_request_mk_data(1, 'o', 100); |
415 | usart1_request_mk_data(1, 'o', 100); |
408 | 416 | ||
409 | // and disable debug... |
417 | // and disable debug... |
410 | usart1_request_mk_data(0, 'd', 0); |
418 | usart1_request_mk_data(0, 'd', 0); |
- | 419 | #endif |
|
411 | 420 | ||
412 | // stats for after flight |
421 | // stats for after flight |
413 | int16_t max_Altimeter = 0; |
422 | int16_t max_Altimeter = 0; |
414 | uint16_t max_GroundSpeed = 0; |
423 | uint16_t max_GroundSpeed = 0; |
415 | int16_t max_Distance = 0; |
424 | int16_t max_Distance = 0; |
416 | uint8_t min_UBat = 255; |
425 | uint8_t min_UBat = 255; |
417 | uint16_t max_FlyingTime = 0; |
426 | uint16_t max_FlyingTime = 0; |
418 | 427 | ||
419 | // flags from last round to check for changes |
428 | // flags from last round to check for changes |
420 | uint8_t old_MKFlags = 0; |
429 | uint8_t old_MKFlags = 0; |
421 | 430 | ||
422 | char* directions[8] = {"NE", "E ", "SE", "S ", "SW", "W ", "NW", "N "}; |
431 | char* directions[8] = {"NE", "E ", "SE", "S ", "SW", "W ", "NW", "N "}; |
423 | //char arrowdir[8] = {218, 217, 224, 223, 222, 221, 220, 219}; |
432 | //char arrowdir[8] = {218, 217, 224, 223, 222, 221, 220, 219}; |
424 | 433 | ||
425 | while (1) { |
434 | while (1) { |
426 | // write icons at init or after menu/mode-switch |
435 | // write icons at init or after menu/mode-switch |
427 | if (!(COSD_FLAGS & COSD_ICONS_WRITTEN) && (COSD_FLAGS & COSD_FLAG_HUD)) { |
436 | if (!(COSD_FLAGS & COSD_ICONS_WRITTEN) && (COSD_FLAGS & COSD_FLAG_HUD)) { |
- | 437 | #if FCONLY |
|
- | 438 | // FC Mode ICONS |
|
- | 439 | write_char_xy(10, top_line, 0xCA); // RC-transmitter |
|
- | 440 | write_char_xy(27, top_line, 0xCC); // small meters m height |
|
- | 441 | write_char_xy(7, bottom_line, 0x9E); // small v |
|
- | 442 | #else |
|
- | 443 | // NAVI Mode ICONS |
|
428 | write_char_xy(5, top_line, 0xCB); // km/h |
444 | write_char_xy(5, top_line, 0xCB); // km/h |
429 | write_char_xy(10, top_line, 0xCA); // RC-transmitter |
445 | write_char_xy(10, top_line, 0xCA); // RC-transmitter |
430 | write_char_xy(16, top_line, 0xD0); // degree symbol |
446 | write_char_xy(16, top_line, 0xD0); // degree symbol |
431 | write_char_xy(27, top_line, 0xCC); // small meters m height |
447 | write_char_xy(27, top_line, 0xCC); // small meters m height |
432 | write_char_xy(20, top_line+1, 0xB0); // left circle |
448 | write_char_xy(20, top_line+1, 0xB0); // left circle |
433 | write_char_xy(22, top_line+1, 0xB2); // right circle |
449 | write_char_xy(22, top_line+1, 0xB2); // right circle |
434 | write_char_xy(27, top_line+1, 0xCC); // small meters m home |
450 | write_char_xy(27, top_line+1, 0xCC); // small meters m home |
435 | write_char_xy(7, bottom_line, 0x9E); // small v |
451 | write_char_xy(7, bottom_line, 0x9E); // small v |
436 | write_char_xy(14, bottom_line, 0xD1); // on clock |
452 | write_char_xy(14, bottom_line, 0xD1); // on clock |
437 | write_char_xy(21, bottom_line, 0xD2); // fly clock |
453 | write_char_xy(21, bottom_line, 0xD2); // fly clock |
438 | write_char_xy(26, bottom_line, 0xC8); // sat1 |
454 | write_char_xy(26, bottom_line, 0xC8); // sat1 |
439 | write_char_xy(27, bottom_line, 0xC9); // sat2 |
455 | write_char_xy(27, bottom_line, 0xC9); // sat2 |
440 | COSD_FLAGS |= COSD_ICONS_WRITTEN; |
456 | COSD_FLAGS |= COSD_ICONS_WRITTEN; |
- | 457 | #endif |
|
441 | } |
458 | } |
442 | if (rxd_buffer_locked) { |
459 | if (rxd_buffer_locked) { |
443 | if (COSD_FLAGS & COSD_FLAG_HUD) { |
460 | if (COSD_FLAGS & COSD_FLAG_HUD) { |
- | 461 | #if FCONLY |
|
444 | if (rxd_buffer[2] == 'D') { // FC Data |
462 | if (rxd_buffer[2] == 'D') { // FC Data |
445 | /*Decode64(); |
463 | Decode64(); |
446 | debugData = *((DebugOut_t*) pRxData); |
464 | debugData = *((DebugOut_t*) pRxData); |
- | 465 | write_ascii_string(2, 2, "FCONLY MODE"); |
|
- | 466 | ||
- | 467 | write_ndigit_number_u(7, top_line, debugData.Analog[10], 100, 0); |
|
- | 468 | if (debugData.Analog[10] <= RCLVL_WRN && last_RC_Quality > RCLVL_WRN) { |
|
- | 469 | for (uint8_t x = 0; x < 4; x++) |
|
- | 470 | write_char_att_xy(7 + x, top_line, BLINK); |
|
- | 471 | } else if (debugData.Analog[10] > RCLVL_WRN && last_RC_Quality <= RCLVL_WRN) { |
|
- | 472 | for (uint8_t x = 0; x < 4; x++) |
|
- | 473 | write_char_att_xy(7 + x, top_line, 0); |
|
- | 474 | } |
|
- | 475 | last_RC_Quality = debugData.Analog[10]; |
|
- | 476 | ||
- | 477 | ||
- | 478 | if (debugData.Analog[5] > 300 || debugData.Analog[5] < -300) { |
|
- | 479 | // above 10m only write full meters |
|
- | 480 | write_ndigit_number_s(23, top_line, debugData.Analog[5] / 30, 1000, 0); |
|
- | 481 | } else { |
|
- | 482 | // up to 10m write meters.dm |
|
- | 483 | write_ndigit_number_s_10th(23, top_line, debugData.Analog[5] / 3, 100, 0); |
|
- | 484 | } |
|
- | 485 | ||
- | 486 | draw_battery(2, bottom_line, min_voltage, debugData.Analog[9], max_voltage); |
|
- | 487 | write_ndigit_number_u_10th(3, bottom_line, debugData.Analog[9], 100, 0); |
|
- | 488 | if (debugData.Analog[9] <= min_voltage && last_UBat > min_voltage) { |
|
447 | write_number_s(12, 2, RxDataLen); |
489 | for (uint8_t x = 2; x < 8; x++) |
- | 490 | write_char_att_xy(x, bottom_line, BLINK); |
|
- | 491 | } else if (debugData.Analog[9] > min_voltage && last_UBat < min_voltage) { |
|
- | 492 | for (uint8_t x = 2; x < 8; x++) |
|
448 | write_number_s(20, 2, setsReceived++); |
493 | write_char_att_xy(x, bottom_line, 0); |
- | 494 | } |
|
- | 495 | // remember last values |
|
- | 496 | last_UBat = debugData.Analog[9]; |
|
- | 497 | ||
- | 498 | /* |
|
449 | write_number_s(12, 3, debugData.Analog[0]); // AngleNick |
499 | debugData.Analog[0]); // AngleNick |
450 | write_number_s(12, 4, debugData.Analog[1]); // AngleRoll |
500 | debugData.Analog[1]); // AngleRoll |
451 | write_number_s(12, 5, debugData.Analog[5]); // Height |
501 | debugData.Analog[5]); // Height |
452 | write_number_s(12, 6, debugData.Analog[9]); // Voltage |
502 | debugData.Analog[9]); // Voltage |
453 | write_number_s(12, 7, debugData.Analog[10]);// RC Signal |
503 | debugData.Analog[10]);// RC Signal |
454 | write_number_s(12, 8, debugData.Analog[11]);// Gyro compass |
504 | debugData.Analog[11]);// Gyro compass |
- | 505 | */ |
|
455 | seconds_since_last_data = 0;*/ |
506 | seconds_since_last_data = 0; |
- | 507 | } |
|
- | 508 | #else |
|
456 | } else if (rxd_buffer[2] == 'O') { // NC OSD Data |
509 | if (rxd_buffer[2] == 'O') { // NC OSD Data |
457 | Decode64(); |
510 | Decode64(); |
458 | naviData = *((NaviData_t*) pRxData); |
511 | naviData = *((NaviData_t*) pRxData); |
459 | 512 | ||
460 | // init on first data retrival, distinguished by last battery :) |
513 | // init on first data retrival, distinguished by last battery :) |
461 | // TODO: this is testing stuff, strings should go progmem and so on... |
514 | // TODO: this is testing stuff, strings should go progmem and so on... |
462 | if (last_UBat == 255) { |
515 | if (last_UBat == 255) { |
463 | clear(); |
516 | clear(); |
464 | // fix for min_bat glitch caused by data only gathered during motors up |
517 | // fix for min_bat glitch caused by data only gathered during motors up |
465 | min_UBat = naviData.UBat; |
518 | min_UBat = naviData.UBat; |
466 | write_ascii_string(2, 2, "C-OSD Initialisation"); |
519 | write_ascii_string(2, 2, "C-OSD Initialisation"); |
467 | uint8_t cellnum = 0; |
520 | uint8_t cellnum = 0; |
468 | if (CELL_NUM == -1) { |
521 | if (CELL_NUM == -1) { |
469 | write_ascii_string(2, 5, "Guessing Number of Cells"); |
522 | write_ascii_string(2, 5, "Guessing Number of Cells"); |
470 | do { |
523 | do { |
471 | cellnum++; |
524 | cellnum++; |
472 | } while (naviData.UBat > ((cellnum * CELL_VOLT_MAX) + 10)); |
525 | } while (naviData.UBat > ((cellnum * CELL_VOLT_MAX) + 10)); |
473 | } else { |
526 | } else { |
474 | cellnum = CELL_NUM; |
527 | cellnum = CELL_NUM; |
475 | } |
528 | } |
476 | min_voltage = cellnum * CELL_VOLT_MIN; |
529 | min_voltage = cellnum * CELL_VOLT_MIN; |
477 | max_voltage = cellnum * CELL_VOLT_MAX; |
530 | max_voltage = cellnum * CELL_VOLT_MAX; |
478 | write_ascii_string(2, 7, "Number of Cells:"); |
531 | write_ascii_string(2, 7, "Number of Cells:"); |
479 | write_ndigit_number_u(21, 7, cellnum, 1, 0); |
532 | write_ndigit_number_u(21, 7, cellnum, 1, 0); |
480 | write_ascii_string(2, 8, "Warn Voltage :"); |
533 | write_ascii_string(2, 8, "Warn Voltage :"); |
481 | write_ndigit_number_s_10th(20, 8, min_voltage, 100, 0); |
534 | write_ndigit_number_s_10th(20, 8, min_voltage, 100, 0); |
482 | write_ascii_string(2, 9, "Max Voltage :"); |
535 | write_ascii_string(2, 9, "Max Voltage :"); |
483 | write_ndigit_number_s_10th(20, 9, max_voltage, 100, 0); |
536 | write_ndigit_number_s_10th(20, 9, max_voltage, 100, 0); |
484 | _delay_ms(200); |
537 | _delay_ms(200); |
485 | clear(); |
538 | clear(); |
486 | // update flags to paint display again because of clear |
539 | // update flags to paint display again because of clear |
487 | COSD_FLAGS &= ~COSD_ICONS_WRITTEN; |
540 | COSD_FLAGS &= ~COSD_ICONS_WRITTEN; |
488 | } |
541 | } |
489 | 542 | ||
490 | // first line |
543 | // first line |
491 | write_ndigit_number_u(2, top_line, (uint16_t) (((uint32_t) naviData.GroundSpeed * (uint32_t)9) / (uint32_t)250), 100, 0); |
544 | write_ndigit_number_u(2, top_line, (uint16_t) (((uint32_t) naviData.GroundSpeed * (uint32_t)9) / (uint32_t)250), 100, 0); |
492 | 545 | ||
493 | write_ndigit_number_u(7, top_line, naviData.RC_Quality, 100, 0); |
546 | write_ndigit_number_u(7, top_line, naviData.RC_Quality, 100, 0); |
494 | if (naviData.RC_Quality <= RCLVL_WRN && last_RC_Quality > RCLVL_WRN) { |
547 | if (naviData.RC_Quality <= RCLVL_WRN && last_RC_Quality > RCLVL_WRN) { |
495 | for (uint8_t x = 0; x < 4; x++) |
548 | for (uint8_t x = 0; x < 4; x++) |
496 | write_char_att_xy(7 + x, top_line, BLINK); |
549 | write_char_att_xy(7 + x, top_line, BLINK); |
497 | } else if (naviData.RC_Quality > RCLVL_WRN && last_RC_Quality <= RCLVL_WRN) { |
550 | } else if (naviData.RC_Quality > RCLVL_WRN && last_RC_Quality <= RCLVL_WRN) { |
498 | for (uint8_t x = 0; x < 4; x++) |
551 | for (uint8_t x = 0; x < 4; x++) |
499 | write_char_att_xy(7 + x, top_line, 0); |
552 | write_char_att_xy(7 + x, top_line, 0); |
500 | } |
553 | } |
501 | last_RC_Quality = naviData.RC_Quality; |
554 | last_RC_Quality = naviData.RC_Quality; |
502 | 555 | ||
503 | if (naviData.NCFlags & NC_FLAG_NOSERIALLINK) { |
556 | if (naviData.NCFlags & NC_FLAG_NOSERIALLINK) { |
504 | write_char_xy(11, top_line, 0); // clear |
557 | write_char_xy(11, top_line, 0); // clear |
505 | } else { |
558 | } else { |
506 | write_char_xy(11, top_line, 0xC6); // PC icon |
559 | write_char_xy(11, top_line, 0xC6); // PC icon |
507 | } |
560 | } |
508 | 561 | ||
509 | write_ndigit_number_u(13, top_line, naviData.CompassHeading, 100, 0); |
562 | write_ndigit_number_u(13, top_line, naviData.CompassHeading, 100, 0); |
510 | 563 | ||
511 | write_ascii_string(17, top_line, directions[heading_conv(naviData.CompassHeading)]); |
564 | write_ascii_string(17, top_line, directions[heading_conv(naviData.CompassHeading)]); |
512 | 565 | ||
513 | draw_variometer(21, top_line, naviData.Variometer); |
566 | draw_variometer(21, top_line, naviData.Variometer); |
514 | 567 | ||
515 | //note:lephisto:according to several sources it's /30 |
568 | //note:lephisto:according to several sources it's /30 |
516 | if (naviData.Altimeter > 300 || naviData.Altimeter < -300) { |
569 | if (naviData.Altimeter > 300 || naviData.Altimeter < -300) { |
517 | // above 10m only write full meters |
570 | // above 10m only write full meters |
518 | write_ndigit_number_s(23, top_line, naviData.Altimeter / 30, 1000, 0); |
571 | write_ndigit_number_s(23, top_line, naviData.Altimeter / 30, 1000, 0); |
519 | } else { |
572 | } else { |
520 | // up to 10m write meters.dm |
573 | // up to 10m write meters.dm |
521 | //write_number_u_10th(21, top_line, naviData.Altimeter / 3); |
574 | //write_number_u_10th(21, top_line, naviData.Altimeter / 3); |
522 | write_ndigit_number_s_10th(23, top_line, naviData.Altimeter / 3, 100, 0); |
575 | write_ndigit_number_s_10th(23, top_line, naviData.Altimeter / 3, 100, 0); |
523 | } |
576 | } |
524 | 577 | ||
525 | // seccond line |
578 | // seccond line |
526 | draw_compass(11, top_line + 1, naviData.CompassHeading); |
579 | draw_compass(11, top_line + 1, naviData.CompassHeading); |
527 | 580 | ||
528 | // TODO: verify correctness |
581 | // TODO: verify correctness |
529 | uint16_t heading_home = (naviData.HomePositionDeviation.Bearing + 360 - naviData.CompassHeading) % 360; |
582 | uint16_t heading_home = (naviData.HomePositionDeviation.Bearing + 360 - naviData.CompassHeading) % 360; |
530 | //write_char_xy(21, top_line + 1, arrowdir[heading_conv(heading_home)]); |
583 | //write_char_xy(21, top_line + 1, arrowdir[heading_conv(heading_home)]); |
531 | // finer resolution, 0xa0 is first character and we add the index 0 <= index < 16 |
584 | // finer resolution, 0xa0 is first character and we add the index 0 <= index < 16 |
532 | write_char_xy(21, top_line + 1, 0xa0 + heading_fine_conv(heading_home)); |
585 | write_char_xy(21, top_line + 1, 0xa0 + heading_fine_conv(heading_home)); |
533 | 586 | ||
534 | write_ndigit_number_u(24, top_line + 1, naviData.HomePositionDeviation.Distance / 10, 100, 0); |
587 | write_ndigit_number_u(24, top_line + 1, naviData.HomePositionDeviation.Distance / 10, 100, 0); |
535 | 588 | ||
536 | // center |
589 | // center |
537 | if (naviData.MKFlags & FLAG_MOTOR_RUN) { // should be engines running |
590 | if (naviData.MKFlags & FLAG_MOTOR_RUN) { // should be engines running |
538 | if (!(old_MKFlags & FLAG_MOTOR_RUN)) { // motors just started, clear middle |
591 | if (!(old_MKFlags & FLAG_MOTOR_RUN)) { // motors just started, clear middle |
539 | clear(); |
592 | clear(); |
540 | // update flags to paint display again if needed |
593 | // update flags to paint display again if needed |
541 | COSD_FLAGS &= ~COSD_ICONS_WRITTEN; |
594 | COSD_FLAGS &= ~COSD_ICONS_WRITTEN; |
542 | } |
595 | } |
543 | if (COSD_FLAGS & COSD_FLAG_ARTHORIZON) { |
596 | if (COSD_FLAGS & COSD_FLAG_ARTHORIZON) { |
544 | draw_artificial_horizon(top_line + 2, bottom_line - 1, naviData.AngleNick, naviData.AngleRoll); |
597 | draw_artificial_horizon(top_line + 2, bottom_line - 1, naviData.AngleNick, naviData.AngleRoll); |
545 | } |
598 | } |
546 | // motors are on, assume we were/are flying |
599 | // motors are on, assume we were/are flying |
547 | COSD_FLAGS |= COSD_WASFLYING; |
600 | COSD_FLAGS |= COSD_WASFLYING; |
548 | } else { |
601 | } else { |
549 | // stats |
602 | // stats |
550 | if ((COSD_FLAGS & COSD_WASFLYING) && (COSD_FLAGS & COSD_FLAG_STATS)) { |
603 | if ((COSD_FLAGS & COSD_WASFLYING) && (COSD_FLAGS & COSD_FLAG_STATS)) { |
551 | write_ascii_string_pgm(2, 4, stats_item_pointers[0]); // max Altitude |
604 | write_ascii_string_pgm(2, 4, stats_item_pointers[0]); // max Altitude |
552 | write_ndigit_number_s(18, 4, max_Altimeter / 30, 1000, 0); |
605 | write_ndigit_number_s(18, 4, max_Altimeter / 30, 1000, 0); |
553 | write_char_xy(22, 4, 204); // small meters m |
606 | write_char_xy(22, 4, 204); // small meters m |
554 | write_ascii_string_pgm(2, 5, stats_item_pointers[1]); // max Speed |
607 | write_ascii_string_pgm(2, 5, stats_item_pointers[1]); // max Speed |
555 | write_ndigit_number_u(19, 5, (uint16_t) (((uint32_t) max_GroundSpeed * (uint32_t)9) / (uint32_t)250), 100, 0); |
608 | write_ndigit_number_u(19, 5, (uint16_t) (((uint32_t) max_GroundSpeed * (uint32_t)9) / (uint32_t)250), 100, 0); |
556 | write_char_xy(22, 5, 203); // km/h |
609 | write_char_xy(22, 5, 203); // km/h |
557 | write_ascii_string_pgm(2, 6, stats_item_pointers[2]); // max Distance |
610 | write_ascii_string_pgm(2, 6, stats_item_pointers[2]); // max Distance |
558 | write_ndigit_number_u(19, 6, max_Distance / 10, 100, 0); |
611 | write_ndigit_number_u(19, 6, max_Distance / 10, 100, 0); |
559 | write_char_xy(22, 6, 204); // small meters m |
612 | write_char_xy(22, 6, 204); // small meters m |
560 | write_ascii_string_pgm(2, 7, stats_item_pointers[3]); // min voltage |
613 | write_ascii_string_pgm(2, 7, stats_item_pointers[3]); // min voltage |
561 | write_ndigit_number_u_10th(18, 7, min_UBat, 100, 0); |
614 | write_ndigit_number_u_10th(18, 7, min_UBat, 100, 0); |
562 | write_char_xy(22, 7, 0x9E); // small v |
615 | write_char_xy(22, 7, 0x9E); // small v |
563 | write_ascii_string_pgm(2, 8, stats_item_pointers[4]); // max time |
616 | write_ascii_string_pgm(2, 8, stats_item_pointers[4]); // max time |
564 | write_time(16, 8, max_FlyingTime); |
617 | write_time(16, 8, max_FlyingTime); |
565 | write_char_xy(22, 8, 210); // fly clock |
618 | write_char_xy(22, 8, 210); // fly clock |
566 | write_ascii_string_pgm(2, 9, stats_item_pointers[5]); // longitude |
619 | write_ascii_string_pgm(2, 9, stats_item_pointers[5]); // longitude |
567 | write_gps_pos(15, 9, naviData.CurrentPosition.Longitude); |
620 | write_gps_pos(15, 9, naviData.CurrentPosition.Longitude); |
568 | write_ascii_string_pgm(2, 10, stats_item_pointers[6]); // latitude |
621 | write_ascii_string_pgm(2, 10, stats_item_pointers[6]); // latitude |
569 | write_gps_pos(15, 10, naviData.CurrentPosition.Latitude); |
622 | write_gps_pos(15, 10, naviData.CurrentPosition.Latitude); |
570 | } else if (COSD_FLAGS & COSD_FLAG_ARTHORIZON) { // if no stats there is space horizon |
623 | } else if (COSD_FLAGS & COSD_FLAG_ARTHORIZON) { // if no stats there is space horizon |
571 | draw_artificial_horizon(top_line + 2, bottom_line - 1, naviData.AngleNick, naviData.AngleRoll); |
624 | draw_artificial_horizon(top_line + 2, bottom_line - 1, naviData.AngleNick, naviData.AngleRoll); |
572 | } |
625 | } |
573 | } |
626 | } |
574 | if (COSD_FLAGS & COSD_FLAG_BIGVARIO) { |
627 | if (COSD_FLAGS & COSD_FLAG_BIGVARIO) { |
575 | draw_big_variometer(27, 8, naviData.Variometer); |
628 | draw_big_variometer(27, 8, naviData.Variometer); |
576 | } |
629 | } |
577 | 630 | ||
578 | // bottom line |
631 | // bottom line |
579 | draw_battery(2, bottom_line, min_voltage, naviData.UBat, max_voltage); |
632 | draw_battery(2, bottom_line, min_voltage, naviData.UBat, max_voltage); |
580 | write_ndigit_number_u_10th(3, bottom_line, naviData.UBat, 100, 0); |
633 | write_ndigit_number_u_10th(3, bottom_line, naviData.UBat, 100, 0); |
581 | if (naviData.UBat <= min_voltage && last_UBat > min_voltage) { |
634 | if (naviData.UBat <= min_voltage && last_UBat > min_voltage) { |
582 | for (uint8_t x = 2; x < 8; x++) |
635 | for (uint8_t x = 2; x < 8; x++) |
583 | write_char_att_xy(x, bottom_line, BLINK); |
636 | write_char_att_xy(x, bottom_line, BLINK); |
584 | } else if (naviData.UBat > min_voltage && last_UBat < min_voltage) { |
637 | } else if (naviData.UBat > min_voltage && last_UBat < min_voltage) { |
585 | for (uint8_t x = 2; x < 8; x++) |
638 | for (uint8_t x = 2; x < 8; x++) |
586 | write_char_att_xy(x, bottom_line, 0); |
639 | write_char_att_xy(x, bottom_line, 0); |
587 | } |
640 | } |
588 | // remember last values |
641 | // remember last values |
589 | last_UBat = naviData.UBat; |
642 | last_UBat = naviData.UBat; |
590 | 643 | ||
591 | write_time(8, bottom_line, uptime); |
644 | write_time(8, bottom_line, uptime); |
592 | write_time(15, bottom_line, naviData.FlyingTime); |
645 | write_time(15, bottom_line, naviData.FlyingTime); |
593 | 646 | ||
594 | write_ndigit_number_u(24, bottom_line, naviData.SatsInUse, 10, 0); |
647 | write_ndigit_number_u(24, bottom_line, naviData.SatsInUse, 10, 0); |
595 | 648 | ||
596 | if (naviData.NCFlags & NC_FLAG_MANUAL_CONTROL) { |
649 | if (naviData.NCFlags & NC_FLAG_MANUAL_CONTROL) { |
597 | write_char_xy(23, bottom_line, 0xB3); // rc transmitter |
650 | write_char_xy(23, bottom_line, 0xB3); // rc transmitter |
598 | } else { |
651 | } else { |
599 | write_char_xy(23, bottom_line, 0); // clear |
652 | write_char_xy(23, bottom_line, 0); // clear |
600 | } |
653 | } |
601 | 654 | ||
602 | if (naviData.NCFlags & NC_FLAG_CH) { |
655 | if (naviData.NCFlags & NC_FLAG_CH) { |
603 | write_char_xy(27, bottom_line, 231); // gps ch |
656 | write_char_xy(27, bottom_line, 231); // gps ch |
604 | } else if (naviData.NCFlags & NC_FLAG_PH) { |
657 | } else if (naviData.NCFlags & NC_FLAG_PH) { |
605 | write_char_xy(27, bottom_line, 230); // gps ph |
658 | write_char_xy(27, bottom_line, 230); // gps ph |
606 | } else { // (naviData.NCFlags & NC_FLAG_FREE) |
659 | } else { // (naviData.NCFlags & NC_FLAG_FREE) |
607 | write_char_xy(27, bottom_line, 201); // sat2 (free) |
660 | write_char_xy(27, bottom_line, 201); // sat2 (free) |
608 | } |
661 | } |
609 | 662 | ||
610 | //write_number_s(8, 5, RxDataLen); |
663 | //write_number_s(8, 5, RxDataLen); |
611 | //write_number_s(16, 5, setsReceived++); |
664 | //write_number_s(16, 5, setsReceived++); |
612 | 665 | ||
613 | // remember statistics (only when engines running) |
666 | // remember statistics (only when engines running) |
614 | if (naviData.MKFlags & FLAG_MOTOR_RUN) { |
667 | if (naviData.MKFlags & FLAG_MOTOR_RUN) { |
615 | if (naviData.Altimeter > max_Altimeter) max_Altimeter = naviData.Altimeter; |
668 | if (naviData.Altimeter > max_Altimeter) max_Altimeter = naviData.Altimeter; |
616 | if (naviData.GroundSpeed > max_GroundSpeed) max_GroundSpeed = naviData.GroundSpeed; |
669 | if (naviData.GroundSpeed > max_GroundSpeed) max_GroundSpeed = naviData.GroundSpeed; |
617 | if (naviData.HomePositionDeviation.Distance > max_Distance) { |
670 | if (naviData.HomePositionDeviation.Distance > max_Distance) { |
618 | max_Distance = naviData.HomePositionDeviation.Distance; |
671 | max_Distance = naviData.HomePositionDeviation.Distance; |
619 | } |
672 | } |
620 | if (naviData.UBat < min_UBat) min_UBat = naviData.UBat; |
673 | if (naviData.UBat < min_UBat) min_UBat = naviData.UBat; |
621 | if (naviData.FlyingTime > max_FlyingTime) max_FlyingTime = naviData.FlyingTime; |
674 | if (naviData.FlyingTime > max_FlyingTime) max_FlyingTime = naviData.FlyingTime; |
622 | } |
675 | } |
623 | 676 | ||
624 | old_MKFlags = naviData.MKFlags; |
677 | old_MKFlags = naviData.MKFlags; |
625 | seconds_since_last_data = 0; |
678 | seconds_since_last_data = 0; |
626 | } |
679 | } |
- | 680 | #endif |
|
627 | } |
681 | } |
628 | rxd_buffer_locked = 0; |
682 | rxd_buffer_locked = 0; |
629 | } |
683 | } |
630 | // handle keypress |
684 | // handle keypress |
631 | if (s1_pressed()) { |
685 | if (s1_pressed()) { |
632 | config_menu(); |
686 | config_menu(); |
633 | } |
687 | } |
634 | if (seconds_since_last_data > 2) { |
688 | if (seconds_since_last_data > 2) { |
- | 689 | #if FCONLY |
|
- | 690 | // request data ever 100ms from FC; |
|
- | 691 | usart1_request_mk_data(0, 'd', 100); |
|
- | 692 | #else |
|
635 | // request OSD Data from NC every 100ms |
693 | // request OSD Data from NC every 100ms |
636 | usart1_request_mk_data(1, 'o', 100); |
694 | usart1_request_mk_data(1, 'o', 100); |
- | 695 | ||
- | 696 | // and disable debug... |
|
637 | seconds_since_last_data = 0; |
697 | usart1_request_mk_data(0, 'd', 0); |
- | 698 | #endif |
|
638 | } |
699 | } |
639 | } |
700 | } |
640 | #endif |
701 | #endif |
641 | return 0; |
702 | return 0; |
642 | } |
703 | } |
643 | 704 |