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