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