]> git.defcon.no Git - rctxduino/blob - source/RCTXDuino/RCTXDuino.pde
Needed to use the code to get the binary code in the hex :P Optimization ftw :P
[rctxduino] / source / RCTXDuino / RCTXDuino.pde
1 #include <LiquidCrystal.h>
2 #include <TimerOne.h>
3 #include <EEPROM.h>
4
5 // Undefine this whenever a "release" or "flight-test" build is made.
6 // Defining DEBUG sets some crazy values for things like battery warning,
7 // and includes a whole bunch of debugging-related code ...
8 #define DEBUG 1
9
10 #define MAX_INPUTS 8
11
12 // Update this _every_ time a change in datastructures that
13 // can/will ber written to EEPROM is done. EEPROM data is
14 // read/written torectly into/from the data structures using
15 // pointers, so every time a data-set change occurs, the EEPROM
16 // format changes as well..
17 #define EEPROM_VERSION 7
18
19 // Some data is stored in fixed locations, e.g.:
20 // * The EEPROM version number for the stored data (loc 0)
21 // * The selected model configuration number (loc 1)
22 // * (add any other fixed-loc's here for doc-purpose)
23 // This means that any pointer-math-operations need a BASE
24 // adress to start calc'ing from. This is defined as:
25 #define EE_BASE_ADDR 10
26
27 // Having to repeat tedious base-address-calculations for the
28 // start of model data should be unnessecary. Plus, updating
29 // what data is stored before the models will mean that each
30 // of those calculations must be updated. A better approach is
31 // to define the calculation in a define!
32 // NOTE: If new data is added in front of the model data,
33 // this define must be updated!
34 #define EE_MDL_BASE_ADDR (EE_BASE_ADDR+(sizeof(input_cal_t)+ 10))
35
36 // Just as a safety-precaution, update/change this if a chip with
37 // a different internal EEPROM size is used. Atmega328p has 1024 bytes.
38 #define INT_EEPROM_SIZE 1024
39
40 #define MAX_MODELS 4 // Nice and random number..
41
42
43 // --------------- ADC related stuffs.... --------------------
44
45 struct input_cal_t // Struct type for input calibration values
46 {
47 int min[MAX_INPUTS];
48 int max[MAX_INPUTS];
49 int center[MAX_INPUTS];
50 } ;
51 input_cal_t input_cal;
52
53 struct model_t
54 {
55 int channels; // How many channels should PPM generate for this model ...
56 float stick[8]; // The (potentially recalc'ed) value of stick/input channel.
57 int raw[8];
58 boolean rev[8];
59 int dr[8]; // The Dual-rate array uses magic numbers :P
60 /* dr[0] = Input channel #1 of 2 for D/R switch #1. 0 means off, 1-4 valid values.
61 dr[1] = Input channel #2 of 2 for D/R switch #1. 0 means off, 1-4 valid values.
62 dr[2] = Input channel #1 of 2 for D/R switch #2. 0 means off, 1-4 valid values.
63 dr[3] = Input channel #2 of 2 for D/R switch #2. 0 means off, 1-4 valid values.
64 dr[4] = D/R value for switch # 1 LOW(off). Value -100 to 100 in steps of 5.
65 dr[5] = D/R value for switch # 1 HIGH(on). Value -100 to 100 in steps of 5.
66 dr[6] = D/R value for switch # 1 LOW(off). Value -100 to 100 in steps of 5.
67 dr[7] = D/R value for switch # 1 HIGH(on). Value -100 to 100 in steps of 5.
68 */
69 };
70 volatile model_t model;
71 unsigned char current_model; // Using uchar to spend a single byte of mem..
72
73 // ----------------- Display related stuffs --------------------
74 LiquidCrystal lcd( 12, 11, 10, 6, 7, 8, 9);
75 // Parameters are: rs, rw, enable, d4, d5, d6, d7 pin numbers.
76
77 // ----------------- PPM related stuffs ------------------------
78 // The PPM generation is handled by Timer0 interrupts, and needs
79 // all modifiable variables to be global and volatile...
80
81 volatile long sum = 0; // Frame-time spent so far
82 volatile int cchannel = 0; // Current channnel
83 volatile bool do_channel = true; // Is next operation a channel or a separator
84
85
86 // All time values in usecs
87 // TODO:
88 // The timing here (and/or in the ISR) needs to be tweaked to provide valid
89 // RC PPM signals accepted by standard RC RX'es and the Microcopter...
90
91 #define framelength 21000 // Max length of frame
92 #define seplength 300 // Lenght of a channel separator
93 #define chmax 1600 // Max lenght of channel pulse
94 #define chmin 495 // Min length of channel
95 #define chwidht (chmax - chmin)// Useable time of channel pulse
96
97 // ----------------- Menu/IU related stuffs --------------------
98
99 // Keys/buttons/switches for UI use, including dual-rate/expo
100 // are digital inputs connected to a 4051 multiplexer, giving
101 // 8 inputs on a single input pin.
102 #define KEY_UP 0
103 #define KEY_DOWN 1
104 #define KEY_RIGHT 2
105 #define KEY_LEFT 3
106 #define KEY_INC 4
107 #define KEY_DEC 5
108 #define KEY_DR1 6
109 #define KEY_DR2 7
110
111 // Voltage sense pin is connected to a 1/3'd voltage divider.
112 #define BATTERY_CONV (10 * 3 * (5.0f/1024.0f))
113
114 #ifdef DEBUG
115 // The following values are for DEBUGGING ONLY!!
116 #define BATTERY_LOW 92
117 #define BATTERY_CRITICAL 0
118 #else
119 #define BATTERY_LOW 92
120 #define BATTERY_CRITICAL 92
121 #endif
122
123 enum {
124 VALUES,
125 BATTERY,
126 TIMER,
127 CURMODEL,
128 MENU
129 }
130 displaystate;
131
132 enum {
133 TOP,
134 INVERTS,
135 DUALRATES,
136 EXPOS, // Some radios have "drawn curves", i.e. loopup tables stored in external EEPROM ...
137 DEBUG_DUMP,
138 SAVE
139 }
140 menu_mainstate;
141 int menu_substate;
142
143 boolean keys[8];
144 boolean prev_keys[8];
145
146 int battery_val;
147
148 // The display/UI is handled only when more
149 // than UI_INTERVAL milliecs has passed since last...
150 #define UI_INTERVAL 250
151 unsigned long last = 0;
152
153 struct clock_timer_t
154 {
155 unsigned long start;
156 unsigned long init;
157 unsigned long value;
158 boolean running;
159 } clock_timer;
160
161 #ifdef DEBUG
162 // ----------------- DEBUG-STUFF --------------------
163 unsigned long prev_loop_time;
164 unsigned long avg_loop_time;
165 unsigned long t;
166 #endif
167 // -----------------------LCD--------------------------
168
169
170 #define PIN_SCE 7 //Pin 3 on LCD
171 #define PIN_RESET 6 //Pin 4 on LCD
172 #define PIN_DC 5 //Pin 5 on LCD
173 #define PIN_SDIN 4 //Pin 6 on LCD
174 #define PIN_SCLK 3 //Pin 7 on LCD
175
176 //The DC pin tells the LCD if we are sending a command or data
177 #define LCD_COMMAND 0
178 #define LCD_DATA 1
179
180 //You may find a different size screen, but this one is 84 by 48 pixels
181 #define LCD_X 84
182 #define LCD_Y 48
183
184 //This table contains the hex values that represent pixels
185 //for a font that is 5 pixels wide and 8 pixels high
186 static const byte ASCII[][5] = {
187 {0x00, 0x00, 0x00, 0x00, 0x00} // 20
188 ,{0x00, 0x00, 0x5f, 0x00, 0x00} // 21 !
189 ,{0x00, 0x07, 0x00, 0x07, 0x00} // 22 "
190 ,{0x14, 0x7f, 0x14, 0x7f, 0x14} // 23 #
191 ,{0x24, 0x2a, 0x7f, 0x2a, 0x12} // 24 $
192 ,{0x23, 0x13, 0x08, 0x64, 0x62} // 25 %
193 ,{0x36, 0x49, 0x55, 0x22, 0x50} // 26 &
194 ,{0x00, 0x05, 0x03, 0x00, 0x00} // 27 '
195 ,{0x00, 0x1c, 0x22, 0x41, 0x00} // 28 (
196 ,{0x00, 0x41, 0x22, 0x1c, 0x00} // 29 )
197 ,{0x14, 0x08, 0x3e, 0x08, 0x14} // 2a *
198 ,{0x08, 0x08, 0x3e, 0x08, 0x08} // 2b +
199 ,{0x00, 0x50, 0x30, 0x00, 0x00} // 2c ,
200 ,{0x08, 0x08, 0x08, 0x08, 0x08} // 2d -
201 ,{0x00, 0x60, 0x60, 0x00, 0x00} // 2e .
202 ,{0x20, 0x10, 0x08, 0x04, 0x02} // 2f /
203 ,{0x3e, 0x51, 0x49, 0x45, 0x3e} // 30 0
204 ,{0x00, 0x42, 0x7f, 0x40, 0x00} // 31 1
205 ,{0x42, 0x61, 0x51, 0x49, 0x46} // 32 2
206 ,{0x21, 0x41, 0x45, 0x4b, 0x31} // 33 3
207 ,{0x18, 0x14, 0x12, 0x7f, 0x10} // 34 4
208 ,{0x27, 0x45, 0x45, 0x45, 0x39} // 35 5
209 ,{0x3c, 0x4a, 0x49, 0x49, 0x30} // 36 6
210 ,{0x01, 0x71, 0x09, 0x05, 0x03} // 37 7
211 ,{0x36, 0x49, 0x49, 0x49, 0x36} // 38 8
212 ,{0x06, 0x49, 0x49, 0x29, 0x1e} // 39 9
213 ,{0x00, 0x36, 0x36, 0x00, 0x00} // 3a :
214 ,{0x00, 0x56, 0x36, 0x00, 0x00} // 3b ;
215 ,{0x08, 0x14, 0x22, 0x41, 0x00} // 3c <
216 ,{0x14, 0x14, 0x14, 0x14, 0x14} // 3d =
217 ,{0x00, 0x41, 0x22, 0x14, 0x08} // 3e >
218 ,{0x02, 0x01, 0x51, 0x09, 0x06} // 3f ?
219 ,{0x32, 0x49, 0x79, 0x41, 0x3e} // 40 @
220 ,{0x7e, 0x11, 0x11, 0x11, 0x7e} // 41 A
221 ,{0x7f, 0x49, 0x49, 0x49, 0x36} // 42 B
222 ,{0x3e, 0x41, 0x41, 0x41, 0x22} // 43 C
223 ,{0x7f, 0x41, 0x41, 0x22, 0x1c} // 44 D
224 ,{0x7f, 0x49, 0x49, 0x49, 0x41} // 45 E
225 ,{0x7f, 0x09, 0x09, 0x09, 0x01} // 46 F
226 ,{0x3e, 0x41, 0x49, 0x49, 0x7a} // 47 G
227 ,{0x7f, 0x08, 0x08, 0x08, 0x7f} // 48 H
228 ,{0x00, 0x41, 0x7f, 0x41, 0x00} // 49 I
229 ,{0x20, 0x40, 0x41, 0x3f, 0x01} // 4a J
230 ,{0x7f, 0x08, 0x14, 0x22, 0x41} // 4b K
231 ,{0x7f, 0x40, 0x40, 0x40, 0x40} // 4c L
232 ,{0x7f, 0x02, 0x0c, 0x02, 0x7f} // 4d M
233 ,{0x7f, 0x04, 0x08, 0x10, 0x7f} // 4e N
234 ,{0x3e, 0x41, 0x41, 0x41, 0x3e} // 4f O
235 ,{0x7f, 0x09, 0x09, 0x09, 0x06} // 50 P
236 ,{0x3e, 0x41, 0x51, 0x21, 0x5e} // 51 Q
237 ,{0x7f, 0x09, 0x19, 0x29, 0x46} // 52 R
238 ,{0x46, 0x49, 0x49, 0x49, 0x31} // 53 S
239 ,{0x01, 0x01, 0x7f, 0x01, 0x01} // 54 T
240 ,{0x3f, 0x40, 0x40, 0x40, 0x3f} // 55 U
241 ,{0x1f, 0x20, 0x40, 0x20, 0x1f} // 56 V
242 ,{0x3f, 0x40, 0x38, 0x40, 0x3f} // 57 W
243 ,{0x63, 0x14, 0x08, 0x14, 0x63} // 58 X
244 ,{0x07, 0x08, 0x70, 0x08, 0x07} // 59 Y
245 ,{0x61, 0x51, 0x49, 0x45, 0x43} // 5a Z
246 ,{0x00, 0x7f, 0x41, 0x41, 0x00} // 5b [
247 ,{0x02, 0x04, 0x08, 0x10, 0x20} // 5c \
248 ,{0x00, 0x41, 0x41, 0x7f, 0x00} // 5d ]
249 ,{0x04, 0x02, 0x01, 0x02, 0x04} // 5e ^
250 ,{0x40, 0x40, 0x40, 0x40, 0x40} // 5f _
251 ,{0x00, 0x01, 0x02, 0x04, 0x00} // 60 `
252 ,{0x20, 0x54, 0x54, 0x54, 0x78} // 61 a
253 ,{0x7f, 0x48, 0x44, 0x44, 0x38} // 62 b
254 ,{0x38, 0x44, 0x44, 0x44, 0x20} // 63 c
255 ,{0x38, 0x44, 0x44, 0x48, 0x7f} // 64 d
256 ,{0x38, 0x54, 0x54, 0x54, 0x18} // 65 e
257 ,{0x08, 0x7e, 0x09, 0x01, 0x02} // 66 f
258 ,{0x0c, 0x52, 0x52, 0x52, 0x3e} // 67 g
259 ,{0x7f, 0x08, 0x04, 0x04, 0x78} // 68 h
260 ,{0x00, 0x44, 0x7d, 0x40, 0x00} // 69 i
261 ,{0x20, 0x40, 0x44, 0x3d, 0x00} // 6a j
262 ,{0x7f, 0x10, 0x28, 0x44, 0x00} // 6b k
263 ,{0x00, 0x41, 0x7f, 0x40, 0x00} // 6c l
264 ,{0x7c, 0x04, 0x18, 0x04, 0x78} // 6d m
265 ,{0x7c, 0x08, 0x04, 0x04, 0x78} // 6e n
266 ,{0x38, 0x44, 0x44, 0x44, 0x38} // 6f o
267 ,{0x7c, 0x14, 0x14, 0x14, 0x08} // 70 p
268 ,{0x08, 0x14, 0x14, 0x18, 0x7c} // 71 q
269 ,{0x7c, 0x08, 0x04, 0x04, 0x08} // 72 r
270 ,{0x48, 0x54, 0x54, 0x54, 0x20} // 73 s
271 ,{0x04, 0x3f, 0x44, 0x40, 0x20} // 74 t
272 ,{0x3c, 0x40, 0x40, 0x20, 0x7c} // 75 u
273 ,{0x1c, 0x20, 0x40, 0x20, 0x1c} // 76 v
274 ,{0x3c, 0x40, 0x30, 0x40, 0x3c} // 77 w
275 ,{0x44, 0x28, 0x10, 0x28, 0x44} // 78 x
276 ,{0x0c, 0x50, 0x50, 0x50, 0x3c} // 79 y
277 ,{0x44, 0x64, 0x54, 0x4c, 0x44} // 7a z
278 ,{0x00, 0x08, 0x36, 0x41, 0x00} // 7b {
279 ,{0x00, 0x00, 0x7f, 0x00, 0x00} // 7c |
280 ,{0x00, 0x41, 0x36, 0x08, 0x00} // 7d }
281 ,{0x10, 0x08, 0x08, 0x10, 0x08} // 7e ~
282 ,{0x78, 0x46, 0x41, 0x46, 0x78} // 7f DEL
283 };
284
285
286
287
288
289
290
291
292 // ---------- CODE! -----------------------------------
293
294 // ---------- Arduino SETUP code ----------------------
295 void setup(){
296 pinMode(13, OUTPUT); // led
297
298 pinMode(2, OUTPUT); // s0
299 pinMode(3, OUTPUT); // s1
300 pinMode(4, OUTPUT); // s2
301 pinMode(5, OUTPUT); // e
302
303 lcd.begin(16,2);
304 lcd.print("Starting....");
305
306 Serial.begin(9600);
307 Serial.println("Starting....");
308 delay(500);
309
310 model_defaults();
311 read_settings();
312
313 displaystate = VALUES;
314
315 // Arduino believes all pins on Port C are Analog.
316 // In reality they are tri-purpose; ADC, Digital, Digital Interrupts
317 // Unfortunately the interrupt mode is unusable in this scenario, but digital I/O works :P
318 pinMode(A2, INPUT);
319 digitalWrite(A2, HIGH);
320 scan_keys();
321 if ( !keys[KEY_UP])
322 calibrate();
323
324 #ifdef DEBUG
325 // Debugging: how long does the main loop take on avg...
326 t = micros();
327 avg_loop_time = t;
328 prev_loop_time = t;
329 #endif
330
331 // Initializing the stopwatch timer/clock values...
332 clock_timer = (clock_timer_t){0, 0, 0, false};
333
334 pinMode(A5, OUTPUT); // PPM output pin
335 do_channel = false;
336 set_timer( seplength );
337 Timer1.initialize(framelength);
338 Timer1.attachInterrupt(ISR_timer);
339
340 // For size-testing :D
341 LCDInit();
342 LCDClear();
343 LCDString("Hello world!");
344 }
345
346 void model_defaults( void )
347 {
348 // This function provides default values for model data
349 // that is not a result of stick input, or in other words:
350 // provides defautls for all user-configurable model options.
351
352 // Remember to update this when a new option/element is added
353 // to the model_t struct (preferably before implementing the
354 // menu code that sets those options ...)
355
356 // This is used when a user wants a new, blank model, a reset
357 // of a configured model, and (most important) when EEPROM
358 // data format changes.
359 // NOTE: This means that stored model conficuration is reset
360 // to defaults when the EEPROM version/format changes.
361 model.channels = 8;
362 model.rev[0] = model.rev[1] = model.rev[2] = model.rev[3] =
363 model.rev[4] = model.rev[5] = model.rev[6] = model.rev[7] = false;
364 model.dr[0] = model.dr[1] = model.dr[2] = model.dr[3] = 0;
365 model.dr[4] = model.dr[5] = model.dr[6] = model.dr[7] = 100;
366
367 }
368
369 // ---------- Arduino main loop -----------------------
370 void loop ()
371 {
372
373 process_inputs();
374
375 // Wasting a full I/O pin on battery status monitoring!
376 battery_val = analogRead(1) * BATTERY_CONV;
377 if ( battery_val < BATTERY_LOW ) {
378 digitalWrite(13, 1); // Simulate alarm :P
379 }
380 if ( battery_val < BATTERY_CRITICAL ) {
381 displaystate = BATTERY;
382 }
383
384 if ( millis() - last > UI_INTERVAL )
385 {
386 last = millis();
387 ui_handler();
388 }
389
390 #ifdef DEBUG
391 if ( displaystate != MENU )
392 {
393 // Debugging: how long does the main loop take on avg,
394 // when not handling the UI...
395 t = micros();
396 avg_loop_time = ( t - prev_loop_time + avg_loop_time ) / 2;
397 prev_loop_time = t;
398 }
399 #endif
400
401 // Whoa! Slow down partner! Let everything settle down before proceeding.
402 delay(5);
403 }
404
405 // ----- Simple support functions used by more complex functions ----
406
407 void set_ppm_output( bool state )
408 {
409 digitalWrite(A5, state); // Hard coded PPM output
410 }
411
412 void set_timer(long time)
413 {
414 Timer1.detachInterrupt();
415 Timer1.attachInterrupt(ISR_timer, time);
416 }
417
418 boolean check_key( int key)
419 {
420 return ( !keys[key] && prev_keys[key] );
421 }
422
423 void mplx_select(int pin)
424 {
425 digitalWrite(5, 1);
426 delayMicroseconds(24);
427
428 digitalWrite(2, bitRead(pin,0)); // Arduino alias for non-modifying bitshift operation
429 digitalWrite(3, bitRead(pin,1)); // us used to extract individual bits from the int (0..7)
430 digitalWrite(4, bitRead(pin,2)); // Select the appropriate input by setting s1,s2,s3 and e
431 digitalWrite(5, 0); // on the 4051 multiplexer.
432
433 // May need to slow the following read down to be able to
434 // get fully reliable values from the 4051 multiplex.
435 delayMicroseconds(24);
436
437 }
438
439 // ----- "Complex" functions follow ---------------------------------
440
441 void calibrate()
442 {
443 int i, adc_in;
444 int num_calibrations = 200;
445
446 lcd.clear();
447 lcd.print("Move controls to");
448 lcd.setCursor(0,1);
449 lcd.print("their extremes..");
450 Serial.print("Calibration. Move all controls to their extremes.");
451
452 for (i=0; i<MAX_INPUTS; i++) {
453 input_cal.min[i] = 1024;
454 input_cal.center[i] = 512;
455 input_cal.max[i] = 0;
456 }
457
458 while ( num_calibrations-- )
459 {
460 for (i=0; i<MAX_INPUTS; i++) {
461 mplx_select(i);
462 adc_in = analogRead(0);
463
464 // Naive min/max calibration
465 if ( adc_in < input_cal.min[i] ) {
466 input_cal.min[i] = adc_in;
467 }
468 if ( adc_in > input_cal.max[i] ) {
469 input_cal.max[i] = adc_in;
470 }
471 delay(10);
472 }
473 }
474
475 // TODO: WILL need to do center-point calibration after min-max...
476
477 lcd.clear();
478 lcd.print("Saving to EEPROM");
479 write_calibration();
480 lcd.setCursor(0 , 1);
481 lcd.print("Done calibrating");
482
483 Serial.print("Done calibrating");
484 delay(2000);
485 }
486
487 void write_calibration(void)
488 {
489 int i;
490 unsigned char v;
491 const byte *p;
492
493 // Set p to be a pointer to the start of the input calibration struct.
494 p = (const byte*)(const void*)&input_cal;
495
496 // Iterate through the bytes of the struct...
497 for (i = 0; i < sizeof(input_cal_t); i++)
498 {
499 // Get a byte of data from the struct...
500 v = (unsigned char) *p;
501 // write it to EEPROM
502 EEPROM.write( EE_BASE_ADDR + i, v);
503 // and move the pointer to the next byte in the struct.
504 *p++;
505 }
506 }
507
508 void read_settings(void)
509 {
510 int i;
511 unsigned char v;
512 byte *p;
513
514 v = EEPROM.read(0);
515 if ( v != EEPROM_VERSION )
516 {
517 // All models have been reset. Set the current model to 0
518 current_model = 0;
519 EEPROM.write(1, current_model);
520
521 calibrate();
522 model_defaults();
523 // The following does not yet work...
524 for ( i = 0; i < MAX_MODELS; i++)
525 write_model_settings(i);
526
527
528 // After saving calibration data and model defaults,
529 // update the saved version-identifier to the current ver.
530 EEPROM.write(0, EEPROM_VERSION);
531 }
532
533 // Read calibration values from EEPROM.
534 // This uses simple pointer-arithmetic and byte-by-byte
535 // to put bytes read from EEPROM to the data-struct.
536 p = (byte*)(void*)&input_cal;
537 for (i = 0; i < sizeof(input_cal_t); i++)
538 *p++ = EEPROM.read( EE_BASE_ADDR + i);
539
540 // Get the previously selected model from EEPROM.
541 current_model = EEPROM.read(1);
542 read_model_settings( current_model );
543 }
544
545 void read_model_settings(unsigned char mod_no)
546 {
547 int model_address;
548 int i;
549 unsigned char v;
550 byte *p;
551
552 // Calculate the EEPROM start adress for the given model (mod_no)
553 model_address = EE_MDL_BASE_ADDR + (mod_no * sizeof(model_t));
554
555 // Do not try to write the model to EEPROM if it won't fit.
556 if ( INT_EEPROM_SIZE < (model_address + sizeof(model_t)) )
557 {
558 lcd.clear();
559 lcd.print("Aborting READ");
560 lcd.setCursor(0 , 1);
561 lcd.print("Invalid location");
562 delay(2000);
563 return;
564 }
565
566 lcd.clear();
567 lcd.print("Reading model ");
568 lcd.print( (int)mod_no );
569
570 // Pointer to the start of the model_t data struct,
571 // used for byte-by-byte reading of data...
572 p = (byte*)(void*)&model;
573 for (i = 0; i < sizeof(model_t); i++)
574 *p++ = EEPROM.read( model_address++ );
575
576 #ifdef DEBUG
577 serial_dump_model();
578 #endif
579
580 lcd.setCursor(0 , 1);
581 lcd.print("... Loaded.");
582 delay(1000);
583 }
584
585 void write_model_settings(unsigned char mod_no)
586 {
587 int model_address;
588 int i;
589 unsigned char v;
590 byte *p;
591
592 // Calculate the EEPROM start adress for the given model (mod_no)
593 model_address = EE_MDL_BASE_ADDR + (mod_no * sizeof(model_t));
594
595 // Do not try to write the model to EEPROM if it won't fit.
596 if ( INT_EEPROM_SIZE < (model_address + sizeof(model_t)) )
597 {
598 lcd.clear();
599 lcd.print("Aborting SAVE");
600 lcd.setCursor(0 , 1);
601 lcd.print("No room for data");
602 delay(2000);
603 return;
604 }
605
606 lcd.clear();
607 lcd.print("Saving model ");
608 lcd.print( (int)mod_no);
609
610 // Pointer to the start of the model_t data struct,
611 // used for byte-by-byte reading of data...
612 p = (byte*)(void*)&model;
613
614 // Write/serialize the model data struct to EEPROM...
615 for (i = 0; i < sizeof(model_t); i++)
616 EEPROM.write( model_address++, *p++);
617
618 lcd.setCursor(0 , 1);
619 lcd.print(".. done saving.");
620 delay(200);
621 }
622
623 #ifdef DEBUG
624 void serial_dump_model ( void )
625 {
626 int i;
627 int model_address;
628 // Calculate the EEPROM start adress for the given model (mod_no)
629 model_address = EE_MDL_BASE_ADDR + (current_model * sizeof(model_t));
630 Serial.print("Current model: ");
631 Serial.println( (int)current_model );
632 Serial.print("Models base addr: ");
633 Serial.println( EE_MDL_BASE_ADDR );
634 Serial.print("Model no: ");
635 Serial.println( current_model, 10 );
636 Serial.print("Size of struct: ");
637 Serial.println( sizeof( model_t) );
638 Serial.print("Model address: ");
639 Serial.println( model_address );
640 Serial.print("End of model: ");
641 Serial.println( model_address + sizeof(model_t) );
642
643 Serial.println();
644
645 Serial.print("Channel reversions: ");
646 for ( i = 0; i<8; i++)
647 {
648 Serial.print(i);
649 Serial.print("=");
650 Serial.print(model.rev[i], 10);
651 Serial.print(" ");
652 }
653 Serial.println();
654
655 Serial.print("DR1 inp 0: ");
656 Serial.println(model.dr[0]);
657 Serial.print("DR1 inp 1: ");
658 Serial.println(model.dr[1]);
659 Serial.print("DR1 LO val: ");
660 Serial.println(model.dr[4]);
661 Serial.print("DR1 HI val: ");
662 Serial.println(model.dr[5]);
663 Serial.print("DR2 inp 0: ");
664 Serial.println(model.dr[2]);
665 Serial.print("DR2 inp 1: ");
666 Serial.println(model.dr[3]);
667 Serial.print("DR2 LO val: ");
668 Serial.println(model.dr[6]);
669 Serial.print("DR2 HI val: ");
670 Serial.println(model.dr[7]);
671
672 for (i=0; i<MAX_INPUTS; i++) {
673 Serial.print("Input #");
674 Serial.print(i);
675 Serial.print(" pct: ");
676 Serial.print(model.stick[i]);
677 Serial.print(" min: ");
678 Serial.print(input_cal.min[i]);
679 Serial.print(" max: ");
680 Serial.print(input_cal.max[i]);
681 Serial.println();
682 }
683 }
684 #endif
685
686 void scan_keys ( void )
687 {
688 boolean key_in;
689
690 // To get more inputs, another 4051 analog multiplexer is used,
691 // but this time it is used for digital inputs. 8 digital inputs
692 // on one input line, as long as proper debouncing and filtering
693 // is done in hardware :P
694 for (int i=0; i<=7; i++) {
695 // To be able to detect that a key has changed state, preserve the previous..
696 prev_keys[i] = keys[i];
697
698 // Select and read input.
699 mplx_select(i);
700 keys[i] = digitalRead(A2);
701 delay(2);
702 }
703 }
704
705
706 void process_inputs(void )
707 {
708 int current_input, adc_in, fact;
709 float min, max;
710
711 for (current_input=0; current_input<MAX_INPUTS; current_input++) {
712
713 mplx_select(current_input);
714 adc_in = analogRead(0);
715
716 model.raw[current_input] = adc_in;
717 // New format on stick values
718 // The calculations happen around the center point, the values
719 // need to arrive at 0...100 of the range "center-to-edge",
720 // and must end up as negative on the ... negative side of center.
721
722 if ( adc_in < input_cal.center[current_input] )
723 {
724 // The stick is on the negative side, so the range is
725 // from the lowest possible value to center, and we must
726 // make this a negative percentage value.
727 max = input_cal.min[current_input];
728 min = input_cal.center[current_input];
729 fact = -100;
730 }
731 else
732 {
733 // The stick is at center, or on the positive side.
734 // Thus, the range is from center to max, and
735 // we need positive percentages.
736 min = input_cal.center[current_input];
737 max = input_cal.max[current_input];
738 fact = 100;
739 }
740 // Calculate the percentage that the current stick position is at
741 // in the given range, referenced to or from center, depending :P
742 model.stick[current_input] = fact * ((float)adc_in - min ) / (max - min);
743
744 // If this input is configured to be reversed, simply do a sign-flip :D
745 if ( model.rev[current_input] ) model.stick[current_input] *= -1;
746
747 // Dual-rate calculation :D
748 // This is very repetitive code. It should be fast, but it may waste code-space.
749 float dr_val;
750 // Test to see if dualrate-switch #1 applies to channel...
751 if ( ( current_input == ( model.dr[0]-1) ) || ( current_input == ( model.dr[1]-1) ) )
752 {
753 if ( !keys[KEY_DR1] )
754 dr_val = ((float)model.dr[4])/100.0;
755 else
756 dr_val = ((float)model.dr[5])/100.0;
757
758 model.stick[current_input] *= dr_val;
759 }
760 else
761 // Test to see if dualrate-switch #1 applies to channel...
762 if ( ( current_input == ( model.dr[2]-1) ) || ( current_input == ( model.dr[3]-1) ) )
763 {
764 if ( !keys[KEY_DR1] )
765 dr_val = ((float)model.dr[6])/100.0;
766 else
767 dr_val = ((float)model.dr[7])/100.0;
768
769 model.stick[current_input] *= dr_val;
770 }
771 }
772 }
773
774
775 void ISR_timer(void)
776 {
777 Timer1.stop(); // Make sure we do not run twice while working :P
778
779 if ( !do_channel )
780 {
781 set_ppm_output( LOW );
782 sum += seplength;
783 do_channel = true;
784 set_timer(seplength);
785 return;
786 }
787
788 if ( cchannel >= model.channels )
789 {
790 set_ppm_output( HIGH );
791 long framesep = framelength - sum;
792
793 sum = 0;
794 do_channel = false;
795 cchannel = 0;
796 set_timer ( framesep );
797 return;
798 }
799
800 if ( do_channel )
801 {
802 set_ppm_output( HIGH );
803
804 // New format on stick values
805 // model.stick contains percentages, -100% to 100% in float. To make the timer-handling
806 // here as simple as possible. We want to calc the channel value as a "ratio-value",
807 // a float in the range 0..1.0. So, by moving the lower bound to 0, then cutting the
808 // range in half, and finally dividing by 100, we should get the ratio value.
809 // Some loss of presicion occurs, perhaps the algo' should be reconsidered :P
810 long next_timer = (( chwidht * ((model.stick[cchannel]+100)/200) ) + chmin);
811 // Do sanity-check of next_timer compared to chmax and chmin...
812 while ( chmax < next_timer ) next_timer--;
813 while ( next_timer < chmin ) next_timer++;
814
815 // Update the sum of elapsed time
816 sum += next_timer;
817
818 // Done with channel separator and value,
819 // prepare for next channel...
820 cchannel++;
821 do_channel = false;
822 set_timer ( next_timer );
823 return;
824 }
825 }
826
827
828 #ifdef DEBUG
829 void serial_debug()
830 {
831 int current_input;
832 for (current_input=0; current_input<MAX_INPUTS; current_input++) {
833
834 Serial.print("Input #");
835 Serial.print(current_input);
836 Serial.print(" pct: ");
837 Serial.print(model.stick[current_input]);
838 Serial.print(" raw value: ");
839 Serial.print(model.raw[current_input]);
840 Serial.print(" min: ");
841 Serial.print(input_cal.min[current_input]);
842 Serial.print(" max: ");
843 Serial.print(input_cal.max[current_input]);
844 Serial.println();
845 }
846 Serial.print("Battery level is: ");
847 Serial.println(battery_val);
848
849 Serial.print("Average loop time:");
850 Serial.println(avg_loop_time);
851
852 Serial.print("Free RAM:");
853 Serial.print( FreeRam() );
854 Serial.println();
855 }
856 #endif
857
858 void dr_inputselect( int no, int in )
859 {
860 if ( model.dr[menu_substate] < 0 ) model.dr[menu_substate] = 4;
861 if ( model.dr[menu_substate] > 4 ) model.dr[menu_substate] = 0;
862
863 lcd.setCursor(0 , 0);
864 lcd.print("D/R switch ");
865 lcd.print( no + 1 );
866 lcd.print(" ");
867 lcd.setCursor(0 , 1);
868 lcd.print("Input ");
869 lcd.print(in+1);
870
871 lcd.print(": ");
872 if ( ! model.dr[menu_substate] ) lcd.print("Off");
873 else lcd.print(model.dr[menu_substate]);
874
875 if ( check_key(KEY_INC) ) {
876 model.dr[menu_substate]++;
877 return;
878 }
879 else if ( check_key(KEY_DEC) ) {
880 model.dr[menu_substate]--;
881 return;
882 }
883 // Wrap around.
884 return;
885
886 }
887
888 void dr_value()
889 {
890 int pos;
891 int state;
892
893 if ( menu_substate == 4) state = keys[KEY_DR1];
894 else state = keys[KEY_DR2];
895
896 pos = 4 + (menu_substate - 4) * 2;
897 if (state) pos++;
898
899 lcd.setCursor(0 , 0);
900 lcd.print("D/R switch ");
901 lcd.print( menu_substate - 3 );
902 lcd.print(" ");
903 lcd.setCursor(0 , 1);
904 lcd.print( state ? "HI" : "LO" );
905 lcd.print(" Value :");
906
907 lcd.print( model.dr[pos] );
908
909 if ( !keys[KEY_INC] ) {
910 if ( model.dr[pos] < 100) model.dr[pos] += 5;
911 return;
912 }
913 else if ( !keys[KEY_DEC] ) {
914 if ( model.dr[pos] > -100) model.dr[pos] -= 5;
915 return;
916 }
917
918 return;
919 }
920 void ui_handler()
921 {
922 int row;
923 int col;
924 scan_keys();
925
926 if ( displaystate != MENU )
927 {
928 menu_substate = 0;
929 if ( check_key(KEY_UP) && displaystate == VALUES ) {
930 displaystate = BATTERY;
931 return;
932 }
933 else if ( check_key(KEY_UP) && displaystate == BATTERY ) {
934 displaystate = TIMER;
935 return;
936 }
937 else if ( check_key(KEY_UP) && displaystate == TIMER ) {
938 displaystate = CURMODEL;
939 return;
940 }
941 else if ( check_key(KEY_UP) && displaystate == CURMODEL ) {
942 displaystate = VALUES;
943 return;
944 }
945
946 else if ( check_key(KEY_DOWN) ) {
947 displaystate = MENU;
948 return;
949 }
950 }
951
952 digitalWrite(13, digitalRead(13) ^ 1 );
953
954 switch ( displaystate )
955 {
956 case VALUES:
957 int current_input;
958 for (current_input=0; current_input<MAX_INPUTS; current_input++) {
959 // In channel value display, do a simple calc
960 // of the LCD row & column location. With 8 channels
961 // we can fit eight channels as percentage values on
962 // a simple 16x2 display...
963 if ( current_input < 4 )
964 {
965 col = current_input * 4;
966 row = 0;
967 }
968 else
969 {
970 col = (current_input-4) * 4;
971 row = 1;
972 }
973 // Overwriting the needed positions with
974 // blanks cause less display-flicker than
975 // actually clearing the display...
976 lcd.setCursor(col, row);
977 lcd.print(" ");
978 lcd.setCursor(col, row);
979 // Display uses percents, while PPM uses ratio....
980 // New format on stick values
981 lcd.print( (int)model.stick[current_input] );
982 }
983 break;
984
985
986 case BATTERY:
987 lcd.clear();
988 lcd.print("Battery level: ");
989 lcd.setCursor(0 , 1);
990 lcd.print( (float)battery_val/10);
991 lcd.print("V");
992 if ( battery_val < BATTERY_LOW ) lcd.print(" - WARNING");
993 else lcd.print(" - OK");
994 break;
995
996
997
998 case TIMER:
999 unsigned long delta;
1000 int hours;
1001 int minutes;
1002 int seconds;
1003
1004 lcd.clear();
1005 lcd.print("Timer: ");
1006 lcd.print( clock_timer.running ? "Running" : "Stopped" );
1007 lcd.setCursor(5 , 1);
1008 if ( clock_timer.running )
1009 {
1010 clock_timer.value = millis() - (clock_timer.start + clock_timer.init);
1011 }
1012 hours = ( clock_timer.value / 1000 ) / 3600;
1013 clock_timer.value = clock_timer.value % 3600000;
1014 minutes = ( clock_timer.value / 1000 ) / 60;
1015 seconds = ( clock_timer.value / 1000 ) % 60;
1016 if ( hours ) {
1017 lcd.print(hours);
1018 lcd.print(":");
1019 }
1020 if ( minutes < 10 ) lcd.print("0");
1021 lcd.print( minutes );
1022 lcd.print(":");
1023 if ( seconds < 10 ) lcd.print("0");
1024 lcd.print( seconds );
1025
1026 if ( check_key(KEY_INC) ) {
1027 if ( !clock_timer.running && !clock_timer.start )
1028 {
1029 clock_timer.start = millis();
1030 clock_timer.value = 0;
1031 clock_timer.running = true;
1032 } else if ( !clock_timer.running && clock_timer.start ) {
1033 clock_timer.start = millis() - clock_timer.value;
1034 clock_timer.running = true;
1035 } else if ( clock_timer.running ) {
1036 clock_timer.running = false;
1037 }
1038 return;
1039 } else if ( check_key(KEY_DEC) ) {
1040 if ( !clock_timer.running && clock_timer.start ) {
1041 clock_timer.value = 0;
1042 clock_timer.start = 0;
1043 clock_timer.init = 0;
1044 }
1045 return;
1046 }
1047 break;
1048
1049
1050
1051 case CURMODEL:
1052 lcd.clear();
1053 lcd.print("Model #: ");
1054 lcd.print( (int)current_model );
1055 lcd.setCursor(0 , 1);
1056 lcd.print("NAME (not impl)");
1057 break;
1058
1059
1060
1061 case MENU:
1062 lcd.clear();
1063 switch ( menu_mainstate )
1064 {
1065 case TOP:
1066 lcd.print("In MENU mode!");
1067 lcd.setCursor(0 , 1);
1068 lcd.print("Esc UP. Scrl DN.");
1069 menu_substate = 0;
1070 if ( check_key(KEY_UP) ) {
1071 displaystate = VALUES;
1072 return;
1073 }
1074 else if ( check_key(KEY_DOWN) ) {
1075 menu_mainstate = INVERTS;
1076 return;
1077 }
1078 break;
1079
1080
1081 case INVERTS:
1082 if ( menu_substate >= model.channels ) menu_substate = 0;
1083 if ( menu_substate < 0) menu_substate = (model.channels - 1);
1084 lcd.print("Channel invert");
1085 lcd.setCursor(0 , 1);
1086 lcd.print("Ch ");
1087 lcd.print(menu_substate+1);
1088 lcd.print( (model.rev[menu_substate] ? ": Invert" : ": Normal"));
1089
1090 if ( check_key(KEY_UP) ) {
1091 menu_mainstate = TOP;
1092 return;
1093 }
1094 else if ( check_key(KEY_DOWN) ) {
1095 menu_mainstate = DUALRATES;
1096 return;
1097 }
1098
1099 if ( check_key(KEY_RIGHT) ) {
1100 menu_substate++;
1101 return;
1102 }
1103 else if ( check_key(KEY_LEFT) ) {
1104 menu_substate--;
1105 return;
1106 }
1107 else if ( check_key(KEY_INC) || check_key(KEY_DEC) ) {
1108 model.rev[menu_substate] ^= 1;
1109 return;
1110 }
1111 break;
1112
1113 case DUALRATES:
1114 if ( menu_substate > 5 ) menu_substate = 0;
1115 if ( menu_substate < 0) menu_substate = 5;
1116
1117 if ( check_key(KEY_UP) ) {
1118 menu_mainstate = INVERTS;
1119 return;
1120 }
1121 if ( check_key(KEY_DOWN) ) {
1122 menu_mainstate = EXPOS;
1123 return;
1124 }
1125 if ( check_key(KEY_RIGHT) ) {
1126 menu_substate++;
1127 return;
1128 }
1129 else if ( check_key(KEY_LEFT) ) {
1130 menu_substate--;
1131 return;
1132 }
1133 switch (menu_substate)
1134 {
1135 case 0:
1136 dr_inputselect(0, 0);
1137 return;
1138 case 1:
1139 dr_inputselect(0, 1);
1140 return;
1141 case 2:
1142 dr_inputselect(1, 0);
1143 return;
1144 case 3:
1145 dr_inputselect(1, 1);
1146 return;
1147 case 4:
1148 case 5:
1149 dr_value();
1150 return;
1151 default:
1152 menu_substate = 0;
1153 break;
1154 }
1155 break;
1156
1157 case EXPOS:
1158 //________________
1159 lcd.print("Input expo curve");
1160 lcd.setCursor(0 , 1);
1161 lcd.print("Not implemented");
1162 // Possible, if input values are mapped to +/- 100 rather than 0..1 ..
1163 // plot ( x*(1 - 1.0*cos (x/(20*PI)) )) 0 to 100
1164 // Run in wolfram to see result, adjust the 1.0 factor to inc/red effect.
1165 // Problem: -100 to 100 is terribly bad presicion, esp. considering that
1166 // the values started as 0...1024, and we have 1000usec to "spend" on channels.
1167
1168 // NEW IDEA provided my ivarf @ hig: use bezier curves og hermite curves!
1169 // Looks like a promising idea, but the implementation is still a bitt off
1170 // on the time-horizon :P
1171 if ( check_key(KEY_UP ) ) {
1172 menu_mainstate = DUALRATES;
1173 return;
1174 }
1175 #ifdef DEBUG
1176 if ( check_key(KEY_DOWN ) ) {
1177 menu_mainstate = DEBUG_DUMP;
1178 return;
1179 }
1180 #else
1181 if ( check_key(KEY_DOWN ) ) {
1182 menu_mainstate = TOP;
1183 return;
1184 }
1185
1186 #endif
1187 break;
1188
1189 #ifdef DEBUG
1190 case DEBUG_DUMP:
1191 lcd.setCursor(0 , 0);
1192 lcd.print("Dumping debug to");
1193 lcd.setCursor(0 , 1);
1194 lcd.print("serial port 0");
1195 serial_debug();
1196 if ( check_key(KEY_UP ) ) {
1197 // FIXME: Remember to update the "Scroll up" state!
1198 menu_mainstate = EXPOS;
1199 return;
1200 } else if ( check_key(KEY_DOWN ) ) {
1201 menu_mainstate = SAVE;
1202 return;
1203 }
1204 break;
1205 #endif
1206 default:
1207 lcd.print("Not implemented");
1208 lcd.setCursor(0 , 1);
1209 lcd.print("Press DOWN...");
1210 if ( check_key(KEY_DOWN ) ) menu_mainstate = TOP;
1211 }
1212 break;
1213
1214
1215 default:
1216 // Invalid
1217 return;
1218 }
1219
1220 return;
1221 }
1222
1223 // ----------- LCD related functions ---------------
1224
1225 void LCDgotoXY(int x, int y) {
1226 LCDWrite(0, 0x80 | x); // Column.
1227 LCDWrite(0, 0x40 | y); // Row. ?
1228 }
1229
1230 //This takes a large array of bits and sends them to the LCD
1231 void LCDBitmap(char my_array[]){
1232 for (int index = 0 ; index < (LCD_X * LCD_Y / 8) ; index++)
1233 LCDWrite(LCD_DATA, my_array[index]);
1234 }
1235
1236 //This function takes in a character, looks it up in the font table/array
1237 //And writes it to the screen
1238 //Each character is 8 bits tall and 5 bits wide. We pad one blank column of
1239 //pixels on each side of the character for readability.
1240 void LCDCharacter(char character) {
1241 LCDWrite(LCD_DATA, 0x00); //Blank vertical line padding
1242
1243 for (int index = 0 ; index < 5 ; index++)
1244 LCDWrite(LCD_DATA, ASCII[character - 0x20][index]);
1245 //0x20 is the ASCII character for Space (' '). The font table starts with this character
1246
1247 LCDWrite(LCD_DATA, 0x00); //Blank vertical line padding
1248 }
1249
1250 //Given a string of characters, one by one is passed to the LCD
1251 void LCDString(char *characters) {
1252 while (*characters)
1253 LCDCharacter(*characters++);
1254 }
1255
1256 //Clears the LCD by writing zeros to the entire screen
1257 void LCDClear(void) {
1258 for (int index = 0 ; index < (LCD_X * LCD_Y / 8) ; index++)
1259 LCDWrite(LCD_DATA, 0x00);
1260
1261 LCDgotoXY(0, 0); //After we clear the display, return to the home position
1262 }
1263
1264 //This sends the magical commands to the PCD8544
1265 void LCDInit(void) {
1266
1267 //Configure control pins
1268 pinMode(PIN_SCE, OUTPUT);
1269 pinMode(PIN_RESET, OUTPUT);
1270 pinMode(PIN_DC, OUTPUT);
1271 pinMode(PIN_SDIN, OUTPUT);
1272 pinMode(PIN_SCLK, OUTPUT);
1273
1274 //Reset the LCD to a known state
1275 digitalWrite(PIN_RESET, LOW);
1276 digitalWrite(PIN_RESET, HIGH);
1277
1278 LCDWrite(LCD_COMMAND, 0x21); //Tell LCD that extended commands follow
1279 LCDWrite(LCD_COMMAND, 0xB0); //Set LCD Vop (Contrast): Try 0xB1(good @ 3.3V) or 0xBF if your display is too dark
1280 LCDWrite(LCD_COMMAND, 0x04); //Set Temp coefficent
1281 LCDWrite(LCD_COMMAND, 0x14); //LCD bias mode 1:48: Try 0x13 or 0x14
1282
1283 LCDWrite(LCD_COMMAND, 0x20); //We must send 0x20 before modifying the display control mode
1284 LCDWrite(LCD_COMMAND, 0x0C); //Set display control, normal mode. 0x0D for inverse
1285 }
1286
1287 //There are two memory banks in the LCD, data/RAM and commands. This
1288 //function sets the DC pin high or low depending, and then sends
1289 //the data byte
1290 void LCDWrite(byte data_or_command, byte data) {
1291 digitalWrite(PIN_DC, data_or_command); //Tell the LCD that we are writing either to data or a command
1292
1293 //Send the data
1294 digitalWrite(PIN_SCE, LOW);
1295 shiftOut(PIN_SDIN, PIN_SCLK, MSBFIRST, data);
1296 digitalWrite(PIN_SCE, HIGH);
1297 }
1298
1299
1300
1301 #ifdef DEBUG
1302 /* The following code is taken from the
1303 Arduino FAT16 Library by William Greiman
1304 The code may or may-not survive in the long run,
1305 depending on what licensing-terms we decide on.
1306 The license will be open source, but the FAT16lib
1307 is GPL v3, and I (fishy) am personally not so sure about that...
1308
1309 On the other hand... This code is a very "intuitive approach",
1310 so contacting the author may give us the option of relicencing just this bit...
1311 */
1312 static int FreeRam(void) {
1313 extern int __bss_end;
1314 extern int* __brkval;
1315 int free_memory;
1316 if (reinterpret_cast<int>(__brkval) == 0) {
1317 // if no heap use from end of bss section
1318 free_memory = reinterpret_cast<int>(&free_memory)
1319 - reinterpret_cast<int>(&__bss_end);
1320 } else {
1321 // use from top of stack to heap
1322 free_memory = reinterpret_cast<int>(&free_memory)
1323 - reinterpret_cast<int>(__brkval);
1324 }
1325 return free_memory;
1326 }
1327 #endif
1328
1329
1330
1331