Subversion Repositories Projects

Rev

Rev 328 | Rev 330 | Go to most recent revision | Only display areas with differences | Ignore whitespace | Details | Blame | Last modification | View Log | RSS feed

Rev 328 Rev 329
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
 
31
 
32
/* TODO:
32
/* TODO:
33
 * - verifiy correctness of values
33
 * - verifiy correctness of values
34
 * - clean up code :)
34
 * - clean up code :)
35
 */
35
 */
36
 
36
 
37
/* ##########################################################################
37
/* ##########################################################################
38
 * Debugging and general purpose definitions
38
 * Debugging and general purpose definitions
39
 * ##########################################################################*/
39
 * ##########################################################################*/
40
#define ALLCHARSDEBUG 0         // set to 1 and flash firmware to see all chars
40
#define ALLCHARSDEBUG 0         // set to 1 and flash firmware to see all chars
-
 
41
 
-
 
42
#ifndef WRITECHARS                      // if WRITECHARS not set via makefile
41
#define WRITECHARS 0            // set to 2XX and flash firmware to write new char
43
#define WRITECHARS -1           // set to 2XX and flash firmware to write new char
42
                                                        // enables the allchars as well to see results
44
                                                        // enables the allchars as well to see results
-
 
45
#endif
-
 
46
 
-
 
47
#ifndef NTSC                            // if NTSC is not thet via makefile
43
#define NTSC 0                          // set to 1 for NTSC mode + lifts the bottom line
48
#define NTSC 0                          // set to 1 for NTSC mode + lifts the bottom line
-
 
49
#endif
-
 
50
 
44
#define ARTHORIZON 0            // set to 1 to enable roll&nick artificial horizon
51
#define ARTHORIZON 0            // set to 1 to enable roll&nick artificial horizon
45
#define NOOSD 0                         // set to 1 to disable OSD completely
52
#define NOOSD 0                         // set to 1 to disable OSD completely
46
#define NOOSD_BUT_WRN 0         // set to 1 to disable OSD completely but show 
53
#define NOOSD_BUT_WRN 0         // set to 1 to disable OSD completely but show 
47
                                                        // battery and receive signal warnings
54
                                                        // battery and receive signal warnings
48
#define UBAT_WRN 94                     // voltage for blinking warning, like FC settings
55
#define UBAT_WRN 94                     // voltage for blinking warning, like FC settings
49
#define RCLVL_WRN 100           // make the RC level blink if below this number
56
#define RCLVL_WRN 100           // make the RC level blink if below this number
50
 
57
 
51
// ### read datasheet before changing stuff below this line :)
58
// ### read datasheet before changing stuff below this line :)
52
#define BLINK   0b01001111      // attribute byte for blinking chars
59
#define BLINK   0b01001111      // attribute byte for blinking chars
53
 
60
 
54
/* ##########################################################################
61
/* ##########################################################################
55
 * FLAGS usable during runtime
62
 * FLAGS usable during runtime
56
 * ##########################################################################*/
63
 * ##########################################################################*/
57
#define COSD_FLAG_NTSC                   1
64
#define COSD_FLAG_NTSC                   1
58
#define COSD_FLAG_ARTHORIZON     2
65
#define COSD_FLAG_ARTHORIZON     2
59
#define COSD_FLAG_NOOSD                  4
66
#define COSD_FLAG_NOOSD                  4
60
#define COSD_FLAG_NOOSD_BUT_WRN  8
67
#define COSD_FLAG_NOOSD_BUT_WRN  8
61
#define COSD_ICONS_WRITTEN              16
68
#define COSD_ICONS_WRITTEN              16
62
 
69
 
63
/* ##########################################################################
70
/* ##########################################################################
64
 * Software SPI to communicate with MAX7456
71
 * Software SPI to communicate with MAX7456
65
 * ##########################################################################*/
72
 * ##########################################################################*/
66
#define MAX_CS_HIGH             PORTA |=  (1 << PA1);
73
#define MAX_CS_HIGH             PORTA |=  (1 << PA1);
67
#define MAX_CS_LOW              PORTA &= ~(1 << PA1);
74
#define MAX_CS_LOW              PORTA &= ~(1 << PA1);
68
#define MAX_SDIN_HIGH           PORTA |=  (1 << PA2);
75
#define MAX_SDIN_HIGH           PORTA |=  (1 << PA2);
69
#define MAX_SDIN_LOW            PORTA &= ~(1 << PA2);
76
#define MAX_SDIN_LOW            PORTA &= ~(1 << PA2);
70
#define MAX_SCLK_HIGH           PORTA |=  (1 << PA3);
77
#define MAX_SCLK_HIGH           PORTA |=  (1 << PA3);
71
#define MAX_SCLK_LOW            PORTA &= ~(1 << PA3);
78
#define MAX_SCLK_LOW            PORTA &= ~(1 << PA3);
72
#define MAX_RESET_HIGH          PORTA |=  (1 << PA5);
79
#define MAX_RESET_HIGH          PORTA |=  (1 << PA5);
73
#define MAX_RESET_LOW           PORTA &= ~(1 << PA5);
80
#define MAX_RESET_LOW           PORTA &= ~(1 << PA5);
74
 
81
 
75
/* ##########################################################################
82
/* ##########################################################################
76
 * LED controll
83
 * LED controll
77
 * ##########################################################################*/
84
 * ##########################################################################*/
78
#define LED1_ON                 PORTC |=  (1 << PC0);
85
#define LED1_ON                 PORTC |=  (1 << PC0);
79
#define LED1_OFF                PORTC &= ~(1 << PC0);
86
#define LED1_OFF                PORTC &= ~(1 << PC0);
80
#define LED2_ON                 PORTC |=  (1 << PC1);
87
#define LED2_ON                 PORTC |=  (1 << PC1);
81
#define LED2_OFF                PORTC &= ~(1 << PC1);
88
#define LED2_OFF                PORTC &= ~(1 << PC1);
82
#define LED3_ON                 PORTC |=  (1 << PC2);
89
#define LED3_ON                 PORTC |=  (1 << PC2);
83
#define LED3_OFF                PORTC &= ~(1 << PC2);
90
#define LED3_OFF                PORTC &= ~(1 << PC2);
84
#define LED4_ON                 PORTC |=  (1 << PC3);
91
#define LED4_ON                 PORTC |=  (1 << PC3);
85
#define LED4_OFF                PORTC &= ~(1 << PC3);
92
#define LED4_OFF                PORTC &= ~(1 << PC3);
86
 
93
 
87
/* ##########################################################################
94
/* ##########################################################################
88
 * switch controll
95
 * switch controll
89
 * ##########################################################################*/
96
 * ##########################################################################*/
90
#define S1_PRESSED              !(PINC & (1<<PC5))
97
#define S1_PRESSED              !(PINC & (1<<PC5))
91
#define S2_PRESSED              !(PINC & (1<<PC4))
98
#define S2_PRESSED              !(PINC & (1<<PC4))
92
 
99
 
93
/* ##########################################################################
100
/* ##########################################################################
94
 * gain some fake arm compat :)
101
 * gain some fake arm compat :)
95
 * ##########################################################################*/
102
 * ##########################################################################*/
96
#define u8 uint8_t
103
#define u8 uint8_t
97
#define s8 int8_t
104
#define s8 int8_t
98
#define u16 uint16_t
105
#define u16 uint16_t
99
#define s16 int16_t
106
#define s16 int16_t
100
#define u32 uint32_t
107
#define u32 uint32_t
101
#define s32 int32_t
108
#define s32 int32_t
102
 
109
 
103
#if !(ALLCHARSDEBUG|WRITECHARS)
110
#if !(ALLCHARSDEBUG|(WRITECHARS != -1))
104
/* ##########################################################################
111
/* ##########################################################################
105
 * MK data strucs & flags
112
 * MK data strucs & flags
106
 * ##########################################################################*/
113
 * ##########################################################################*/
107
#define NC_FLAG_FREE                    1
114
#define NC_FLAG_FREE                    1
108
#define NC_FLAG_PH                      2
115
#define NC_FLAG_PH                      2
109
#define NC_FLAG_CH                      4
116
#define NC_FLAG_CH                      4
110
#define NC_FLAG_RANGE_LIMIT             8
117
#define NC_FLAG_RANGE_LIMIT             8
111
#define NC_SERIAL_LINK_OK               16
118
#define NC_SERIAL_LINK_OK               16
112
#define NC_FLAG_TARGET_REACHED          32
119
#define NC_FLAG_TARGET_REACHED          32
113
 
120
 
114
#define FLAG_MOTOR_RUN  1
121
#define FLAG_MOTOR_RUN  1
115
#define FLAG_FLY        2
122
#define FLAG_FLY        2
116
#define FLAG_CALIBRATE  4
123
#define FLAG_CALIBRATE  4
117
#define FLAG_START      8
124
#define FLAG_START      8
118
 
125
 
119
/*
126
/*
120
 * FC Debug Struct
127
 * FC Debug Struct
121
 * portions taken and adapted from
128
 * portions taken and adapted from
122
 * http://svn.mikrokopter.de/mikrowebsvn/filedetails.php?repname=FlightCtrl&path=%2Ftags%2FV0.72p%2Fuart.h
129
 * http://svn.mikrokopter.de/mikrowebsvn/filedetails.php?repname=FlightCtrl&path=%2Ftags%2FV0.72p%2Fuart.h
123
 */
130
 */
124
typedef struct {
131
typedef struct {
125
    uint8_t Digital[2];
132
    uint8_t Digital[2];
126
    uint16_t Analog[32]; // Debugvalues
133
    uint16_t Analog[32]; // Debugvalues
127
} __attribute__((packed)) DebugOut_t;
134
} __attribute__((packed)) DebugOut_t;
128
 
135
 
129
/*
136
/*
130
 * NaviCtrl OSD Structs
137
 * NaviCtrl OSD Structs
131
 * portions taken and adapted from
138
 * portions taken and adapted from
132
 * http://svn.mikrokopter.de/mikrowebsvn/filedetails.php?repname=NaviCtrl&path=%2Ftags%2FV0.14e%2Fuart1.h
139
 * http://svn.mikrokopter.de/mikrowebsvn/filedetails.php?repname=NaviCtrl&path=%2Ftags%2FV0.14e%2Fuart1.h
133
 */
140
 */
134
typedef struct {
141
typedef struct {
135
    s32 Longitude; // in 1E-7 deg
142
    s32 Longitude; // in 1E-7 deg
136
    s32 Latitude; // in 1E-7 deg
143
    s32 Latitude; // in 1E-7 deg
137
    s32 Altitude; // in mm
144
    s32 Altitude; // in mm
138
    u8 Status; // validity of data
145
    u8 Status; // validity of data
139
} __attribute__((packed)) GPS_Pos_t;
146
} __attribute__((packed)) GPS_Pos_t;
140
 
147
 
141
typedef struct {
148
typedef struct {
142
    s16 Distance; // distance to target in cm
149
    s16 Distance; // distance to target in cm
143
    s16 Bearing; // course to target in deg
150
    s16 Bearing; // course to target in deg
144
} __attribute__((packed)) GPS_PosDev_t;
151
} __attribute__((packed)) GPS_PosDev_t;
145
 
152
 
146
typedef struct {
153
typedef struct {
147
    GPS_Pos_t CurrentPosition; // see ubx.h for details
154
    GPS_Pos_t CurrentPosition; // see ubx.h for details
148
    GPS_Pos_t TargetPosition;
155
    GPS_Pos_t TargetPosition;
149
    GPS_PosDev_t TargetPositionDeviation;
156
    GPS_PosDev_t TargetPositionDeviation;
150
    GPS_Pos_t HomePosition;
157
    GPS_Pos_t HomePosition;
151
    GPS_PosDev_t HomePositionDeviation;
158
    GPS_PosDev_t HomePositionDeviation;
152
    u8 WaypointIndex; // index of current waypoints running from 0 to WaypointNumber-1
159
    u8 WaypointIndex; // index of current waypoints running from 0 to WaypointNumber-1
153
    u8 WaypointNumber; // number of stored waypoints
160
    u8 WaypointNumber; // number of stored waypoints
154
    u8 SatsInUse; // no of satellites used for position solution
161
    u8 SatsInUse; // no of satellites used for position solution
155
    s16 Altimeter; // hight according to air pressure
162
    s16 Altimeter; // hight according to air pressure
156
    s16 Variometer; // climb(+) and sink(-) rate
163
    s16 Variometer; // climb(+) and sink(-) rate
157
    u16 FlyingTime; // in seconds
164
    u16 FlyingTime; // in seconds
158
    u8 UBat; // Battery Voltage in 0.1 Volts
165
    u8 UBat; // Battery Voltage in 0.1 Volts
159
    u16 GroundSpeed; // speed over ground in cm/s (2D)
166
    u16 GroundSpeed; // speed over ground in cm/s (2D)
160
    s16 Heading; // current flight direction in deg as angle to north
167
    s16 Heading; // current flight direction in deg as angle to north
161
    s16 CompassHeading; // current compass value
168
    s16 CompassHeading; // current compass value
162
    s8 AngleNick; // current Nick angle in 1°
169
    s8 AngleNick; // current Nick angle in 1°
163
    s8 AngleRoll; // current Rick angle in 1°
170
    s8 AngleRoll; // current Rick angle in 1°
164
    u8 RC_Quality; // RC_Quality
171
    u8 RC_Quality; // RC_Quality
165
    u8 MKFlags; // Flags from FC
172
    u8 MKFlags; // Flags from FC
166
    u8 NCFlags; // Flags from NC
173
    u8 NCFlags; // Flags from NC
167
    u8 Errorcode; // 0 --> okay
174
    u8 Errorcode; // 0 --> okay
168
    u8 OperatingRadius; // current operation radius around the Home Position in m
175
    u8 OperatingRadius; // current operation radius around the Home Position in m
169
    u8 Reserve[7]; // for future use
176
    u8 Reserve[7]; // for future use
170
} __attribute__((packed)) NaviData_t;
177
} __attribute__((packed)) NaviData_t;
171
 
178
 
172
 
179
 
173
/* ##########################################################################
180
/* ##########################################################################
174
 * global definitions and global vars
181
 * global definitions and global vars
175
 * ##########################################################################*/
182
 * ##########################################################################*/
176
#define baud 57600
183
#define baud 57600
177
 
184
 
178
#define RXD_BUFFER_LEN          150
185
#define RXD_BUFFER_LEN          150
179
#define TXD_BUFFER_LEN          150
186
#define TXD_BUFFER_LEN          150
180
 
187
 
181
volatile uint8_t rxd_buffer_locked = 0;
188
volatile uint8_t rxd_buffer_locked = 0;
182
volatile uint8_t rxd_buffer[RXD_BUFFER_LEN];
189
volatile uint8_t rxd_buffer[RXD_BUFFER_LEN];
183
volatile uint8_t txd_buffer[TXD_BUFFER_LEN];
190
volatile uint8_t txd_buffer[TXD_BUFFER_LEN];
184
volatile uint8_t ReceivedBytes = 0;
191
volatile uint8_t ReceivedBytes = 0;
185
volatile uint8_t *pRxData = 0;
192
volatile uint8_t *pRxData = 0;
186
volatile uint8_t RxDataLen = 0;
193
volatile uint8_t RxDataLen = 0;
187
volatile uint16_t setsReceived = 0;
194
volatile uint16_t setsReceived = 0;
188
 
195
 
189
volatile NaviData_t naviData;
196
volatile NaviData_t naviData;
190
volatile DebugOut_t debugData;
197
volatile DebugOut_t debugData;
191
 
198
 
192
// cache old vars for blinking attribute, checkup is faster than full
199
// cache old vars for blinking attribute, checkup is faster than full
193
// attribute write each time
200
// attribute write each time
194
volatile uint8_t last_UBat = 255;
201
volatile uint8_t last_UBat = 255;
195
volatile uint8_t last_RC_Quality = 255;
202
volatile uint8_t last_RC_Quality = 255;
196
 
203
 
197
// 16bit should be enough, normal LiPos don't last that long
204
// 16bit should be enough, normal LiPos don't last that long
198
volatile uint16_t uptime = 0;
205
volatile uint16_t uptime = 0;
199
volatile uint16_t timer = 0;
206
volatile uint16_t timer = 0;
200
 
207
 
201
#endif // ends !(ALLCHARSDEBUG|WRITECHARS)
208
#endif // ends !(ALLCHARSDEBUG|(WRITECHARS != -1))
202
 
209
 
203
// general PAL|NTSC distingiusch stuff
210
// general PAL|NTSC distingiusch stuff
204
uint8_t top_line = 1;
211
uint8_t top_line = 1;
205
uint8_t bottom_line = 14;
212
uint8_t bottom_line = 14;
206
 
213
 
207
// Flags
214
// Flags
208
uint8_t COSD_FLAGS = 0;
215
uint8_t COSD_FLAGS = 0;
209
 
216
 
210
/* ##########################################################################
217
/* ##########################################################################
211
 * debounce buttons
218
 * debounce buttons
212
 * ##########################################################################*/
219
 * ##########################################################################*/
213
int s1_pressed() {
220
int s1_pressed() {
214
        if (S1_PRESSED) {
221
        if (S1_PRESSED) {
215
                _delay_ms(25);
222
                _delay_ms(25);
216
                if (S1_PRESSED) return 1;
223
                if (S1_PRESSED) return 1;
217
        }
224
        }
218
        return 0;
225
        return 0;
219
}
226
}
220
 
227
 
221
int s2_pressed() {
228
int s2_pressed() {
222
        if (S2_PRESSED) {
229
        if (S2_PRESSED) {
223
                _delay_ms(25);
230
                _delay_ms(25);
224
                if (S2_PRESSED) return 1;
231
                if (S2_PRESSED) return 1;
225
        }
232
        }
226
        return 0;
233
        return 0;
227
}
234
}
228
 
235
 
229
/* ##########################################################################
236
/* ##########################################################################
230
 * MAX7456 SPI & Display stuff
237
 * MAX7456 SPI & Display stuff
231
 * ##########################################################################*/
238
 * ##########################################################################*/
232
 
239
 
233
/**
240
/**
234
 * Send a byte through SPI
241
 * Send a byte through SPI
235
 */
242
 */
236
void spi_send(uint8_t byte) {
243
void spi_send(uint8_t byte) {
237
    for (int8_t i = 7; i >= 0; i--) {
244
    for (int8_t i = 7; i >= 0; i--) {
238
        if (((byte >> i) & 1)) {
245
        if (((byte >> i) & 1)) {
239
            MAX_SDIN_HIGH
246
            MAX_SDIN_HIGH
240
        } else {
247
        } else {
241
            MAX_SDIN_LOW
248
            MAX_SDIN_LOW
242
        }
249
        }
243
        MAX_SCLK_HIGH
250
        MAX_SCLK_HIGH
244
        MAX_SCLK_LOW
251
        MAX_SCLK_LOW
245
    }
252
    }
246
}
253
}
247
 
254
 
248
/**
255
/**
249
 *  Send <byte> to <address> of MAX7456
256
 *  Send <byte> to <address> of MAX7456
250
 */
257
 */
251
void spi_send_byte(uint8_t address, uint8_t byte) {
258
void spi_send_byte(uint8_t address, uint8_t byte) {
252
    // start sending
259
    // start sending
253
    MAX_CS_LOW
260
    MAX_CS_LOW
254
 
261
 
255
    spi_send(address);
262
    spi_send(address);
256
    spi_send(byte);
263
    spi_send(byte);
257
 
264
 
258
    // end sending
265
    // end sending
259
    MAX_CS_HIGH
266
    MAX_CS_HIGH
260
}
267
}
261
 
268
 
262
/**
269
/**
263
 *  write a <character> to <address> of MAX7456 display memory
270
 *  write a <character> to <address> of MAX7456 display memory
264
 */
271
 */
265
void write_char(uint16_t address, char character) {
272
void write_char(uint16_t address, char character) {
266
    spi_send_byte(0x05, (address & 0xFF00) >> 8); // DMAH
273
    spi_send_byte(0x05, (address & 0xFF00) >> 8); // DMAH
267
    spi_send_byte(0x06, (address & 0x00FF)); // DMAL
274
    spi_send_byte(0x06, (address & 0x00FF)); // DMAL
268
    spi_send_byte(0x07, character); // DMDI
275
    spi_send_byte(0x07, character); // DMDI
269
}
276
}
270
 
277
 
271
/**
278
/**
272
 *  write a character <attribute> to <address> of MAX7456 display memory
279
 *  write a character <attribute> to <address> of MAX7456 display memory
273
 */
280
 */
274
void write_char_att(uint16_t address, char attribute) {
281
void write_char_att(uint16_t address, char attribute) {
275
    // the only important part is that the DMAH[1] is set
282
    // the only important part is that the DMAH[1] is set
276
    // so we add 2 which binary is the 2nd lowest byte
283
    // so we add 2 which binary is the 2nd lowest byte
277
    spi_send_byte(0x05, ((address & 0xFF00) >> 8) | 2); // DMAH
284
    spi_send_byte(0x05, ((address & 0xFF00) >> 8) | 2); // DMAH
278
    spi_send_byte(0x06, (address & 0x00FF)); // DMAL
285
    spi_send_byte(0x06, (address & 0x00FF)); // DMAL
279
    spi_send_byte(0x07, attribute); // DMDI
286
    spi_send_byte(0x07, attribute); // DMDI
280
}
287
}
281
 
288
 
282
/**
289
/**
283
 *  write a <character> at <x>/<y> to MAX7456 display memory
290
 *  write a <character> at <x>/<y> to MAX7456 display memory
284
 */
291
 */
285
void write_char_xy(uint8_t x, uint8_t y, char character) {
292
void write_char_xy(uint8_t x, uint8_t y, char character) {
286
    uint16_t address = y * 30 + x;
293
    uint16_t address = y * 30 + x;
287
    write_char(address, character);
294
    write_char(address, character);
288
}
295
}
289
 
296
 
290
/**
297
/**
291
 *  write a  character <attribute> at <x>/<y> to MAX7456 display memory
298
 *  write a  character <attribute> at <x>/<y> to MAX7456 display memory
292
 */
299
 */
293
void write_char_att_xy(uint8_t x, uint8_t y, char attribute) {
300
void write_char_att_xy(uint8_t x, uint8_t y, char attribute) {
294
    uint16_t address = y * 30 + x;
301
    uint16_t address = y * 30 + x;
295
    write_char_att(address, attribute);
302
    write_char_att(address, attribute);
296
}
303
}
297
 
304
 
298
/**
305
/**
299
 *  clear display by writing blank characters all over it
306
 *  clear display by writing blank characters all over it
300
 */
307
 */
301
void clear(void) {
308
void clear(void) {
302
    uint16_t memory_address = 0;
309
    uint16_t memory_address = 0;
303
    for (unsigned int a = 0; a < 480; a++) {
310
    for (unsigned int a = 0; a < 480; a++) {
304
        write_char(memory_address++, 0);
311
        write_char(memory_address++, 0);
305
    }
312
    }
306
}
313
}
307
 
314
 
308
/**
315
/**
309
 *  write an ascii <character> to <address> of MAX7456 display memory
316
 *  write an ascii <character> to <address> of MAX7456 display memory
310
 */
317
 */
311
void write_ascii_char(uint16_t address, char c) {
318
void write_ascii_char(uint16_t address, char c) {
312
    if (c == 32) c = 0; // remap space
319
    if (c == 32) c = 0; // remap space
313
    else if (c > 48 && c <= 57) c -= 48; // remap numbers
320
    else if (c > 48 && c <= 57) c -= 48; // remap numbers
314
    else if (c == '0') c = 10; // remap zero
321
    else if (c == '0') c = 10; // remap zero
315
    else if (c >= 65 && c <= 90) c -= 54; // remap big letters
322
    else if (c >= 65 && c <= 90) c -= 54; // remap big letters
316
    else if (c >= 97 && c <= 122) c -= 60; // remap small letters
323
    else if (c >= 97 && c <= 122) c -= 60; // remap small letters
317
    else if (c == '(') c = 63; // remap
324
    else if (c == '(') c = 63; // remap
318
    else if (c == ')') c = 64; // remap
325
    else if (c == ')') c = 64; // remap
319
    else if (c == '.') c = 65; // remap
326
    else if (c == '.') c = 65; // remap
320
    else if (c == '?') c = 66; // remap
327
    else if (c == '?') c = 66; // remap
321
    else if (c == ';') c = 67; // remap
328
    else if (c == ';') c = 67; // remap
322
    else if (c == ':') c = 68; // remap
329
    else if (c == ':') c = 68; // remap
323
    else if (c == ',') c = 69; // remap
330
    else if (c == ',') c = 69; // remap
324
    else if (c == '\'') c = 70; // remap
331
    else if (c == '\'') c = 70; // remap
325
    else if (c == '/') c = 71; // remap
332
    else if (c == '/') c = 71; // remap
326
    else if (c == '"') c = 72; // remap
333
    else if (c == '"') c = 72; // remap
327
    else if (c == '-') c = 73; // remap minus
334
    else if (c == '-') c = 73; // remap minus
328
    else if (c == '<') c = 74; // remap
335
    else if (c == '<') c = 74; // remap
329
    else if (c == '>') c = 75; // remap
336
    else if (c == '>') c = 75; // remap
330
    else if (c == '@') c = 76; // remap
337
    else if (c == '@') c = 76; // remap
331
    write_char(address, c);
338
    write_char(address, c);
332
}
339
}
333
 
340
 
334
/**
341
/**
335
 *  write an ascii <string> at <x>/<y> to MAX7456 display memory
342
 *  write an ascii <string> at <x>/<y> to MAX7456 display memory
336
 */
343
 */
337
void write_ascii_string(uint8_t x, uint8_t y, char *string) {
344
void write_ascii_string(uint8_t x, uint8_t y, char *string) {
338
    while (*string) {
345
    while (*string) {
339
        write_ascii_char(((x++)+(y * 30)), *string);
346
        write_ascii_char(((x++)+(y * 30)), *string);
340
        string++;
347
        string++;
341
    }
348
    }
342
}
349
}
343
 
350
 
344
/**
351
/**
345
 *  Write only the last three digits of a <number> at <x>/<y> to MAX7456
352
 *  Write only the last three digits of a <number> at <x>/<y> to MAX7456
346
 *  display memory. takes full 16bit numbers as well for stuff
353
 *  display memory. takes full 16bit numbers as well for stuff
347
 *  like compass only taking three characters (values <= 999)
354
 *  like compass only taking three characters (values <= 999)
348
 */
355
 */
349
void write_3digit_number_u(uint8_t x, uint8_t y, uint16_t number) {
356
void write_3digit_number_u(uint8_t x, uint8_t y, uint16_t number) {
350
    uint16_t num = 100;
357
    uint16_t num = 100;
351
    uint8_t started = 0;
358
    uint8_t started = 0;
352
 
359
 
353
    while (num > 0) {
360
    while (num > 0) {
354
        uint8_t b = number / num;
361
        uint8_t b = number / num;
355
        if (b > 0 || started || num == 1) {
362
        if (b > 0 || started || num == 1) {
356
            write_ascii_char((x++)+(y * 30), '0' + b);
363
            write_ascii_char((x++)+(y * 30), '0' + b);
357
            started = 1;
364
            started = 1;
358
        } else {
365
        } else {
359
            write_ascii_char((x++)+(y * 30), 0);
366
            write_ascii_char((x++)+(y * 30), 0);
360
        }
367
        }
361
        number -= b * num;
368
        number -= b * num;
362
 
369
 
363
        num /= 10;
370
        num /= 10;
364
    }
371
    }
365
}
372
}
366
 
373
 
367
/**
374
/**
368
 *  Write only the last two digits of a number at <x>/<y> to MAX7456
375
 *  Write only the last two digits of a number at <x>/<y> to MAX7456
369
 *  display memory. takes full 16bit numbers as well for stuff
376
 *  display memory. takes full 16bit numbers as well for stuff
370
 *  like seconds only taking two characters (values <= 99)
377
 *  like seconds only taking two characters (values <= 99)
371
 *  Since this is used for seconds only and it looks better, there
378
 *  Since this is used for seconds only and it looks better, there
372
 *  is a trading 0 attached
379
 *  is a trading 0 attached
373
 */
380
 */
374
void write_2digit_number_u(uint8_t x, uint8_t y, uint16_t number) {
381
void write_2digit_number_u(uint8_t x, uint8_t y, uint16_t number) {
375
    uint16_t num = 10;
382
    uint16_t num = 10;
376
    uint8_t started = 0;
383
    uint8_t started = 0;
377
 
384
 
378
    while (num > 0) {
385
    while (num > 0) {
379
        uint8_t b = number / num;
386
        uint8_t b = number / num;
380
        if (b > 0 || started || num == 1) {
387
        if (b > 0 || started || num == 1) {
381
            write_ascii_char((x++)+(y * 30), '0' + b);
388
            write_ascii_char((x++)+(y * 30), '0' + b);
382
            started = 1;
389
            started = 1;
383
        } else {
390
        } else {
384
            write_ascii_char((x++)+(y * 30), '0');
391
            write_ascii_char((x++)+(y * 30), '0');
385
        }
392
        }
386
        number -= b * num;
393
        number -= b * num;
387
 
394
 
388
        num /= 10;
395
        num /= 10;
389
    }
396
    }
390
}
397
}
391
 
398
 
392
/**
399
/**
393
 *  write a unsigned number as /10th at <x>/<y> to MAX7456 display memory
400
 *  write a unsigned number as /10th at <x>/<y> to MAX7456 display memory
394
 */
401
 */
395
void write_number_u_10th(uint8_t x, uint8_t y, uint16_t number) {
402
void write_number_u_10th(uint8_t x, uint8_t y, uint16_t number) {
396
    uint16_t num = 10000;
403
    uint16_t num = 10000;
397
    uint8_t started = 0;
404
    uint8_t started = 0;
398
 
405
 
399
    while (num > 0) {
406
    while (num > 0) {
400
        uint8_t b = number / num;
407
        uint8_t b = number / num;
401
 
408
 
402
        if (b > 0 || started || num == 1) {
409
        if (b > 0 || started || num == 1) {
403
            if ((num / 10) == 0) write_char((x++)+(y * 30), 65);
410
            if ((num / 10) == 0) write_char((x++)+(y * 30), 65);
404
            write_ascii_char((x++)+(y * 30), '0' + b);
411
            write_ascii_char((x++)+(y * 30), '0' + b);
405
            started = 1;
412
            started = 1;
406
        } else {
413
        } else {
407
            write_ascii_char((x++)+(y * 30), 0);
414
            write_ascii_char((x++)+(y * 30), 0);
408
        }
415
        }
409
        number -= b * num;
416
        number -= b * num;
410
 
417
 
411
        num /= 10;
418
        num /= 10;
412
    }
419
    }
413
}
420
}
414
 
421
 
415
/**
422
/**
416
 *  write a unsigned number at <x>/<y> to MAX7456 display memory
423
 *  write a unsigned number at <x>/<y> to MAX7456 display memory
417
 */
424
 */
418
void write_number_u(uint8_t x, uint8_t y, uint16_t number) {
425
void write_number_u(uint8_t x, uint8_t y, uint16_t number) {
419
    uint16_t num = 10000;
426
    uint16_t num = 10000;
420
    uint8_t started = 0;
427
    uint8_t started = 0;
421
 
428
 
422
    while (num > 0) {
429
    while (num > 0) {
423
        uint8_t b = number / num;
430
        uint8_t b = number / num;
424
        if (b > 0 || started || num == 1) {
431
        if (b > 0 || started || num == 1) {
425
            write_ascii_char((x++)+(y * 30), '0' + b);
432
            write_ascii_char((x++)+(y * 30), '0' + b);
426
            started = 1;
433
            started = 1;
427
        } else {
434
        } else {
428
            write_ascii_char((x++)+(y * 30), 0);
435
            write_ascii_char((x++)+(y * 30), 0);
429
        }
436
        }
430
        number -= b * num;
437
        number -= b * num;
431
 
438
 
432
        num /= 10;
439
        num /= 10;
433
    }
440
    }
434
}
441
}
435
 
442
 
436
/**
443
/**
437
 *  write a signed number at <x>/<y> to MAX7456 display memory
444
 *  write a signed number at <x>/<y> to MAX7456 display memory
438
 */
445
 */
439
void write_number_s(uint8_t x, uint8_t y, int16_t w) {
446
void write_number_s(uint8_t x, uint8_t y, int16_t w) {
440
    if (((uint16_t) w) > 32767) {
447
    if (((uint16_t) w) > 32767) {
441
        w = w - 65536;
448
        w = w - 65536;
442
 
449
 
443
        int16_t num = -10000;
450
        int16_t num = -10000;
444
        uint8_t started = 0;
451
        uint8_t started = 0;
445
 
452
 
446
        while (num < 0) {
453
        while (num < 0) {
447
            uint8_t b = w / num;
454
            uint8_t b = w / num;
448
            if (b > 0 || started || num == 1) {
455
            if (b > 0 || started || num == 1) {
449
                if (!started) write_char((x - 1)+(y * 30), 0x49);
456
                if (!started) write_char((x - 1)+(y * 30), 0x49);
450
                write_ascii_char((x++)+(y * 30), '0' + b);
457
                write_ascii_char((x++)+(y * 30), '0' + b);
451
                started = 1;
458
                started = 1;
452
            } else {
459
            } else {
453
                write_ascii_char((x++)+(y * 30), 0);
460
                write_ascii_char((x++)+(y * 30), 0);
454
            }
461
            }
455
            w -= b * num;
462
            w -= b * num;
456
 
463
 
457
            num /= 10;
464
            num /= 10;
458
        }
465
        }
459
    } else {
466
    } else {
460
        write_char((x)+(y * 30), 0);
467
        write_char((x)+(y * 30), 0);
461
        write_number_u(x, y, w);
468
        write_number_u(x, y, w);
462
    }
469
    }
463
}
470
}
464
 
471
 
465
/**
472
/**
466
 *  write <seconds> as human readable time at <x>/<y> to MAX7456 display mem
473
 *  write <seconds> as human readable time at <x>/<y> to MAX7456 display mem
467
 */
474
 */
468
void write_time(uint8_t x, uint8_t y, uint16_t seconds) {
475
void write_time(uint8_t x, uint8_t y, uint16_t seconds) {
469
    uint16_t min = seconds / 60;
476
    uint16_t min = seconds / 60;
470
    seconds -= min * 60;
477
    seconds -= min * 60;
471
    write_3digit_number_u(x, y, min);
478
    write_3digit_number_u(x, y, min);
472
    write_char_xy(x + 3, y, 68);
479
    write_char_xy(x + 3, y, 68);
473
    write_2digit_number_u(x + 4, y, seconds);
480
    write_2digit_number_u(x + 4, y, seconds);
474
}
481
}
475
 
482
 
476
/**
483
/**
477
 * for testing write all chars to screen
484
 * for testing write all chars to screen
478
 */
485
 */
479
void write_all_chars() {
486
void write_all_chars() {
480
    uint16_t x = 3, y = 2, t = 0;
487
    uint16_t x = 3, y = 2, t = 0;
481
    while (t < 256) {
488
    while (t < 256) {
482
        write_char_xy(x++, y, t++);
489
        write_char_xy(x++, y, t++);
483
        if (x > 25) {
490
        if (x > 25) {
484
            y++;
491
            y++;
485
            x = 3;
492
            x = 3;
486
        }
493
        }
487
    }
494
    }
488
}
495
}
489
 
496
 
490
#if !(ALLCHARSDEBUG|WRITECHARS)
497
#if !(ALLCHARSDEBUG|(WRITECHARS != -1))
491
/* ##########################################################################
498
/* ##########################################################################
492
 * USART stuff
499
 * USART stuff
493
 * ##########################################################################*/
500
 * ##########################################################################*/
494
 
501
 
495
/**
502
/**
496
 * init usart1
503
 * init usart1
497
 */
504
 */
498
void usart1_init() {
505
void usart1_init() {
499
    UBRR1H = ((F_CPU / (16UL * baud)) - 1) >> 8;
506
    UBRR1H = ((F_CPU / (16UL * baud)) - 1) >> 8;
500
    UBRR1L = (F_CPU / (16UL * baud)) - 1;
507
    UBRR1L = (F_CPU / (16UL * baud)) - 1;
501
 
508
 
502
    // Enable receiver and transmitter; enable RX interrupt
509
    // Enable receiver and transmitter; enable RX interrupt
503
    UCSR1B = (1 << RXEN1) | (1 << TXEN1) | (1 << RXCIE1);
510
    UCSR1B = (1 << RXEN1) | (1 << TXEN1) | (1 << RXCIE1);
504
 
511
 
505
    //asynchronous 8N1
512
    //asynchronous 8N1
506
    UCSR1C = (1 << URSEL1) | (3 << UCSZ10);
513
    UCSR1C = (1 << URSEL1) | (3 << UCSZ10);
507
}
514
}
508
 
515
 
509
/**
516
/**
510
 * send a single <character> through usart1
517
 * send a single <character> through usart1
511
 */
518
 */
512
void usart1_putc(unsigned char character) {
519
void usart1_putc(unsigned char character) {
513
    // wait until UDR ready
520
    // wait until UDR ready
514
    while (!(UCSR1A & (1 << UDRE1)));
521
    while (!(UCSR1A & (1 << UDRE1)));
515
    UDR1 = character;
522
    UDR1 = character;
516
}
523
}
517
 
524
 
518
/**
525
/**
519
 * send a <string> throught usart1
526
 * send a <string> throught usart1
520
 */
527
 */
521
void usart1_puts(char *s) {
528
void usart1_puts(char *s) {
522
    while (*s) {
529
    while (*s) {
523
        usart1_putc(*s);
530
        usart1_putc(*s);
524
        s++;
531
        s++;
525
    }
532
    }
526
}
533
}
527
 
534
 
528
/**
535
/**
529
 * receive data through usart1
536
 * receive data through usart1
530
 * portions taken and adapted from
537
 * portions taken and adapted from
531
 * http://svn.mikrokopter.de/mikrowebsvn/filedetails.php?repname=FlightCtrl&path=%2Fbranches%2FV0.72p+Code+Redesign+killagreg%2Fuart0.c
538
 * http://svn.mikrokopter.de/mikrowebsvn/filedetails.php?repname=FlightCtrl&path=%2Fbranches%2FV0.72p+Code+Redesign+killagreg%2Fuart0.c
532
 */
539
 */
533
ISR(SIG_USART1_RECV) {
540
ISR(SIG_USART1_RECV) {
534
    if (rxd_buffer_locked) return; // if rxd buffer is locked immediately return
541
    if (rxd_buffer_locked) return; // if rxd buffer is locked immediately return
535
    LED1_ON
542
    LED1_ON
536
            static uint16_t crc;
543
            static uint16_t crc;
537
    static uint8_t ptr_rxd_buffer = 0;
544
    static uint8_t ptr_rxd_buffer = 0;
538
    uint8_t crc1, crc2;
545
    uint8_t crc1, crc2;
539
    uint8_t c;
546
    uint8_t c;
540
 
547
 
541
    c = UDR1; // catch the received byte
548
    c = UDR1; // catch the received byte
542
 
549
 
543
    // the rxd buffer is unlocked
550
    // the rxd buffer is unlocked
544
    if ((ptr_rxd_buffer == 0) && (c == '#')) // if rxd buffer is empty and syncronisation character is received
551
    if ((ptr_rxd_buffer == 0) && (c == '#')) // if rxd buffer is empty and syncronisation character is received
545
    {
552
    {
546
                /*
553
                /*
547
                // skip other datasets
554
                // skip other datasets
548
        if (ptr_rxd_buffer == 2 && rxd_buffer[ptr_rxd_buffer] != 'O') {
555
        if (ptr_rxd_buffer == 2 && rxd_buffer[ptr_rxd_buffer] != 'O') {
549
                        ptr_rxd_buffer = 0; // reset rxd buffer
556
                        ptr_rxd_buffer = 0; // reset rxd buffer
550
                rxd_buffer_locked = 0; // unlock rxd buffer
557
                rxd_buffer_locked = 0; // unlock rxd buffer
551
                }*/
558
                }*/
552
                rxd_buffer[ptr_rxd_buffer++] = c; // copy 1st byte to buffer
559
                rxd_buffer[ptr_rxd_buffer++] = c; // copy 1st byte to buffer
553
        crc = c; // init crc
560
        crc = c; // init crc
554
    } else if (ptr_rxd_buffer < RXD_BUFFER_LEN) // collect incomming bytes
561
    } else if (ptr_rxd_buffer < RXD_BUFFER_LEN) // collect incomming bytes
555
    {
562
    {
556
        if (c != '\r') // no termination character
563
        if (c != '\r') // no termination character
557
        {
564
        {
558
            rxd_buffer[ptr_rxd_buffer++] = c; // copy byte to rxd buffer
565
            rxd_buffer[ptr_rxd_buffer++] = c; // copy byte to rxd buffer
559
            crc += c; // update crc
566
            crc += c; // update crc
560
        } else // termination character was received
567
        } else // termination character was received
561
        {
568
        {
562
            // the last 2 bytes are no subject for checksum calculation
569
            // the last 2 bytes are no subject for checksum calculation
563
            // they are the checksum itself
570
            // they are the checksum itself
564
            crc -= rxd_buffer[ptr_rxd_buffer - 2];
571
            crc -= rxd_buffer[ptr_rxd_buffer - 2];
565
            crc -= rxd_buffer[ptr_rxd_buffer - 1];
572
            crc -= rxd_buffer[ptr_rxd_buffer - 1];
566
            // calculate checksum from transmitted data
573
            // calculate checksum from transmitted data
567
            crc %= 4096;
574
            crc %= 4096;
568
            crc1 = '=' + crc / 64;
575
            crc1 = '=' + crc / 64;
569
            crc2 = '=' + crc % 64;
576
            crc2 = '=' + crc % 64;
570
            // compare checksum to transmitted checksum bytes
577
            // compare checksum to transmitted checksum bytes
571
            if ((crc1 == rxd_buffer[ptr_rxd_buffer - 2]) && (crc2 == rxd_buffer[ptr_rxd_buffer - 1])) { // checksum valid
578
            if ((crc1 == rxd_buffer[ptr_rxd_buffer - 2]) && (crc2 == rxd_buffer[ptr_rxd_buffer - 1])) { // checksum valid
572
                rxd_buffer[ptr_rxd_buffer] = '\r'; // set termination character
579
                rxd_buffer[ptr_rxd_buffer] = '\r'; // set termination character
573
                ReceivedBytes = ptr_rxd_buffer + 1; // store number of received bytes
580
                ReceivedBytes = ptr_rxd_buffer + 1; // store number of received bytes
574
                rxd_buffer_locked = 1; // lock the rxd buffer
581
                rxd_buffer_locked = 1; // lock the rxd buffer
575
            } else { // checksum invalid
582
            } else { // checksum invalid
576
                rxd_buffer_locked = 0; // unlock rxd buffer
583
                rxd_buffer_locked = 0; // unlock rxd buffer
577
            }
584
            }
578
            ptr_rxd_buffer = 0; // reset rxd buffer pointer
585
            ptr_rxd_buffer = 0; // reset rxd buffer pointer
579
        }
586
        }
580
    } else // rxd buffer overrun
587
    } else // rxd buffer overrun
581
    {
588
    {
582
        ptr_rxd_buffer = 0; // reset rxd buffer
589
        ptr_rxd_buffer = 0; // reset rxd buffer
583
        rxd_buffer_locked = 0; // unlock rxd buffer
590
        rxd_buffer_locked = 0; // unlock rxd buffer
584
    }
591
    }
585
    LED1_OFF
592
    LED1_OFF
586
}
593
}
587
 
594
 
588
/**
595
/**
589
 * Decode the recevied Buffer
596
 * Decode the recevied Buffer
590
 * portions taken and adapted from
597
 * portions taken and adapted from
591
 * http://svn.mikrokopter.de/mikrowebsvn/filedetails.php?repname=FlightCtrl&path=%2Ftags%2FV0.72p%2Fuart.c
598
 * http://svn.mikrokopter.de/mikrowebsvn/filedetails.php?repname=FlightCtrl&path=%2Ftags%2FV0.72p%2Fuart.c
592
 */
599
 */
593
void Decode64(void) {
600
void Decode64(void) {
594
    uint8_t a, b, c, d;
601
    uint8_t a, b, c, d;
595
    uint8_t x, y, z;
602
    uint8_t x, y, z;
596
    uint8_t ptrIn = 3;
603
    uint8_t ptrIn = 3;
597
    uint8_t ptrOut = 3;
604
    uint8_t ptrOut = 3;
598
    uint8_t len = ReceivedBytes - 6;
605
    uint8_t len = ReceivedBytes - 6;
599
 
606
 
600
    while (len) {
607
    while (len) {
601
        a = rxd_buffer[ptrIn++] - '=';
608
        a = rxd_buffer[ptrIn++] - '=';
602
        b = rxd_buffer[ptrIn++] - '=';
609
        b = rxd_buffer[ptrIn++] - '=';
603
        c = rxd_buffer[ptrIn++] - '=';
610
        c = rxd_buffer[ptrIn++] - '=';
604
        d = rxd_buffer[ptrIn++] - '=';
611
        d = rxd_buffer[ptrIn++] - '=';
605
 
612
 
606
        x = (a << 2) | (b >> 4);
613
        x = (a << 2) | (b >> 4);
607
        y = ((b & 0x0f) << 4) | (c >> 2);
614
        y = ((b & 0x0f) << 4) | (c >> 2);
608
        z = ((c & 0x03) << 6) | d;
615
        z = ((c & 0x03) << 6) | d;
609
 
616
 
610
        if (len--) rxd_buffer[ptrOut++] = x;
617
        if (len--) rxd_buffer[ptrOut++] = x;
611
        else break;
618
        else break;
612
        if (len--) rxd_buffer[ptrOut++] = y;
619
        if (len--) rxd_buffer[ptrOut++] = y;
613
        else break;
620
        else break;
614
        if (len--) rxd_buffer[ptrOut++] = z;
621
        if (len--) rxd_buffer[ptrOut++] = z;
615
        else break;
622
        else break;
616
    }
623
    }
617
    pRxData = &rxd_buffer[3];
624
    pRxData = &rxd_buffer[3];
618
    RxDataLen = ptrOut - 3;
625
    RxDataLen = ptrOut - 3;
619
}
626
}
620
 
627
 
621
/**
628
/**
622
 * request Data through USART in special MK format by adding checksum and
629
 * request Data through USART in special MK format by adding checksum and
623
 * encode data in modified Base64
630
 * encode data in modified Base64
624
 * portions taken and adapted from
631
 * portions taken and adapted from
625
 * http://svn.mikrokopter.de/mikrowebsvn/filedetails.php?repname=FlightCtrl&path=%2Ftags%2FV0.72p%2Fuart.c
632
 * http://svn.mikrokopter.de/mikrowebsvn/filedetails.php?repname=FlightCtrl&path=%2Ftags%2FV0.72p%2Fuart.c
626
 */
633
 */
627
void sendMKData(unsigned char cmd, unsigned char addr, unsigned char *snd, unsigned char len) {
634
void sendMKData(unsigned char cmd, unsigned char addr, unsigned char *snd, unsigned char len) {
628
    unsigned int pt = 0;
635
    unsigned int pt = 0;
629
    unsigned char a, b, c;
636
    unsigned char a, b, c;
630
    unsigned char ptr = 0;
637
    unsigned char ptr = 0;
631
 
638
 
632
    txd_buffer[pt++] = '#'; // Start-Byte
639
    txd_buffer[pt++] = '#'; // Start-Byte
633
    txd_buffer[pt++] = 'a' + addr; // Adress
640
    txd_buffer[pt++] = 'a' + addr; // Adress
634
    txd_buffer[pt++] = cmd; // Command
641
    txd_buffer[pt++] = cmd; // Command
635
    while (len) {
642
    while (len) {
636
        if (len) {
643
        if (len) {
637
            a = snd[ptr++];
644
            a = snd[ptr++];
638
            len--;
645
            len--;
639
        } else a = 0;
646
        } else a = 0;
640
        if (len) {
647
        if (len) {
641
            b = snd[ptr++];
648
            b = snd[ptr++];
642
            len--;
649
            len--;
643
        } else b = 0;
650
        } else b = 0;
644
        if (len) {
651
        if (len) {
645
            c = snd[ptr++];
652
            c = snd[ptr++];
646
            len--;
653
            len--;
647
        } else c = 0;
654
        } else c = 0;
648
        txd_buffer[pt++] = '=' + (a >> 2);
655
        txd_buffer[pt++] = '=' + (a >> 2);
649
        txd_buffer[pt++] = '=' + (((a & 0x03) << 4) | ((b & 0xf0) >> 4));
656
        txd_buffer[pt++] = '=' + (((a & 0x03) << 4) | ((b & 0xf0) >> 4));
650
        txd_buffer[pt++] = '=' + (((b & 0x0f) << 2) | ((c & 0xc0) >> 6));
657
        txd_buffer[pt++] = '=' + (((b & 0x0f) << 2) | ((c & 0xc0) >> 6));
651
        txd_buffer[pt++] = '=' + (c & 0x3f);
658
        txd_buffer[pt++] = '=' + (c & 0x3f);
652
    }
659
    }
653
 
660
 
654
    // add crc
661
    // add crc
655
    unsigned int tmpCRC = 0, i;
662
    unsigned int tmpCRC = 0, i;
656
    for (i = 0; i < pt; i++) {
663
    for (i = 0; i < pt; i++) {
657
        tmpCRC += txd_buffer[i];
664
        tmpCRC += txd_buffer[i];
658
    }
665
    }
659
    tmpCRC %= 4096;
666
    tmpCRC %= 4096;
660
    txd_buffer[i++] = '=' + tmpCRC / 64;
667
    txd_buffer[i++] = '=' + tmpCRC / 64;
661
    txd_buffer[i++] = '=' + tmpCRC % 64;
668
    txd_buffer[i++] = '=' + tmpCRC % 64;
662
    txd_buffer[i++] = '\r';
669
    txd_buffer[i++] = '\r';
663
 
670
 
664
    usart1_puts((char*) txd_buffer);
671
    usart1_puts((char*) txd_buffer);
665
}
672
}
666
 
673
 
667
/* ##########################################################################
674
/* ##########################################################################
668
 * timer stuff
675
 * timer stuff
669
 * ##########################################################################*/
676
 * ##########################################################################*/
670
 
677
 
671
/*
678
/*
672
 * timer kicks in every 1000uS
679
 * timer kicks in every 1000uS
673
 */
680
 */
674
ISR(TIMER0_OVF_vect) {
681
ISR(TIMER0_OVF_vect) {
675
    OCR0 = 6; // preload
682
    OCR0 = 6; // preload
676
    if (!timer--) {
683
    if (!timer--) {
677
        uptime++;
684
        uptime++;
678
        timer = 999;
685
        timer = 999;
679
    }
686
    }
680
}
687
}
681
 
688
 
682
/* ##########################################################################
689
/* ##########################################################################
683
 * compass stuff
690
 * compass stuff
684
 * ##########################################################################*/
691
 * ##########################################################################*/
685
 
692
 
686
/**
693
/**
687
 * convert the <heading> gotton from NC into an index
694
 * convert the <heading> gotton from NC into an index
688
 */
695
 */
689
uint8_t heading_conv(uint16_t heading) {
696
uint8_t heading_conv(uint16_t heading) {
690
    if (heading > 23 && heading < 68) {
697
    if (heading > 23 && heading < 68) {
691
        //direction = "NE";
698
        //direction = "NE";
692
        return 0;
699
        return 0;
693
    } else if (heading > 67 && heading < 113) {
700
    } else if (heading > 67 && heading < 113) {
694
        //direction = "E ";
701
        //direction = "E ";
695
        return 1;
702
        return 1;
696
    } else if (heading > 112 && heading < 158) {
703
    } else if (heading > 112 && heading < 158) {
697
        //direction = "SE";
704
        //direction = "SE";
698
        return 2;
705
        return 2;
699
    } else if (heading > 157 && heading < 203) {
706
    } else if (heading > 157 && heading < 203) {
700
        //direction = "S ";
707
        //direction = "S ";
701
        return 3;
708
        return 3;
702
    } else if (heading > 202 && heading < 248) {
709
    } else if (heading > 202 && heading < 248) {
703
        //direction = "SW";
710
        //direction = "SW";
704
        return 4;
711
        return 4;
705
    } else if (heading > 247 && heading < 293) {
712
    } else if (heading > 247 && heading < 293) {
706
        //direction = "W ";
713
        //direction = "W ";
707
        return 5;
714
        return 5;
708
    } else if (heading > 292 && heading < 338) {
715
    } else if (heading > 292 && heading < 338) {
709
        //direction = "NW";
716
        //direction = "NW";
710
        return 6;
717
        return 6;
711
    }
718
    }
712
    //direction = "N ";
719
    //direction = "N ";
713
    return 7;
720
    return 7;
714
}
721
}
715
 
722
 
716
/**
723
/**
717
 * draw a compass rose at <x>/<y> for <heading>
724
 * draw a compass rose at <x>/<y> for <heading>
718
 */
725
 */
719
void draw_compass(uint8_t x, uint8_t y, uint16_t heading) {
726
void draw_compass(uint8_t x, uint8_t y, uint16_t heading) {
720
    //char* rose = "---N---O---S---W---N---O---S---W---N---O---S---W";
727
    //char* rose = "---N---O---S---W---N---O---S---W---N---O---S---W";
721
    char rose[48] = {216, 215, 216, 211, 216, 215, 216, 213, 216, 215, 216, 212,
728
    char rose[48] = {216, 215, 216, 211, 216, 215, 216, 213, 216, 215, 216, 212,
722
                    216, 215, 216, 214, 216, 215, 216, 211, 216, 215, 216, 213,
729
                    216, 215, 216, 214, 216, 215, 216, 211, 216, 215, 216, 213,
723
                    216, 215, 216, 212, 216, 215, 216, 214, 216, 215, 216, 211,
730
                    216, 215, 216, 212, 216, 215, 216, 214, 216, 215, 216, 211,
724
                    216, 215, 216, 213, 216, 215, 216, 212, 216, 215, 216, 214};
731
                    216, 215, 216, 213, 216, 215, 216, 212, 216, 215, 216, 214};
725
        // the center is char 19 (north), we add the current heading in 8th
732
        // the center is char 19 (north), we add the current heading in 8th
726
        // which would be 22.5 degrees, but float would bloat up the code
733
        // which would be 22.5 degrees, but float would bloat up the code
727
        // and *10 / 225 would take ages... so we take the uncorrect way
734
        // and *10 / 225 would take ages... so we take the uncorrect way
728
    uint8_t front = 19 + (heading / 22);
735
    uint8_t front = 19 + (heading / 22);
729
    for (uint8_t i = 0; i < 9; i++) {
736
    for (uint8_t i = 0; i < 9; i++) {
730
                write_char_xy(x++, y, rose[front - 4 + i]);
737
                write_char_xy(x++, y, rose[front - 4 + i]);
731
    }
738
    }
732
}
739
}
733
 
740
 
734
/* ##########################################################################
741
/* ##########################################################################
735
 * artificial horizon
742
 * artificial horizon
736
 * ##########################################################################*/
743
 * ##########################################################################*/
737
// remember last time displayed values
744
// remember last time displayed values
738
int8_t old_af_x = -1, old_af_y = -1;
745
int8_t old_af_x = -1, old_af_y = -1;
739
 
746
 
740
/**
747
/**
741
 * draw roll und nick indicators (could be enhanced to full artificial horizon)
748
 * draw roll und nick indicators (could be enhanced to full artificial horizon)
742
 * from line <firstline> to <listlines> for given <nick> and <roll> values
749
 * from line <firstline> to <listlines> for given <nick> and <roll> values
743
 */
750
 */
744
void draw_artificial_horizon(uint8_t firstline, uint8_t lastline, int16_t nick, int16_t roll) {
751
void draw_artificial_horizon(uint8_t firstline, uint8_t lastline, int16_t nick, int16_t roll) {
745
        char noodle[5] = {225, 225, 226, 227, 227};
752
        char noodle[5] = {225, 225, 226, 227, 227};
746
        uint8_t center_x = 15;
753
        uint8_t center_x = 15;
747
        uint8_t center_y = lastline - firstline;
754
        uint8_t center_y = lastline - firstline;
748
        center_y = 7;
755
        center_y = 7;
749
        write_char_xy(center_x,center_y,228);
756
        write_char_xy(center_x,center_y,228);
750
        uint8_t cpos, nicky, rollx;
757
        uint8_t cpos, nicky, rollx;
751
       
758
       
752
        // which line
759
        // which line
753
        int8_t ypos =  nick / 20;
760
        int8_t ypos =  nick / 20;
754
        // which character from the array?
761
        // which character from the array?
755
        if (nick < 0) {
762
        if (nick < 0) {
756
                cpos = -1*((nick - (ypos * 20))/4);
763
                cpos = -1*((nick - (ypos * 20))/4);
757
                ypos--;
764
                ypos--;
758
        } else cpos = 4-((nick - (ypos * 20))/4);
765
        } else cpos = 4-((nick - (ypos * 20))/4);
759
        if (cpos > 4) cpos = 4;
766
        if (cpos > 4) cpos = 4;
760
 
767
 
761
        nicky = center_y - ypos;
768
        nicky = center_y - ypos;
762
        if (nicky > lastline) nicky = lastline;
769
        if (nicky > lastline) nicky = lastline;
763
        else if (nicky < firstline) nicky = firstline;
770
        else if (nicky < firstline) nicky = firstline;
764
 
771
 
765
        // ensure roll-borders
772
        // ensure roll-borders
766
        rollx = (roll / 8)+15;
773
        rollx = (roll / 8)+15;
767
        if (rollx < 2) rollx = 2;
774
        if (rollx < 2) rollx = 2;
768
        else if (rollx > 28) rollx = 28;
775
        else if (rollx > 28) rollx = 28;
769
 
776
 
770
 
777
 
771
        // clear roll
778
        // clear roll
772
        if (old_af_x != rollx && old_af_x >= 0) {
779
        if (old_af_x != rollx && old_af_x >= 0) {
773
                write_char_xy(old_af_x,13,0);
780
                write_char_xy(old_af_x,13,0);
774
        }
781
        }
775
 
782
 
776
        // clear nick
783
        // clear nick
777
        if (old_af_y != nicky && old_af_y >= 0) {
784
        if (old_af_y != nicky && old_af_y >= 0) {
778
                write_char_xy(center_x-1,old_af_y,0);
785
                write_char_xy(center_x-1,old_af_y,0);
779
                write_char_xy(center_x+1,old_af_y,0);
786
                write_char_xy(center_x+1,old_af_y,0);
780
        }
787
        }
781
 
788
 
782
 
789
 
783
        // draw nick
790
        // draw nick
784
        write_char_xy(center_x-1,nicky,noodle[cpos]);
791
        write_char_xy(center_x-1,nicky,noodle[cpos]);
785
        write_char_xy(center_x+1,nicky,noodle[cpos]);
792
        write_char_xy(center_x+1,nicky,noodle[cpos]);
786
 
793
 
787
        // draw roll
794
        // draw roll
788
        write_char_xy(rollx,lastline,229);
795
        write_char_xy(rollx,lastline,229);
789
 
796
 
790
        // update old vars
797
        // update old vars
791
        old_af_x = rollx;
798
        old_af_x = rollx;
792
        old_af_y = nicky;
799
        old_af_y = nicky;
793
 
800
 
794
        // debug numbers
801
        // debug numbers
795
        //write_3digit_number_u(20,6,cpos);
802
        //write_3digit_number_u(20,6,cpos);
796
        //write_number_s(20,7,ypos);    
803
        //write_number_s(20,7,ypos);    
797
        //write_number_s(0,7,nick);             
804
        //write_number_s(0,7,nick);             
798
        //write_number_s(18,11,roll);   
805
        //write_number_s(18,11,roll);   
799
}
806
}
800
 
807
 
801
/* ##########################################################################
808
/* ##########################################################################
802
 * A simple config menu for the flags
809
 * A simple config menu for the flags
803
 * ##########################################################################*/
810
 * ##########################################################################*/
804
void config_menu(void) {
811
void config_menu(void) {
805
        // disable interrupts (makes the menu more smoothely)
812
        // disable interrupts (makes the menu more smoothely)
806
        cli();
813
        cli();
807
 
814
 
808
        // clear screen
815
        // clear screen
809
        clear();
816
        clear();
810
       
817
       
811
        char* menu[4] = {"Normal OSD      ",
818
        char* menu[4] = {"Normal OSD      ",
812
                                         "Art.Horizon     ",
819
                                         "Art.Horizon     ",
813
                                         "NO OSD          ",
820
                                         "NO OSD          ",
814
                                         "NO OSD but WRN  "};
821
                                         "NO OSD but WRN  "};
815
 
822
 
816
        uint8_t inmenu = 1;
823
        uint8_t inmenu = 1;
817
        uint8_t chosen = 0;
824
        uint8_t chosen = 0;
818
        write_ascii_string(10,  4, "Config Menu");
825
        write_ascii_string(10,  4, "Config Menu");
819
       
826
       
820
        // clear all mode flags
827
        // clear all mode flags
821
        COSD_FLAGS &= ~(COSD_FLAG_ARTHORIZON | COSD_FLAG_NOOSD | COSD_FLAG_NOOSD_BUT_WRN);
828
        COSD_FLAGS &= ~(COSD_FLAG_ARTHORIZON | COSD_FLAG_NOOSD | COSD_FLAG_NOOSD_BUT_WRN);
822
 
829
 
823
        // wait a bit before doing stuff so user has chance to release button
830
        // wait a bit before doing stuff so user has chance to release button
824
        _delay_ms(250);
831
        _delay_ms(250);
825
 
832
 
826
        while (inmenu) {
833
        while (inmenu) {
827
                        write_ascii_string(2,  7, menu[chosen]);
834
                        write_ascii_string(2,  7, menu[chosen]);
828
                        if (s2_pressed()) {
835
                        if (s2_pressed()) {
829
                                chosen = (chosen + 1) % 4;
836
                                chosen = (chosen + 1) % 4;
830
                                _delay_ms(500);
837
                                _delay_ms(500);
831
                        } else if (s1_pressed()) {
838
                        } else if (s1_pressed()) {
832
                                switch (chosen) {
839
                                switch (chosen) {
833
                                        case 1:         // artificial horizon
840
                                        case 1:         // artificial horizon
834
                                                COSD_FLAGS |= COSD_FLAG_ARTHORIZON;
841
                                                COSD_FLAGS |= COSD_FLAG_ARTHORIZON;
835
                                                break;
842
                                                break;
836
                                        case 2:         // everything off
843
                                        case 2:         // everything off
837
                                                COSD_FLAGS |= COSD_FLAG_NOOSD;
844
                                                COSD_FLAGS |= COSD_FLAG_NOOSD;
838
                                                break;
845
                                                break;
839
                                        case 3:         // only warning
846
                                        case 3:         // only warning
840
                                                COSD_FLAGS |= COSD_FLAG_NOOSD_BUT_WRN;
847
                                                COSD_FLAGS |= COSD_FLAG_NOOSD_BUT_WRN;
841
                                                break;
848
                                                break;
842
                                        //default:      // normal OSD, so let the flags cleared
849
                                        //default:      // normal OSD, so let the flags cleared
843
                                }
850
                                }
844
                                // leave menu
851
                                // leave menu
845
                                inmenu = 0;
852
                                inmenu = 0;
846
                                _delay_ms(500);
853
                                _delay_ms(500);
847
                        }
854
                        }
848
        }
855
        }
849
 
856
 
850
        // clear screen up again
857
        // clear screen up again
851
        clear();
858
        clear();
852
 
859
 
853
        // update flags to paint display again if needed
860
        // update flags to paint display again if needed
854
        COSD_FLAGS &= ~COSD_ICONS_WRITTEN;
861
        COSD_FLAGS &= ~COSD_ICONS_WRITTEN;
855
 
862
 
856
        // enable interrupts again
863
        // enable interrupts again
857
        sei();
864
        sei();
858
}
865
}
859
 
866
 
860
#endif // ends !(ALLCHARSDEBUG|WRITECHARS)
867
#endif // ends !(ALLCHARSDEBUG|(WRITECHARS != -1))
861
 
868
 
862
/* ##########################################################################
869
/* ##########################################################################
863
 * MAIN
870
 * MAIN
864
 * ##########################################################################*/
871
 * ##########################################################################*/
865
int main(void) {
872
int main(void) {
866
        // set up FLAGS, compiler should flatten this one
873
        // set up FLAGS, compiler should flatten this one
867
        COSD_FLAGS = (NTSC << (COSD_FLAG_NTSC - 1));
874
        COSD_FLAGS = (NTSC << (COSD_FLAG_NTSC - 1));
868
        COSD_FLAGS |= (ARTHORIZON << (COSD_FLAG_ARTHORIZON - 1));
875
        COSD_FLAGS |= (ARTHORIZON << (COSD_FLAG_ARTHORIZON - 1));
869
        COSD_FLAGS |= (NOOSD << (COSD_FLAG_NOOSD - 1));
876
        COSD_FLAGS |= (NOOSD << (COSD_FLAG_NOOSD - 1));
870
        COSD_FLAGS |= (NOOSD_BUT_WRN << (COSD_FLAG_NOOSD_BUT_WRN - 1));
877
        COSD_FLAGS |= (NOOSD_BUT_WRN << (COSD_FLAG_NOOSD_BUT_WRN - 1));
871
 
878
 
872
        // set up Atmega162 Ports
879
        // set up Atmega162 Ports
873
    DDRA |= (1 << PA1); // PA1 output (/CS)
880
    DDRA |= (1 << PA1); // PA1 output (/CS)
874
    MAX_CS_HIGH
881
    MAX_CS_HIGH
875
    DDRA |= (1 << PA2); // PA2 output (SDIN)
882
    DDRA |= (1 << PA2); // PA2 output (SDIN)
876
    MAX_SDIN_LOW
883
    MAX_SDIN_LOW
877
    DDRA |= (1 << PA3); // PA3 output (SCLK)
884
    DDRA |= (1 << PA3); // PA3 output (SCLK)
878
    MAX_SCLK_LOW
885
    MAX_SCLK_LOW
879
    DDRA |= (1 << PA5); // PA5 output (RESET)
886
    DDRA |= (1 << PA5); // PA5 output (RESET)
880
    MAX_RESET_HIGH
887
    MAX_RESET_HIGH
881
 
888
 
882
    DDRC |= (1 << PC0); // PC0 output (LED1 gn)
889
    DDRC |= (1 << PC0); // PC0 output (LED1 gn)
883
    LED1_OFF
890
    LED1_OFF
884
    DDRC |= (1 << PC1); // PC1 output (LED2 rt)
891
    DDRC |= (1 << PC1); // PC1 output (LED2 rt)
885
    LED2_OFF
892
    LED2_OFF
886
    DDRC |= (1 << PC2); // PC2 output (LED3 gn)
893
    DDRC |= (1 << PC2); // PC2 output (LED3 gn)
887
    LED3_OFF
894
    LED3_OFF
888
    DDRC |= (1 << PC3); // PC3 output (LED4 rt)
895
    DDRC |= (1 << PC3); // PC3 output (LED4 rt)
889
    LED4_OFF
896
    LED4_OFF
890
 
897
 
891
    DDRC &= ~(1 << PC4); // PC4 input  (MODE)
898
    DDRC &= ~(1 << PC4); // PC4 input  (MODE)
892
    PORTC |= (1 << PC4); // pullup
899
    PORTC |= (1 << PC4); // pullup
893
    DDRC &= ~(1 << PC5); // PC5 input  (SET)
900
    DDRC &= ~(1 << PC5); // PC5 input  (SET)
894
    PORTC |= (1 << PC5); // pullup
901
    PORTC |= (1 << PC5); // pullup
895
 
902
 
896
        // set up top and bottom lines
903
        // set up top and bottom lines
897
        if (COSD_FLAGS & COSD_FLAG_NTSC) {
904
        if (COSD_FLAGS & COSD_FLAG_NTSC) {
898
                bottom_line = 12;
905
                bottom_line = 12;
899
        } else {
906
        } else {
900
                bottom_line = 14;
907
                bottom_line = 14;
901
        }
908
        }
902
 
909
 
903
        // reset the MAX7456 to be sure any undefined states do no harm
910
        // reset the MAX7456 to be sure any undefined states do no harm
904
    MAX_RESET_LOW
911
    MAX_RESET_LOW
905
    MAX_RESET_HIGH
912
    MAX_RESET_HIGH
906
 
913
 
907
        // check for keypress at startup
914
        // check for keypress at startup
908
        if (s2_pressed()) { // togle COSD_FLAG_ARTHORIZON
915
        if (s2_pressed()) { // togle COSD_FLAG_ARTHORIZON
909
                        COSD_FLAGS ^= (1 << (COSD_FLAG_ARTHORIZON - 1));
916
                        COSD_FLAGS ^= (1 << (COSD_FLAG_ARTHORIZON - 1));
910
                        _delay_ms(100);
917
                        _delay_ms(100);
911
    }
918
    }
912
 
919
 
913
    // give the FC/NC and the maxim time to come up
920
    // give the FC/NC and the maxim time to come up
914
    LED4_ON
921
    LED4_ON
915
    _delay_ms(2000);
922
    _delay_ms(2000);
916
 
923
 
917
    LED4_OFF
924
    LED4_OFF
918
 
925
 
919
    /* ##########################################################################
926
    /* ##########################################################################
920
     * Pushing NEW chars to the MAX7456
927
     * Pushing NEW chars to the MAX7456
921
     * ##########################################################################*/
928
     * ##########################################################################*/
922
#if WRITECHARS
929
#if (WRITECHARS != -1)
923
        void learn_char(uint8_t number, unsigned char* data) {
930
        void learn_char(uint8_t number, unsigned char* data) {
924
        // select character to write (CMAH)
931
        // select character to write (CMAH)
925
        spi_send_byte(0x09, number);
932
        spi_send_byte(0x09, number);
926
 
933
 
927
        for (uint8_t i = 0; i < 54; i++) {
934
        for (uint8_t i = 0; i < 54; i++) {
928
            // select 4pixel byte of char (CMAL)
935
            // select 4pixel byte of char (CMAL)
929
            spi_send_byte(0x0A, i);
936
            spi_send_byte(0x0A, i);
930
 
937
 
931
            // write 4pixel byte of char (CMDI)
938
            // write 4pixel byte of char (CMDI)
932
            spi_send_byte(0x0B, data[i]);
939
            spi_send_byte(0x0B, data[i]);
933
        }
940
        }
934
 
941
 
935
        // write to the NVM array from the shadow RAM (CMM)
942
        // write to the NVM array from the shadow RAM (CMM)
936
        spi_send_byte(0x08, 0b10100000);
943
        spi_send_byte(0x08, 0b10100000);
937
 
944
 
938
        // according to maxim writing to nvram takes about 12ms, lets wait longer
945
        // according to maxim writing to nvram takes about 12ms, lets wait longer
939
        _delay_ms(120);
946
        _delay_ms(120);
940
    }
947
    }
941
 
948
 
942
    // DISABLE display (VM0)
949
    // DISABLE display (VM0)
943
    spi_send_byte(0x00, 0b00000000);
950
    spi_send_byte(0x00, 0b00000000);
944
 
951
 
945
    /**
952
    /**
946
     * easy char creation:
953
     * easy char creation:
947
     * http://cascade.dyndns.org/~cascade/scripts/max7456/
954
     * http://cascade.dyndns.org/~cascade/scripts/max7456/
948
     */
955
     */
949
        // flashing more than 8 chars per time is not proven to be safe
956
        // flashing more than 8 chars per time is not proven to be safe
950
        // so take care
957
        // so take care
951
#if WRITECHARS == 200
958
#if WRITECHARS == 200
952
        // GPS
959
        // GPS
953
    unsigned char cc8[54] = {0x55, 0x50, 0x55, 0x55, 0x4a, 0x15, 0x55, 0x2a,
960
    unsigned char cc8[54] = {0x55, 0x50, 0x55, 0x55, 0x4a, 0x15, 0x55, 0x2a,
954
        0x85, 0x55, 0x2a, 0xa1, 0x55, 0x4a, 0xa8, 0x55,
961
        0x85, 0x55, 0x2a, 0xa1, 0x55, 0x4a, 0xa8, 0x55,
955
        0x52, 0xa8, 0x55, 0x54, 0xaa, 0x55, 0x55, 0x09,
962
        0x52, 0xa8, 0x55, 0x54, 0xaa, 0x55, 0x55, 0x09,
956
        0x55, 0x55, 0x52, 0x55, 0x55, 0x1a, 0x55, 0x51,
963
        0x55, 0x55, 0x52, 0x55, 0x55, 0x1a, 0x55, 0x51,
957
        0x96, 0x55, 0x18, 0x85, 0x54, 0x88, 0x28, 0x54,
964
        0x96, 0x55, 0x18, 0x85, 0x54, 0x88, 0x28, 0x54,
958
        0x82, 0x05, 0x55, 0x20, 0xa1, 0x55, 0x48, 0x15,
965
        0x82, 0x05, 0x55, 0x20, 0xa1, 0x55, 0x48, 0x15,
959
        0x55, 0x52, 0x85, 0x55, 0x54, 0x15};
966
        0x55, 0x52, 0x85, 0x55, 0x54, 0x15};
960
 
967
 
961
    unsigned char cc9[54] = {0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
968
    unsigned char cc9[54] = {0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
962
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x45,
969
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x45,
963
        0x55, 0x55, 0x21, 0x55, 0x55, 0xa8, 0x55, 0x55,
970
        0x55, 0x55, 0x21, 0x55, 0x55, 0xa8, 0x55, 0x55,
964
        0xa1, 0x55, 0x55, 0x98, 0x15, 0x55, 0x2a, 0x85,
971
        0xa1, 0x55, 0x55, 0x98, 0x15, 0x55, 0x2a, 0x85,
965
        0x55, 0x4a, 0xa1, 0x55, 0x4a, 0xa8, 0x55, 0x52,
972
        0x55, 0x4a, 0xa1, 0x55, 0x4a, 0xa8, 0x55, 0x52,
966
        0xaa, 0x15, 0x54, 0xaa, 0x15, 0x55, 0x28, 0x55,
973
        0xaa, 0x15, 0x54, 0xaa, 0x15, 0x55, 0x28, 0x55,
967
        0x55, 0x41, 0x55, 0x55, 0x55, 0x55};
974
        0x55, 0x41, 0x55, 0x55, 0x55, 0x55};
968
 
975
 
969
    // RC
976
    // RC
970
    unsigned char cca[54] = {0x54, 0xaa, 0x85, 0x52, 0x00, 0x21, 0x48, 0x2a,
977
    unsigned char cca[54] = {0x54, 0xaa, 0x85, 0x52, 0x00, 0x21, 0x48, 0x2a,
971
        0x08, 0x60, 0x80, 0x82, 0x62, 0x08, 0x22, 0x62,
978
        0x08, 0x60, 0x80, 0x82, 0x62, 0x08, 0x22, 0x62,
972
        0x2a, 0x22, 0x62, 0x08, 0x22, 0x60, 0x88, 0x82,
979
        0x2a, 0x22, 0x62, 0x08, 0x22, 0x60, 0x88, 0x82,
973
        0x48, 0x08, 0x08, 0x52, 0x08, 0x21, 0x54, 0x48,
980
        0x48, 0x08, 0x08, 0x52, 0x08, 0x21, 0x54, 0x48,
974
        0x45, 0x55, 0x48, 0x55, 0x55, 0x48, 0x55, 0x55,
981
        0x45, 0x55, 0x48, 0x55, 0x55, 0x48, 0x55, 0x55,
975
        0x48, 0x55, 0x55, 0x48, 0x55, 0x55, 0x48, 0x55,
982
        0x48, 0x55, 0x55, 0x48, 0x55, 0x55, 0x48, 0x55,
976
        0x55, 0x2a, 0x15, 0x54, 0xaa, 0x85};
983
        0x55, 0x2a, 0x15, 0x54, 0xaa, 0x85};
977
 
984
 
978
    // km/h
985
    // km/h
979
    unsigned char ccb[54] = {0x55, 0x55, 0x55, 0x01, 0x55, 0x55, 0x21, 0x55,
986
    unsigned char ccb[54] = {0x55, 0x55, 0x55, 0x01, 0x55, 0x55, 0x21, 0x55,
980
        0x55, 0x20, 0x15, 0x55, 0x22, 0x15, 0x55, 0x28,
987
        0x55, 0x20, 0x15, 0x55, 0x22, 0x15, 0x55, 0x28,
981
        0x15, 0x55, 0x22, 0x15, 0x55, 0x00, 0x00, 0x15,
988
        0x15, 0x55, 0x22, 0x15, 0x55, 0x00, 0x00, 0x15,
982
        0x52, 0xaa, 0x15, 0x52, 0x22, 0x15, 0x52, 0x22,
989
        0x52, 0xaa, 0x15, 0x52, 0x22, 0x15, 0x52, 0x22,
983
        0x15, 0x50, 0x00, 0x05, 0x55, 0x54, 0x85, 0x55,
990
        0x15, 0x50, 0x00, 0x05, 0x55, 0x54, 0x85, 0x55,
984
        0x54, 0x80, 0x55, 0x54, 0xa8, 0x55, 0x54, 0x88,
991
        0x54, 0x80, 0x55, 0x54, 0xa8, 0x55, 0x54, 0x88,
985
        0x55, 0x54, 0x88, 0x55, 0x54, 0x00};
992
        0x55, 0x54, 0x88, 0x55, 0x54, 0x00};
986
 
993
 
987
 
994
 
988
    // small meters m
995
    // small meters m
989
    unsigned char ccc[54] = {0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
996
    unsigned char ccc[54] = {0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
990
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
997
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
991
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
998
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
992
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
999
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
993
        0x55, 0x55, 0x55, 0x55, 0x00, 0x00, 0x15, 0x22,
1000
        0x55, 0x55, 0x55, 0x55, 0x00, 0x00, 0x15, 0x22,
994
        0x8a, 0x15, 0x28, 0xa2, 0x15, 0x20, 0x82, 0x15,
1001
        0x8a, 0x15, 0x28, 0xa2, 0x15, 0x20, 0x82, 0x15,
995
        0x20, 0x82, 0x15, 0x00, 0x00, 0x15};
1002
        0x20, 0x82, 0x15, 0x00, 0x00, 0x15};
996
 
1003
 
997
    // vario down
1004
    // vario down
998
    unsigned char ccd[54] = {0x55, 0x00, 0x55, 0x55, 0x28, 0x55, 0x55, 0x28,
1005
    unsigned char ccd[54] = {0x55, 0x00, 0x55, 0x55, 0x28, 0x55, 0x55, 0x28,
999
        0x55, 0x55, 0x28, 0x55, 0x55, 0x28, 0x55, 0x55,
1006
        0x55, 0x55, 0x28, 0x55, 0x55, 0x28, 0x55, 0x55,
1000
        0x28, 0x55, 0x55, 0x28, 0x55, 0x55, 0x28, 0x55,
1007
        0x28, 0x55, 0x55, 0x28, 0x55, 0x55, 0x28, 0x55,
1001
        0x55, 0x28, 0x55, 0x55, 0x28, 0x55, 0x55, 0x28,
1008
        0x55, 0x28, 0x55, 0x55, 0x28, 0x55, 0x55, 0x28,
1002
        0x55, 0x00, 0x28, 0x00, 0x2a, 0xaa, 0xa8, 0x0a,
1009
        0x55, 0x00, 0x28, 0x00, 0x2a, 0xaa, 0xa8, 0x0a,
1003
        0xaa, 0xa0, 0x42, 0xaa, 0x81, 0x50, 0xaa, 0x05,
1010
        0xaa, 0xa0, 0x42, 0xaa, 0x81, 0x50, 0xaa, 0x05,
1004
        0x54, 0x28, 0x15, 0x55, 0x00, 0x55};
1011
        0x54, 0x28, 0x15, 0x55, 0x00, 0x55};
1005
 
1012
 
1006
    // vario hold
1013
    // vario hold
1007
    unsigned char cce[54] = {0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1014
    unsigned char cce[54] = {0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1008
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1015
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1009
        0x55, 0x55, 0x55, 0x55, 0x55, 0x00, 0x00, 0x00,
1016
        0x55, 0x55, 0x55, 0x55, 0x55, 0x00, 0x00, 0x00,
1010
        0x2a, 0xaa, 0xa8, 0x2a, 0xaa, 0xa8, 0x00, 0x00,
1017
        0x2a, 0xaa, 0xa8, 0x2a, 0xaa, 0xa8, 0x00, 0x00,
1011
        0x00, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1018
        0x00, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1012
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1019
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1013
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55};
1020
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55};
1014
 
1021
 
1015
    // vario up
1022
    // vario up
1016
    unsigned char ccf[54] = {0x55, 0x00, 0x55, 0x54, 0x28, 0x15, 0x50, 0xaa,
1023
    unsigned char ccf[54] = {0x55, 0x00, 0x55, 0x54, 0x28, 0x15, 0x50, 0xaa,
1017
        0x05, 0x42, 0xaa, 0x81, 0x0a, 0xaa, 0xa0, 0x2a,
1024
        0x05, 0x42, 0xaa, 0x81, 0x0a, 0xaa, 0xa0, 0x2a,
1018
        0xaa, 0xa8, 0x00, 0x28, 0x00, 0x55, 0x28, 0x55,
1025
        0xaa, 0xa8, 0x00, 0x28, 0x00, 0x55, 0x28, 0x55,
1019
        0x55, 0x28, 0x55, 0x55, 0x28, 0x55, 0x55, 0x28,
1026
        0x55, 0x28, 0x55, 0x55, 0x28, 0x55, 0x55, 0x28,
1020
        0x55, 0x55, 0x28, 0x55, 0x55, 0x28, 0x55, 0x55,
1027
        0x55, 0x55, 0x28, 0x55, 0x55, 0x28, 0x55, 0x55,
1021
        0x28, 0x55, 0x55, 0x28, 0x55, 0x55, 0x28, 0x55,
1028
        0x28, 0x55, 0x55, 0x28, 0x55, 0x55, 0x28, 0x55,
1022
        0x55, 0x28, 0x55, 0x55, 0x00, 0x55};
1029
        0x55, 0x28, 0x55, 0x55, 0x00, 0x55};
1023
 
1030
 
1024
    learn_char(200, cc8);
1031
    learn_char(200, cc8);
1025
    learn_char(201, cc9);
1032
    learn_char(201, cc9);
1026
    learn_char(202, cca);
1033
    learn_char(202, cca);
1027
    learn_char(203, ccb);
1034
    learn_char(203, ccb);
1028
    learn_char(204, ccc);
1035
    learn_char(204, ccc);
1029
    learn_char(205, ccd);
1036
    learn_char(205, ccd);
1030
    learn_char(206, cce);
1037
    learn_char(206, cce);
1031
    learn_char(207, ccf);
1038
    learn_char(207, ccf);
1032
#endif
1039
#endif
1033
#if WRITECHARS == 208
1040
#if WRITECHARS == 208
1034
   // degree symbol
1041
   // degree symbol
1035
    unsigned char cd0[54] = {0x55, 0x55, 0x55, 0x54, 0x01, 0x55, 0x52, 0xa8,
1042
    unsigned char cd0[54] = {0x55, 0x55, 0x55, 0x54, 0x01, 0x55, 0x52, 0xa8,
1036
        0x55, 0x48, 0x02, 0x15, 0x48, 0x52, 0x15, 0x48,
1043
        0x55, 0x48, 0x02, 0x15, 0x48, 0x52, 0x15, 0x48,
1037
        0x52, 0x15, 0x48, 0x02, 0x15, 0x52, 0xa8, 0x55,
1044
        0x52, 0x15, 0x48, 0x02, 0x15, 0x52, 0xa8, 0x55,
1038
        0x54, 0x01, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1045
        0x54, 0x01, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1039
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1046
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1040
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1047
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1041
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55};
1048
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55};
1042
 
1049
 
1043
    // clock on symbol
1050
    // clock on symbol
1044
    unsigned char cd1[54] = {0x54, 0x14, 0x51, 0x52, 0x82, 0x08, 0x48, 0x22,
1051
    unsigned char cd1[54] = {0x54, 0x14, 0x51, 0x52, 0x82, 0x08, 0x48, 0x22,
1045
        0x88, 0x48, 0x22, 0x28, 0x48, 0x22, 0x28, 0x52,
1052
        0x88, 0x48, 0x22, 0x28, 0x48, 0x22, 0x28, 0x52,
1046
        0x82, 0x08, 0x54, 0x14, 0x51, 0x55, 0x40, 0x55,
1053
        0x82, 0x08, 0x54, 0x14, 0x51, 0x55, 0x40, 0x55,
1047
        0x55, 0x2a, 0x15, 0x54, 0x88, 0x85, 0x52, 0x08,
1054
        0x55, 0x2a, 0x15, 0x54, 0x88, 0x85, 0x52, 0x08,
1048
        0x21, 0x48, 0x48, 0x08, 0x48, 0x4a, 0x88, 0x48,
1055
        0x21, 0x48, 0x48, 0x08, 0x48, 0x4a, 0x88, 0x48,
1049
        0x50, 0x08, 0x52, 0x15, 0x21, 0x54, 0x80, 0x85,
1056
        0x50, 0x08, 0x52, 0x15, 0x21, 0x54, 0x80, 0x85,
1050
        0x55, 0x2a, 0x15, 0x55, 0x40, 0x55};
1057
        0x55, 0x2a, 0x15, 0x55, 0x40, 0x55};
1051
 
1058
 
1052
    // clock fly symbol
1059
    // clock fly symbol
1053
    unsigned char cd2[54] = {0x40, 0x45, 0x11, 0x2a, 0x20, 0x88, 0x20, 0x20,
1060
    unsigned char cd2[54] = {0x40, 0x45, 0x11, 0x2a, 0x20, 0x88, 0x20, 0x20,
1054
        0x88, 0x28, 0x21, 0x21, 0x21, 0x20, 0x21, 0x21,
1061
        0x88, 0x28, 0x21, 0x21, 0x21, 0x20, 0x21, 0x21,
1055
        0x2a, 0x21, 0x45, 0x40, 0x45, 0x55, 0x40, 0x55,
1062
        0x2a, 0x21, 0x45, 0x40, 0x45, 0x55, 0x40, 0x55,
1056
        0x55, 0x2a, 0x15, 0x54, 0x88, 0x85, 0x52, 0x08,
1063
        0x55, 0x2a, 0x15, 0x54, 0x88, 0x85, 0x52, 0x08,
1057
        0x21, 0x48, 0x48, 0x08, 0x48, 0x4a, 0x88, 0x48,
1064
        0x21, 0x48, 0x48, 0x08, 0x48, 0x4a, 0x88, 0x48,
1058
        0x50, 0x08, 0x52, 0x15, 0x21, 0x54, 0x80, 0x85,
1065
        0x50, 0x08, 0x52, 0x15, 0x21, 0x54, 0x80, 0x85,
1059
        0x55, 0x2a, 0x15, 0x55, 0x40, 0x55};
1066
        0x55, 0x2a, 0x15, 0x55, 0x40, 0x55};
1060
 
1067
 
1061
    // compass north
1068
    // compass north
1062
    unsigned char cd3[54] = {0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1069
    unsigned char cd3[54] = {0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1063
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x54,
1070
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x54,
1064
        0x54, 0x55, 0x52, 0x12, 0x15, 0x52, 0x82, 0x15,
1071
        0x54, 0x55, 0x52, 0x12, 0x15, 0x52, 0x82, 0x15,
1065
        0x02, 0x82, 0x00, 0xa2, 0x22, 0x2a, 0x02, 0x0a,
1072
        0x02, 0x82, 0x00, 0xa2, 0x22, 0x2a, 0x02, 0x0a,
1066
        0x00, 0x52, 0x0a, 0x15, 0x52, 0x12, 0x15, 0x54,
1073
        0x00, 0x52, 0x0a, 0x15, 0x52, 0x12, 0x15, 0x54,
1067
        0x54, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1074
        0x54, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1068
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55};
1075
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55};
1069
 
1076
 
1070
    // compass south
1077
    // compass south
1071
    unsigned char cd4[54] = {0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1078
    unsigned char cd4[54] = {0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1072
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1079
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1073
        0x01, 0x55, 0x54, 0xa8, 0x55, 0x52, 0x02, 0x15,
1080
        0x01, 0x55, 0x54, 0xa8, 0x55, 0x52, 0x02, 0x15,
1074
        0x04, 0x84, 0x40, 0xa1, 0x21, 0x2a, 0x04, 0x48,
1081
        0x04, 0x84, 0x40, 0xa1, 0x21, 0x2a, 0x04, 0x48,
1075
        0x40, 0x52, 0x02, 0x15, 0x54, 0xa8, 0x55, 0x55,
1082
        0x40, 0x52, 0x02, 0x15, 0x54, 0xa8, 0x55, 0x55,
1076
        0x01, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1083
        0x01, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1077
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55};
1084
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55};
1078
 
1085
 
1079
    // compass east
1086
    // compass east
1080
    unsigned char cd5[54] = {0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1087
    unsigned char cd5[54] = {0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1081
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x54,
1088
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x54,
1082
        0x00, 0x55, 0x52, 0xaa, 0x15, 0x52, 0x00, 0x55,
1089
        0x00, 0x55, 0x52, 0xaa, 0x15, 0x52, 0x00, 0x55,
1083
        0x02, 0x05, 0x40, 0xa2, 0xa1, 0x2a, 0x02, 0x05,
1090
        0x02, 0x05, 0x40, 0xa2, 0xa1, 0x2a, 0x02, 0x05,
1084
        0x40, 0x52, 0x00, 0x55, 0x52, 0xaa, 0x15, 0x54,
1091
        0x40, 0x52, 0x00, 0x55, 0x52, 0xaa, 0x15, 0x54,
1085
        0x00, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1092
        0x00, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1086
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55};
1093
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55};
1087
 
1094
 
1088
    // compass west
1095
    // compass west
1089
    unsigned char cd6[54] = {0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1096
    unsigned char cd6[54] = {0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1090
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x54,
1097
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x54,
1091
        0x54, 0x55, 0x52, 0x12, 0x15, 0x52, 0x12, 0x15,
1098
        0x54, 0x55, 0x52, 0x12, 0x15, 0x52, 0x12, 0x15,
1092
        0x02, 0x02, 0x00, 0xa2, 0x22, 0x2a, 0x02, 0x8a,
1099
        0x02, 0x02, 0x00, 0xa2, 0x22, 0x2a, 0x02, 0x8a,
1093
        0x00, 0x52, 0x8a, 0x15, 0x52, 0x12, 0x15, 0x54,
1100
        0x00, 0x52, 0x8a, 0x15, 0x52, 0x12, 0x15, 0x54,
1094
        0x54, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1101
        0x54, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1095
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55};
1102
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55};
1096
 
1103
 
1097
    // compass between
1104
    // compass between
1098
    unsigned char cd7[54] = {0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1105
    unsigned char cd7[54] = {0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1099
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1106
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1100
        0x55, 0x55, 0x55, 0x45, 0x55, 0x55, 0x21, 0x55,
1107
        0x55, 0x55, 0x55, 0x45, 0x55, 0x55, 0x21, 0x55,
1101
        0x01, 0x21, 0x00, 0xa8, 0x20, 0xaa, 0x01, 0x21,
1108
        0x01, 0x21, 0x00, 0xa8, 0x20, 0xaa, 0x01, 0x21,
1102
        0x00, 0x55, 0x21, 0x55, 0x55, 0x45, 0x55, 0x55,
1109
        0x00, 0x55, 0x21, 0x55, 0x55, 0x45, 0x55, 0x55,
1103
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1110
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1104
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55};
1111
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55};
1105
 
1112
 
1106
    learn_char(208, cd0);
1113
    learn_char(208, cd0);
1107
    learn_char(209, cd1);
1114
    learn_char(209, cd1);
1108
    learn_char(210, cd2);
1115
    learn_char(210, cd2);
1109
    learn_char(211, cd3);
1116
    learn_char(211, cd3);
1110
    learn_char(212, cd4);
1117
    learn_char(212, cd4);
1111
    learn_char(213, cd5);
1118
    learn_char(213, cd5);
1112
    learn_char(214, cd6);
1119
    learn_char(214, cd6);
1113
    learn_char(215, cd7);
1120
    learn_char(215, cd7);
1114
#endif
1121
#endif
1115
#if WRITECHARS == 216
1122
#if WRITECHARS == 216
1116
    // compass line
1123
    // compass line
1117
    unsigned char cd8[54] = {0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1124
    unsigned char cd8[54] = {0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1118
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1125
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1119
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1126
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1120
        0x00, 0x00, 0x00, 0xaa, 0xaa, 0xaa, 0x00, 0x00,
1127
        0x00, 0x00, 0x00, 0xaa, 0xaa, 0xaa, 0x00, 0x00,
1121
        0x00, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1128
        0x00, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1122
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1129
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1123
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55};
1130
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55};
1124
 
1131
 
1125
    // arrow right
1132
    // arrow right
1126
    unsigned char cd9[54] ={0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1133
    unsigned char cd9[54] ={0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1127
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1134
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1128
        0x55, 0x15, 0x55, 0x54, 0x85, 0x40, 0x00, 0xa1,
1135
        0x55, 0x15, 0x55, 0x54, 0x85, 0x40, 0x00, 0xa1,
1129
        0x2a, 0xaa, 0xa8, 0x2a, 0xaa, 0xa8, 0x40, 0x00,
1136
        0x2a, 0xaa, 0xa8, 0x2a, 0xaa, 0xa8, 0x40, 0x00,
1130
        0xa1, 0x55, 0x54, 0x85, 0x55, 0x55, 0x15, 0x55,
1137
        0xa1, 0x55, 0x54, 0x85, 0x55, 0x55, 0x15, 0x55,
1131
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1138
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1132
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55};
1139
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55};
1133
 
1140
 
1134
    // arrow right-up
1141
    // arrow right-up
1135
    unsigned char cda[54] ={0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1142
    unsigned char cda[54] ={0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1136
        0x55, 0x55, 0x40, 0x01, 0x55, 0x2a, 0xa8, 0x55,
1143
        0x55, 0x55, 0x40, 0x01, 0x55, 0x2a, 0xa8, 0x55,
1137
        0x4a, 0xa8, 0x55, 0x52, 0xa8, 0x55, 0x4a, 0xa8,
1144
        0x4a, 0xa8, 0x55, 0x52, 0xa8, 0x55, 0x4a, 0xa8,
1138
        0x55, 0x2a, 0x28, 0x54, 0xa8, 0x48, 0x52, 0xa1,
1145
        0x55, 0x2a, 0x28, 0x54, 0xa8, 0x48, 0x52, 0xa1,
1139
        0x51, 0x4a, 0x85, 0x55, 0x52, 0x15, 0x55, 0x54,
1146
        0x51, 0x4a, 0x85, 0x55, 0x52, 0x15, 0x55, 0x54,
1140
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1147
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1141
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55};
1148
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55};
1142
 
1149
 
1143
    // arrow up
1150
    // arrow up
1144
    unsigned char cdb[54] ={0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1151
    unsigned char cdb[54] ={0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1145
        0x55, 0x55, 0x41, 0x55, 0x55, 0x28, 0x55, 0x54,
1152
        0x55, 0x55, 0x41, 0x55, 0x55, 0x28, 0x55, 0x54,
1146
        0xaa, 0x15, 0x52, 0xaa, 0x85, 0x54, 0x28, 0x15,
1153
        0xaa, 0x15, 0x52, 0xaa, 0x85, 0x54, 0x28, 0x15,
1147
        0x55, 0x28, 0x55, 0x55, 0x28, 0x55, 0x55, 0x28,
1154
        0x55, 0x28, 0x55, 0x55, 0x28, 0x55, 0x55, 0x28,
1148
        0x55, 0x55, 0x28, 0x55, 0x55, 0x28, 0x55, 0x55,
1155
        0x55, 0x55, 0x28, 0x55, 0x55, 0x28, 0x55, 0x55,
1149
        0x28, 0x55, 0x55, 0x41, 0x55, 0x55, 0x55, 0x55,
1156
        0x28, 0x55, 0x55, 0x41, 0x55, 0x55, 0x55, 0x55,
1150
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55};
1157
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55};
1151
 
1158
 
1152
    // arrow left-up
1159
    // arrow left-up
1153
    unsigned char cdc[54] ={0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1160
    unsigned char cdc[54] ={0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1154
        0x55, 0x40, 0x01, 0x55, 0x2a, 0xa8, 0x55, 0x2a,
1161
        0x55, 0x40, 0x01, 0x55, 0x2a, 0xa8, 0x55, 0x2a,
1155
        0xa1, 0x55, 0x2a, 0x85, 0x55, 0x2a, 0xa1, 0x55,
1162
        0xa1, 0x55, 0x2a, 0x85, 0x55, 0x2a, 0xa1, 0x55,
1156
        0x28, 0xa8, 0x55, 0x21, 0x2a, 0x15, 0x45, 0x4a,
1163
        0x28, 0xa8, 0x55, 0x21, 0x2a, 0x15, 0x45, 0x4a,
1157
        0x85, 0x55, 0x52, 0xa1, 0x55, 0x54, 0x85, 0x55,
1164
        0x85, 0x55, 0x52, 0xa1, 0x55, 0x54, 0x85, 0x55,
1158
        0x55, 0x15, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1165
        0x55, 0x15, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1159
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55};
1166
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55};
1160
 
1167
 
1161
    // arrow left
1168
    // arrow left
1162
    unsigned char cdd[54] ={0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1169
    unsigned char cdd[54] ={0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1163
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x54,
1170
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x54,
1164
        0x55, 0x55, 0x52, 0x15, 0x55, 0x4a, 0x00, 0x01,
1171
        0x55, 0x55, 0x52, 0x15, 0x55, 0x4a, 0x00, 0x01,
1165
        0x2a, 0xaa, 0xa8, 0x2a, 0xaa, 0xa8, 0x4a, 0x00,
1172
        0x2a, 0xaa, 0xa8, 0x2a, 0xaa, 0xa8, 0x4a, 0x00,
1166
        0x01, 0x52, 0x15, 0x55, 0x54, 0x55, 0x55, 0x55,
1173
        0x01, 0x52, 0x15, 0x55, 0x54, 0x55, 0x55, 0x55,
1167
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1174
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1168
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55};
1175
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55};
1169
 
1176
 
1170
    // arrow left-down
1177
    // arrow left-down
1171
    unsigned char cde[54] ={0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1178
    unsigned char cde[54] ={0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1172
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x15, 0x55,
1179
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x15, 0x55,
1173
        0x54, 0x85, 0x55, 0x52, 0xa1, 0x45, 0x4a, 0x85,
1180
        0x54, 0x85, 0x55, 0x52, 0xa1, 0x45, 0x4a, 0x85,
1174
        0x21, 0x2a, 0x15, 0x28, 0xa8, 0x55, 0x2a, 0xa1,
1181
        0x21, 0x2a, 0x15, 0x28, 0xa8, 0x55, 0x2a, 0xa1,
1175
        0x55, 0x2a, 0x85, 0x55, 0x2a, 0xa1, 0x55, 0x2a,
1182
        0x55, 0x2a, 0x85, 0x55, 0x2a, 0xa1, 0x55, 0x2a,
1176
        0xa8, 0x55, 0x40, 0x01, 0x55, 0x55, 0x55, 0x55,
1183
        0xa8, 0x55, 0x40, 0x01, 0x55, 0x55, 0x55, 0x55,
1177
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55};
1184
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55};
1178
 
1185
 
1179
    // arrow down
1186
    // arrow down
1180
    unsigned char cdf[54] ={0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1187
    unsigned char cdf[54] ={0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1181
        0x55, 0x55, 0x41, 0x55, 0x55, 0x28, 0x55, 0x55,
1188
        0x55, 0x55, 0x41, 0x55, 0x55, 0x28, 0x55, 0x55,
1182
        0x28, 0x55, 0x55, 0x28, 0x55, 0x55, 0x28, 0x55,
1189
        0x28, 0x55, 0x55, 0x28, 0x55, 0x55, 0x28, 0x55,
1183
        0x55, 0x28, 0x55, 0x55, 0x28, 0x55, 0x54, 0x28,
1190
        0x55, 0x28, 0x55, 0x55, 0x28, 0x55, 0x54, 0x28,
1184
        0x15, 0x52, 0xaa, 0x85, 0x54, 0xaa, 0x15, 0x55,
1191
        0x15, 0x52, 0xaa, 0x85, 0x54, 0xaa, 0x15, 0x55,
1185
        0x28, 0x55, 0x55, 0x41, 0x55, 0x55, 0x55, 0x55,
1192
        0x28, 0x55, 0x55, 0x41, 0x55, 0x55, 0x55, 0x55,
1186
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55};
1193
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55};
1187
 
1194
 
1188
    learn_char(216, cd8);
1195
    learn_char(216, cd8);
1189
        learn_char(217, cd9);
1196
        learn_char(217, cd9);
1190
    learn_char(218, cda);
1197
    learn_char(218, cda);
1191
    learn_char(219, cdb);
1198
    learn_char(219, cdb);
1192
    learn_char(220, cdc);
1199
    learn_char(220, cdc);
1193
    learn_char(221, cdd);
1200
    learn_char(221, cdd);
1194
    learn_char(222, cde);
1201
    learn_char(222, cde);
1195
    learn_char(223, cdf);
1202
    learn_char(223, cdf);
1196
#endif
1203
#endif
1197
#if WRITECHARS == 224
1204
#if WRITECHARS == 224
1198
     // arrow right-down
1205
     // arrow right-down
1199
    unsigned char ce0[54] ={0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1206
    unsigned char ce0[54] ={0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1200
        0x55, 0x55, 0x55, 0x55, 0x54, 0x55, 0x55, 0x52,
1207
        0x55, 0x55, 0x55, 0x55, 0x54, 0x55, 0x55, 0x52,
1201
        0x15, 0x55, 0x4a, 0x85, 0x55, 0x52, 0xa1, 0x51,
1208
        0x15, 0x55, 0x4a, 0x85, 0x55, 0x52, 0xa1, 0x51,
1202
        0x54, 0xa8, 0x48, 0x55, 0x2a, 0x28, 0x55, 0x4a,
1209
        0x54, 0xa8, 0x48, 0x55, 0x2a, 0x28, 0x55, 0x4a,
1203
        0xa8, 0x55, 0x52, 0xa8, 0x55, 0x4a, 0xa8, 0x55,
1210
        0xa8, 0x55, 0x52, 0xa8, 0x55, 0x4a, 0xa8, 0x55,
1204
        0x2a, 0xa8, 0x55, 0x40, 0x01, 0x55, 0x55, 0x55,
1211
        0x2a, 0xa8, 0x55, 0x40, 0x01, 0x55, 0x55, 0x55,
1205
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55};
1212
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55};
1206
 
1213
 
1207
        // horizon up
1214
        // horizon up
1208
    unsigned char ce1[54] ={0x55, 0x55, 0x55, 0x00, 0x00, 0x00, 0xaa, 0xaa,
1215
    unsigned char ce1[54] ={0x55, 0x55, 0x55, 0x00, 0x00, 0x00, 0xaa, 0xaa,
1209
        0xaa, 0xaa, 0xaa, 0xaa, 0x00, 0x00, 0x00, 0x55,
1216
        0xaa, 0xaa, 0xaa, 0xaa, 0x00, 0x00, 0x00, 0x55,
1210
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1217
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1211
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1218
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1212
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1219
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1213
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1220
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1214
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55};
1221
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55};
1215
 
1222
 
1216
        // horizon middle
1223
        // horizon middle
1217
    unsigned char ce2[54] ={0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1224
    unsigned char ce2[54] ={0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1218
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1225
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1219
        0x55, 0x55, 0x55, 0x55, 0x55, 0x00, 0x00, 0x00,
1226
        0x55, 0x55, 0x55, 0x55, 0x55, 0x00, 0x00, 0x00,
1220
        0xaa, 0xaa, 0xaa, 0xaa, 0xaa, 0xaa, 0x00, 0x00,
1227
        0xaa, 0xaa, 0xaa, 0xaa, 0xaa, 0xaa, 0x00, 0x00,
1221
        0x00, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1228
        0x00, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1222
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1229
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1223
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55};
1230
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55};
1224
 
1231
 
1225
        // horizon down
1232
        // horizon down
1226
    unsigned char ce3[54] ={0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1233
    unsigned char ce3[54] ={0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1227
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1234
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1228
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1235
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1229
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1236
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1230
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x00,
1237
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x00,
1231
        0x00, 0x00, 0xaa, 0xaa, 0xaa, 0xaa, 0xaa, 0xaa,
1238
        0x00, 0x00, 0xaa, 0xaa, 0xaa, 0xaa, 0xaa, 0xaa,
1232
        0x00, 0x00, 0x00, 0x55, 0x55, 0x55};
1239
        0x00, 0x00, 0x00, 0x55, 0x55, 0x55};
1233
 
1240
 
1234
        // horizon center
1241
        // horizon center
1235
    unsigned char ce4[54] ={0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1242
    unsigned char ce4[54] ={0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1236
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1243
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1237
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1244
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1238
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1245
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1239
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x00,
1246
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x00,
1240
        0x14, 0x00, 0xaa, 0x14, 0xaa, 0xaa, 0x82, 0xaa,
1247
        0x14, 0x00, 0xaa, 0x14, 0xaa, 0xaa, 0x82, 0xaa,
1241
        0x00, 0xaa, 0x00, 0x54, 0x00, 0x15};
1248
        0x00, 0xaa, 0x00, 0x54, 0x00, 0x15};
1242
 
1249
 
1243
        // horizon roll
1250
        // horizon roll
1244
    unsigned char ce5[54] ={0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1251
    unsigned char ce5[54] ={0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1245
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1252
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1246
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1253
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1247
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1254
        0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55,
1248
        0x55, 0x00, 0x55, 0x00, 0x2a, 0x14, 0xa8, 0x4a,
1255
        0x55, 0x00, 0x55, 0x00, 0x2a, 0x14, 0xa8, 0x4a,
1249
        0x82, 0xa1, 0x52, 0xaa, 0x85, 0x54, 0xaa, 0x15,
1256
        0x82, 0xa1, 0x52, 0xaa, 0x85, 0x54, 0xaa, 0x15,
1250
        0x55, 0x28, 0x55, 0x55, 0x41, 0x55};
1257
        0x55, 0x28, 0x55, 0x55, 0x41, 0x55};
1251
       
1258
       
1252
        // gps PH
1259
        // gps PH
1253
    unsigned char ce6[54] ={0x55, 0x05, 0x11, 0x54, 0xa0, 0x88, 0x54, 0x88,
1260
    unsigned char ce6[54] ={0x55, 0x05, 0x11, 0x54, 0xa0, 0x88, 0x54, 0x88,
1254
        0x88, 0x54, 0xa0, 0xa8, 0x54, 0x84, 0x88, 0x44,
1261
        0x88, 0x54, 0xa0, 0xa8, 0x54, 0x84, 0x88, 0x44,
1255
        0x84, 0x88, 0x21, 0x15, 0x11, 0xa8, 0x55, 0x55,
1262
        0x84, 0x88, 0x21, 0x15, 0x11, 0xa8, 0x55, 0x55,
1256
        0xa1, 0x55, 0x55, 0x98, 0x15, 0x55, 0x2a, 0x85,
1263
        0xa1, 0x55, 0x55, 0x98, 0x15, 0x55, 0x2a, 0x85,
1257
        0x55, 0x4a, 0xa1, 0x55, 0x4a, 0xa8, 0x55, 0x52,
1264
        0x55, 0x4a, 0xa1, 0x55, 0x4a, 0xa8, 0x55, 0x52,
1258
        0xaa, 0x15, 0x54, 0xaa, 0x15, 0x55, 0x28, 0x55,
1265
        0xaa, 0x15, 0x54, 0xaa, 0x15, 0x55, 0x28, 0x55,
1259
        0x55, 0x41, 0x55, 0x55, 0x55, 0x55};
1266
        0x55, 0x41, 0x55, 0x55, 0x55, 0x55};
1260
       
1267
       
1261
        // gps CH
1268
        // gps CH
1262
    unsigned char ce7[54] ={0x55, 0x55, 0x41, 0x55, 0x55, 0x28, 0x55, 0x54,
1269
    unsigned char ce7[54] ={0x55, 0x55, 0x41, 0x55, 0x55, 0x28, 0x55, 0x54,
1263
        0x81, 0x55, 0x54, 0x85, 0x55, 0x54, 0x81, 0x45,
1270
        0x81, 0x55, 0x54, 0x85, 0x55, 0x54, 0x81, 0x45,
1264
        0x55, 0x28, 0x21, 0x55, 0x01, 0xa8, 0x54, 0x88,
1271
        0x55, 0x28, 0x21, 0x55, 0x01, 0xa8, 0x54, 0x88,
1265
        0xa1, 0x54, 0x88, 0x98, 0x14, 0xa8, 0x2a, 0x84,
1272
        0xa1, 0x54, 0x88, 0x98, 0x14, 0xa8, 0x2a, 0x84,
1266
        0x88, 0x4a, 0xa0, 0x88, 0x4a, 0xa8, 0x11, 0x52,
1273
        0x88, 0x4a, 0xa0, 0x88, 0x4a, 0xa8, 0x11, 0x52,
1267
        0xaa, 0x15, 0x54, 0xaa, 0x15, 0x55, 0x28, 0x55,
1274
        0xaa, 0x15, 0x54, 0xaa, 0x15, 0x55, 0x28, 0x55,
1268
        0x55, 0x41, 0x55, 0x55, 0x55, 0x55};
1275
        0x55, 0x41, 0x55, 0x55, 0x55, 0x55};
1269
 
1276
 
1270
    learn_char(224, ce0);
1277
    learn_char(224, ce0);
1271
        learn_char(225, ce1);
1278
        learn_char(225, ce1);
1272
        learn_char(226, ce2);
1279
        learn_char(226, ce2);
1273
        learn_char(227, ce3);
1280
        learn_char(227, ce3);
1274
        learn_char(228, ce4);
1281
        learn_char(228, ce4);
1275
        learn_char(229, ce5);
1282
        learn_char(229, ce5);
1276
        learn_char(230, ce6);
1283
        learn_char(230, ce6);
1277
        learn_char(231, ce7);
1284
        learn_char(231, ce7);
1278
#endif
1285
#endif
1279
#endif // write char general
1286
#endif // write char general
1280
    /* ##########################################################################
1287
    /* ##########################################################################
1281
     * continue normal main
1288
     * continue normal main
1282
     * ##########################################################################*/
1289
     * ##########################################################################*/
1283
       
1290
       
1284
        // Setup Video Mode
1291
        // Setup Video Mode
1285
        if (COSD_FLAGS & COSD_FLAG_NTSC) {
1292
        if (COSD_FLAGS & COSD_FLAG_NTSC) {
1286
        // NTSC + enable display immediately (VM0)
1293
        // NTSC + enable display immediately (VM0)
1287
        spi_send_byte(0x00, 0b00001000);
1294
        spi_send_byte(0x00, 0b00001000);
1288
        } else {
1295
        } else {
1289
        // PAL + enable display immediately (VM0)
1296
        // PAL + enable display immediately (VM0)
1290
        spi_send_byte(0x00, 0b01001000);
1297
        spi_send_byte(0x00, 0b01001000);
1291
        }
1298
        }
1292
 
1299
 
1293
    // clear all display-mem (DMM)
1300
    // clear all display-mem (DMM)
1294
    spi_send_byte(0x04, 0b00000100);
1301
    spi_send_byte(0x04, 0b00000100);
1295
 
1302
 
1296
    // clearing takes 12uS according to maxim so lets wait longer
1303
    // clearing takes 12uS according to maxim so lets wait longer
1297
    _delay_us(120);
1304
    _delay_us(120);
1298
 
1305
 
1299
    // 8bit mode
1306
    // 8bit mode
1300
    spi_send_byte(0x04, 0b01000000);
1307
    spi_send_byte(0x04, 0b01000000);
1301
 
1308
 
1302
    // write blank chars to whole screen
1309
    // write blank chars to whole screen
1303
    clear();
1310
    clear();
1304
 
1311
 
1305
#if !(ALLCHARSDEBUG|WRITECHARS)
1312
#if !(ALLCHARSDEBUG|(WRITECHARS != -1))
1306
    // init usart
1313
    // init usart
1307
    usart1_init();
1314
    usart1_init();
1308
 
1315
 
1309
    // set up timer
1316
    // set up timer
1310
    TCCR0 |= (1 << CS00) | (1 << CS01); // timer0 prescaler 64
1317
    TCCR0 |= (1 << CS00) | (1 << CS01); // timer0 prescaler 64
1311
    OCR0 = 6; // preload
1318
    OCR0 = 6; // preload
1312
    TIMSK |= (1 << TOIE0); // enable overflow timer0
1319
    TIMSK |= (1 << TOIE0); // enable overflow timer0
1313
 
1320
 
1314
    // enable interrupts
1321
    // enable interrupts
1315
    sei();
1322
    sei();
1316
#endif
1323
#endif
1317
 
1324
 
1318
    //write_ascii_string(2,  7, "         CaScAdE          ");
1325
    //write_ascii_string(2,  7, "         CaScAdE          ");
1319
    //write_ascii_string(2,  8, "is TESTING his open source");
1326
    //write_ascii_string(2,  8, "is TESTING his open source");
1320
    //write_ascii_string(2,  9, "    EPi OSD Firmware");
1327
    //write_ascii_string(2,  9, "    EPi OSD Firmware");
1321
 
1328
 
1322
    // custom char preview
1329
    // custom char preview
1323
    /*write_char_xy( 2, 7, 200);
1330
    /*write_char_xy( 2, 7, 200);
1324
    write_char_xy( 3, 7, 201);
1331
    write_char_xy( 3, 7, 201);
1325
    write_char_xy( 4, 7, 202);
1332
    write_char_xy( 4, 7, 202);
1326
    write_char_xy( 5, 7, 203);
1333
    write_char_xy( 5, 7, 203);
1327
    write_char_xy( 6, 7, 204);
1334
    write_char_xy( 6, 7, 204);
1328
    write_char_xy( 7, 7, 205);
1335
    write_char_xy( 7, 7, 205);
1329
    write_char_xy( 8, 7, 206);
1336
    write_char_xy( 8, 7, 206);
1330
    write_char_xy( 9, 7, 207);
1337
    write_char_xy( 9, 7, 207);
1331
    write_char_xy(10, 7, 208);
1338
    write_char_xy(10, 7, 208);
1332
    write_char_xy(11, 7, 209);
1339
    write_char_xy(11, 7, 209);
1333
    write_char_xy(12, 7, 210);
1340
    write_char_xy(12, 7, 210);
1334
    write_char_xy(13, 7, 211);
1341
    write_char_xy(13, 7, 211);
1335
    write_char_xy(14, 7, 212);
1342
    write_char_xy(14, 7, 212);
1336
    write_char_xy(15, 7, 213);
1343
    write_char_xy(15, 7, 213);
1337
    write_char_xy(16, 7, 214);
1344
    write_char_xy(16, 7, 214);
1338
    write_char_xy(17, 7, 215);*/
1345
    write_char_xy(17, 7, 215);*/
1339
 
1346
 
1340
    // we are ready
1347
    // we are ready
1341
    LED3_ON
1348
    LED3_ON
1342
 
1349
 
1343
 
1350
 
1344
 
1351
 
1345
#if ALLCHARSDEBUG | WRITECHARS
1352
#if ALLCHARSDEBUG | (WRITECHARS != -1)
1346
        clear();
1353
        clear();
1347
    write_all_chars();
1354
    write_all_chars();
1348
#else
1355
#else
1349
    // clear serial screen
1356
    // clear serial screen
1350
    //usart1_puts("\x1B[2J\x1B[H");
1357
    //usart1_puts("\x1B[2J\x1B[H");
1351
    //usart1_puts("hello world!\r\n");
1358
    //usart1_puts("hello world!\r\n");
1352
 
1359
 
1353
   
1360
   
1354
    // request data ever 100ms from FC
1361
    // request data ever 100ms from FC
1355
        //unsigned char ms = 10;
1362
        //unsigned char ms = 10;
1356
        //sendMKData('d', 0, &ms, 1);
1363
        //sendMKData('d', 0, &ms, 1);
1357
     
1364
     
1358
    // request OSD Data from NC every 100ms
1365
    // request OSD Data from NC every 100ms
1359
        unsigned char ms = 10;
1366
        unsigned char ms = 10;
1360
    sendMKData('o', 1, &ms, 1);
1367
    sendMKData('o', 1, &ms, 1);
1361
        // and disable debug...
1368
        // and disable debug...
1362
        //ms = 0;
1369
        //ms = 0;
1363
        //sendMKData('d', 0, &ms, 1);
1370
        //sendMKData('d', 0, &ms, 1);
1364
 
1371
 
1365
        // stats for after flight
1372
        // stats for after flight
1366
        int16_t max_Altimeter = 0;
1373
        int16_t max_Altimeter = 0;
1367
        uint16_t max_GroundSpeed = 0;
1374
        uint16_t max_GroundSpeed = 0;
1368
        int16_t max_Distance = 0;
1375
        int16_t max_Distance = 0;
1369
        uint8_t min_UBat = 255;
1376
        uint8_t min_UBat = 255;
1370
        uint16_t max_FlyingTime = 0;
1377
        uint16_t max_FlyingTime = 0;
1371
 
1378
 
1372
        // flags from last round to check for changes
1379
        // flags from last round to check for changes
1373
        uint8_t old_MKFlags = 0;
1380
        uint8_t old_MKFlags = 0;
1374
       
1381
       
1375
    char* directions[8] = {"NE", "E ", "SE", "S ", "SW", "W ", "NW", "N "};
1382
    char* directions[8] = {"NE", "E ", "SE", "S ", "SW", "W ", "NW", "N "};
1376
        char arrowdir[8] =   { 218,  217,  224,  223,  222,  221,  220, 219};
1383
        char arrowdir[8] =   { 218,  217,  224,  223,  222,  221,  220, 219};
1377
 
1384
 
1378
    while (1) {
1385
    while (1) {
1379
                // write icons at init or after menu/mode-switch
1386
                // write icons at init or after menu/mode-switch
1380
                if (!(COSD_FLAGS & COSD_ICONS_WRITTEN)) {
1387
                if (!(COSD_FLAGS & COSD_ICONS_WRITTEN)) {
1381
                            write_char_xy(5, top_line, 203); // km/h
1388
                            write_char_xy(5, top_line, 203); // km/h
1382
                            write_char_xy(10, top_line, 202); // RC-transmitter
1389
                            write_char_xy(10, top_line, 202); // RC-transmitter
1383
                            write_char_xy(16, top_line, 208); // degree symbol
1390
                            write_char_xy(16, top_line, 208); // degree symbol
1384
                            write_char_xy(27, top_line, 204); // small meters m
1391
                            write_char_xy(27, top_line, 204); // small meters m
1385
                            write_ascii_string(6, bottom_line, "V"); // voltage
1392
                            write_ascii_string(6, bottom_line, "V"); // voltage
1386
                            write_char_xy(14, bottom_line, 209); // on clock
1393
                            write_char_xy(14, bottom_line, 209); // on clock
1387
                            write_char_xy(22, bottom_line, 210); // fly clock
1394
                            write_char_xy(22, bottom_line, 210); // fly clock
1388
                            write_char_xy(26, bottom_line, 200); // sat1
1395
                            write_char_xy(26, bottom_line, 200); // sat1
1389
                            write_char_xy(27, bottom_line, 201); // sat2
1396
                            write_char_xy(27, bottom_line, 201); // sat2
1390
                                COSD_FLAGS |= COSD_ICONS_WRITTEN;
1397
                                COSD_FLAGS |= COSD_ICONS_WRITTEN;
1391
                }
1398
                }
1392
        if (rxd_buffer_locked) {
1399
        if (rxd_buffer_locked) {
1393
            if (rxd_buffer[2] == 'D') { // FC Data
1400
            if (rxd_buffer[2] == 'D') { // FC Data
1394
                /*Decode64();
1401
                /*Decode64();
1395
                debugData = *((DebugOut_t*) pRxData);
1402
                debugData = *((DebugOut_t*) pRxData);
1396
                write_number_s(12, 2, RxDataLen);
1403
                write_number_s(12, 2, RxDataLen);
1397
                write_number_s(20, 2, setsReceived++);
1404
                write_number_s(20, 2, setsReceived++);
1398
                write_number_s(12, 3, debugData.Analog[0]);
1405
                write_number_s(12, 3, debugData.Analog[0]);
1399
                write_number_s(12, 4, debugData.Analog[2]);
1406
                write_number_s(12, 4, debugData.Analog[2]);
1400
                write_number_s(12, 5, debugData.Analog[1]);
1407
                write_number_s(12, 5, debugData.Analog[1]);
1401
                write_number_s(12, 6, debugData.Analog[3]);
1408
                write_number_s(12, 6, debugData.Analog[3]);
1402
                write_number_s(12, 7, debugData.Analog[9]);
1409
                write_number_s(12, 7, debugData.Analog[9]);
1403
                write_number_s(12, 8, debugData.Analog[10]);
1410
                write_number_s(12, 8, debugData.Analog[10]);
1404
                                write_number_s(12, 4, debugData.Analog[12]);
1411
                                write_number_s(12, 4, debugData.Analog[12]);
1405
                                write_number_s(12, 5, debugData.Analog[13]);
1412
                                write_number_s(12, 5, debugData.Analog[13]);
1406
                                write_number_s(12, 6, debugData.Analog[14]);
1413
                                write_number_s(12, 6, debugData.Analog[14]);
1407
                                write_number_s(12, 7, debugData.Analog[15]);*/
1414
                                write_number_s(12, 7, debugData.Analog[15]);*/
1408
            } else if (rxd_buffer[2] == 'O') { // NC OSD Data
1415
            } else if (rxd_buffer[2] == 'O') { // NC OSD Data
1409
                Decode64();
1416
                Decode64();
1410
                naviData = *((NaviData_t*) pRxData);
1417
                naviData = *((NaviData_t*) pRxData);
1411
 
1418
 
1412
                                // first line
1419
                                // first line
1413
                                write_3digit_number_u(2, top_line, (uint16_t)(((uint32_t)naviData.GroundSpeed*36)/1000));
1420
                                write_3digit_number_u(2, top_line, (uint16_t)(((uint32_t)naviData.GroundSpeed*36)/1000));
1414
 
1421
 
1415
                write_3digit_number_u(7, top_line, naviData.RC_Quality);
1422
                write_3digit_number_u(7, top_line, naviData.RC_Quality);
1416
                if (naviData.RC_Quality <= RCLVL_WRN && last_RC_Quality > RCLVL_WRN) {
1423
                if (naviData.RC_Quality <= RCLVL_WRN && last_RC_Quality > RCLVL_WRN) {
1417
                    for (uint8_t x = 0; x < 4; x++)
1424
                    for (uint8_t x = 0; x < 4; x++)
1418
                        write_char_att_xy(7 + x, top_line, BLINK);
1425
                        write_char_att_xy(7 + x, top_line, BLINK);
1419
                } else if (naviData.RC_Quality > RCLVL_WRN && last_RC_Quality <= RCLVL_WRN) {
1426
                } else if (naviData.RC_Quality > RCLVL_WRN && last_RC_Quality <= RCLVL_WRN) {
1420
                    for (uint8_t x = 0; x < 4; x++)
1427
                    for (uint8_t x = 0; x < 4; x++)
1421
                        write_char_att_xy(7 + x, top_line, 0);
1428
                        write_char_att_xy(7 + x, top_line, 0);
1422
                }
1429
                }
1423
                last_RC_Quality = naviData.RC_Quality;
1430
                last_RC_Quality = naviData.RC_Quality;
1424
 
1431
 
1425
                write_3digit_number_u(13, top_line, naviData.CompassHeading);
1432
                write_3digit_number_u(13, top_line, naviData.CompassHeading);
1426
 
1433
 
1427
                write_ascii_string(17, top_line, directions[heading_conv(naviData.CompassHeading)]);
1434
                write_ascii_string(17, top_line, directions[heading_conv(naviData.CompassHeading)]);
1428
 
1435
 
1429
                if (naviData.Variometer == 0) {
1436
                if (naviData.Variometer == 0) {
1430
                    write_char_xy(20, top_line, 206); // plain line
1437
                    write_char_xy(20, top_line, 206); // plain line
1431
                } else if (naviData.Variometer > 0) {
1438
                } else if (naviData.Variometer > 0) {
1432
                    write_char_xy(20, top_line, 207); // arrow up
1439
                    write_char_xy(20, top_line, 207); // arrow up
1433
                } else {
1440
                } else {
1434
                    write_char_xy(20, top_line, 205); // arrow down
1441
                    write_char_xy(20, top_line, 205); // arrow down
1435
                }
1442
                }
1436
 
1443
 
1437
                                // TODO: is this really dm?
1444
                                // TODO: is this really dm?
1438
                write_number_s(22, top_line, naviData.Altimeter/10);
1445
                write_number_s(22, top_line, naviData.Altimeter/10);
1439
 
1446
 
1440
                                // seccond line
1447
                                // seccond line
1441
                draw_compass(11, top_line + 1, naviData.CompassHeading);
1448
                draw_compass(11, top_line + 1, naviData.CompassHeading);
1442
 
1449
 
1443
                                // TODO: verify correctness
1450
                                // TODO: verify correctness
1444
                                uint16_t heading_home = (naviData.HomePositionDeviation.Bearing + 360 - naviData.CompassHeading) % 360;
1451
                                uint16_t heading_home = (naviData.HomePositionDeviation.Bearing + 360 - naviData.CompassHeading) % 360;
1445
                                write_char_xy(27, top_line + 1, arrowdir[heading_conv(heading_home)]);
1452
                                write_char_xy(27, top_line + 1, arrowdir[heading_conv(heading_home)]);
1446
 
1453
 
1447
       
1454
       
1448
                                write_number_s(22, top_line + 1, naviData.HomePositionDeviation.Distance/100);
1455
                                write_number_s(22, top_line + 1, naviData.HomePositionDeviation.Distance/100);
1449
 
1456
 
1450
                                // center
1457
                                // center
1451
                                if (naviData.MKFlags & FLAG_MOTOR_RUN) { // should be engines running
1458
                                if (naviData.MKFlags & FLAG_MOTOR_RUN) { // should be engines running
1452
                                        if (!(old_MKFlags & FLAG_MOTOR_RUN)) { // motors just started, clear middle
1459
                                        if (!(old_MKFlags & FLAG_MOTOR_RUN)) { // motors just started, clear middle
1453
                                                clear();
1460
                                                clear();
1454
                                                // update flags to paint display again if needed
1461
                                                // update flags to paint display again if needed
1455
                                                COSD_FLAGS &= ~COSD_ICONS_WRITTEN;
1462
                                                COSD_FLAGS &= ~COSD_ICONS_WRITTEN;
1456
                                        }
1463
                                        }
1457
                                if (COSD_FLAGS & COSD_FLAG_ARTHORIZON) {
1464
                                if (COSD_FLAGS & COSD_FLAG_ARTHORIZON) {
1458
                                        draw_artificial_horizon(top_line + 2, bottom_line - 1, naviData.AngleNick, naviData.AngleRoll);
1465
                                        draw_artificial_horizon(top_line + 2, bottom_line - 1, naviData.AngleNick, naviData.AngleRoll);
1459
                                }
1466
                                }
1460
                                } else {
1467
                                } else {
1461
                                        // stats
1468
                                        // stats
1462
                                        write_ascii_string(2, 5, "max Altitude:");
1469
                                        write_ascii_string(2, 5, "max Altitude:");
1463
                                        write_number_s(17, 5, max_Altimeter/10);
1470
                                        write_number_s(17, 5, max_Altimeter/10);
1464
                                        write_char_xy(22, 5, 204); // small meters m
1471
                                        write_char_xy(22, 5, 204); // small meters m
1465
                                        write_ascii_string(2, 6, "max Speed   :");
1472
                                        write_ascii_string(2, 6, "max Speed   :");
1466
                                        write_3digit_number_u(19, 6, (uint16_t)(((uint32_t)max_GroundSpeed*36)/1000));
1473
                                        write_3digit_number_u(19, 6, (uint16_t)(((uint32_t)max_GroundSpeed*36)/1000));
1467
                                        write_char_xy(22, 6, 203); // km/h
1474
                                        write_char_xy(22, 6, 203); // km/h
1468
                                        write_ascii_string(2, 7, "max Distance:");
1475
                                        write_ascii_string(2, 7, "max Distance:");
1469
                                        write_number_s(17, 7, max_Distance/100);
1476
                                        write_number_s(17, 7, max_Distance/100);
1470
                                        write_char_xy(22, 7, 204); // small meters m
1477
                                        write_char_xy(22, 7, 204); // small meters m
1471
                                        write_ascii_string(2, 8, "min voltage :");
1478
                                        write_ascii_string(2, 8, "min voltage :");
1472
                                        //write_number_s(17, 8, min_UBat/10);
1479
                                        //write_number_s(17, 8, min_UBat/10);
1473
                                        write_number_u_10th(16, 8, min_UBat);
1480
                                        write_number_u_10th(16, 8, min_UBat);
1474
                                        write_ascii_string(22, 8, "V"); // voltage
1481
                                        write_ascii_string(22, 8, "V"); // voltage
1475
                                        write_ascii_string(2, 9, "max time    :");
1482
                                        write_ascii_string(2, 9, "max time    :");
1476
                                        write_time(16, 9, max_FlyingTime);
1483
                                        write_time(16, 9, max_FlyingTime);
1477
                                        write_char_xy(22, 9, 210); // fly clock
1484
                                        write_char_xy(22, 9, 210); // fly clock
1478
                                }
1485
                                }
1479
 
1486
 
1480
                                // bottom line
1487
                                // bottom line
1481
                write_number_u_10th(0, bottom_line, naviData.UBat);
1488
                write_number_u_10th(0, bottom_line, naviData.UBat);
1482
                if (naviData.UBat <= UBAT_WRN && last_UBat > UBAT_WRN) {
1489
                if (naviData.UBat <= UBAT_WRN && last_UBat > UBAT_WRN) {
1483
                    for (uint8_t x = 0; x < 7; x++)
1490
                    for (uint8_t x = 0; x < 7; x++)
1484
                        write_char_att_xy(x, bottom_line, BLINK);
1491
                        write_char_att_xy(x, bottom_line, BLINK);
1485
                } else {
1492
                } else {
1486
                    for (uint8_t x = 0; x < 7; x++)
1493
                    for (uint8_t x = 0; x < 7; x++)
1487
                        write_char_att_xy(x, bottom_line, 0);
1494
                        write_char_att_xy(x, bottom_line, 0);
1488
                }
1495
                }
1489
 
1496
 
1490
                write_time(8, bottom_line, uptime);
1497
                write_time(8, bottom_line, uptime);
1491
                write_time(16, bottom_line, naviData.FlyingTime);
1498
                write_time(16, bottom_line, naviData.FlyingTime);
1492
 
1499
 
1493
                write_3digit_number_u(23, bottom_line, naviData.SatsInUse);
1500
                write_3digit_number_u(23, bottom_line, naviData.SatsInUse);
1494
 
1501
 
1495
                                if (naviData.NCFlags & NC_FLAG_CH) {
1502
                                if (naviData.NCFlags & NC_FLAG_CH) {
1496
                                        write_char_xy(27, bottom_line, 231);    // gps ch
1503
                                        write_char_xy(27, bottom_line, 231);    // gps ch
1497
                                } else if (naviData.NCFlags & NC_FLAG_PH) {
1504
                                } else if (naviData.NCFlags & NC_FLAG_PH) {
1498
                                        write_char_xy(27, bottom_line, 230);    // gps ph
1505
                                        write_char_xy(27, bottom_line, 230);    // gps ph
1499
                                } else { // (naviData.NCFlags & NC_FLAG_FREE)
1506
                                } else { // (naviData.NCFlags & NC_FLAG_FREE)
1500
                                        write_char_xy(27, bottom_line, 201);    // sat2 (free)
1507
                                        write_char_xy(27, bottom_line, 201);    // sat2 (free)
1501
                                }
1508
                                }
1502
 
1509
 
1503
                //write_number_s(8, 5, RxDataLen);
1510
                //write_number_s(8, 5, RxDataLen);
1504
                //write_number_s(16, 5, setsReceived++);
1511
                //write_number_s(16, 5, setsReceived++);
1505
 
1512
 
1506
                                // remember statistics
1513
                                // remember statistics
1507
                                if (naviData.Altimeter > max_Altimeter) max_Altimeter = naviData.Altimeter;
1514
                                if (naviData.Altimeter > max_Altimeter) max_Altimeter = naviData.Altimeter;
1508
                                if (naviData.GroundSpeed > max_GroundSpeed) max_GroundSpeed = naviData.GroundSpeed;
1515
                                if (naviData.GroundSpeed > max_GroundSpeed) max_GroundSpeed = naviData.GroundSpeed;
1509
                                if (naviData.HomePositionDeviation.Distance > max_Distance) {
1516
                                if (naviData.HomePositionDeviation.Distance > max_Distance) {
1510
                                        max_Distance = naviData.HomePositionDeviation.Distance;
1517
                                        max_Distance = naviData.HomePositionDeviation.Distance;
1511
                                }
1518
                                }
1512
                                if (naviData.UBat < min_UBat) min_UBat = naviData.UBat;
1519
                                if (naviData.UBat < min_UBat) min_UBat = naviData.UBat;
1513
                                if (naviData.FlyingTime > max_FlyingTime) max_FlyingTime = naviData.FlyingTime;
1520
                                if (naviData.FlyingTime > max_FlyingTime) max_FlyingTime = naviData.FlyingTime;
1514
                               
1521
                               
1515
                                old_MKFlags = naviData.MKFlags;
1522
                                old_MKFlags = naviData.MKFlags;
1516
            }
1523
            }
1517
            rxd_buffer_locked = 0;
1524
            rxd_buffer_locked = 0;
1518
        }
1525
        }
1519
        // handle keypress
1526
        // handle keypress
1520
        if (s1_pressed()) {
1527
        if (s1_pressed()) {
1521
                        //sendMKData('d', 1, (unsigned char*) 0, 1);
1528
                        //sendMKData('d', 1, (unsigned char*) 0, 1);
1522
            // request OSD Data from NC every 100ms
1529
            // request OSD Data from NC every 100ms
1523
                        /*unsigned char ms = 10;
1530
                        /*unsigned char ms = 10;
1524
            sendMKData('o', 1, &ms, 1);
1531
            sendMKData('o', 1, &ms, 1);
1525
            _delay_ms(500);*/
1532
            _delay_ms(500);*/
1526
                        config_menu();
1533
                        config_menu();
1527
        }
1534
        }
1528
                if (s2_pressed()) {
1535
                if (s2_pressed()) {
1529
            uptime = 0;
1536
            uptime = 0;
1530
            _delay_ms(100);
1537
            _delay_ms(100);
1531
        }
1538
        }
1532
    }
1539
    }
1533
#endif
1540
#endif
1534
    return 0;
1541
    return 0;
1535
}
1542
}
1536
 
1543