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