]> git.defcon.no Git - rctxduino/blob - source/RCTXDuino/RCTXDuino.pde
Cleaned up indentation and coding style ...
[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 void model_defaults( void )
227 {
228 // This function provides default values for model data
229 // that is not a result of stick input, or in other words:
230 // provides defautls for all user-configurable model options.
231
232 // Remember to update this when a new option/element is added
233 // to the model_t struct (preferably before implementing the
234 // menu code that sets those options ...)
235
236 // This is used when a user wants a new, blank model, a reset
237 // of a configured model, and (most important) when EEPROM
238 // data format changes.
239 // NOTE: This means that stored model conficuration is reset
240 // to defaults when the EEPROM version/format changes.
241 model.channels = 8;
242 model.rev[0] = model.rev[1] = model.rev[2] = model.rev[3] =
243 model.rev[4] = model.rev[5] = model.rev[6] = model.rev[7] = false;
244 model.dr[0] = model.dr[1] = model.dr[2] = model.dr[3] = 0;
245 model.dr[4] = model.dr[5] = model.dr[6] = model.dr[7] = 100;
246 }
247
248 // ---------- Arduino main loop -----------------------
249 void loop ()
250 {
251 process_inputs();
252
253 // Wasting a full I/O pin on battery status monitoring!
254 battery_val = analogRead(1) * BATTERY_CONV;
255 if ( battery_val < BATTERY_LOW )
256 digitalWrite(13, 1); // Simulate alarm :P
257
258 if ( battery_val < BATTERY_CRITICAL )
259 displaystate = BATTERY;
260
261 if ( millis() - last > UI_INTERVAL )
262 {
263 last = millis();
264 ui_handler();
265 }
266
267 #ifdef DEBUG
268 if ( displaystate != MENU )
269 {
270 // Debugging: how long does the main loop take on avg,
271 // when not handling the UI...
272 t = micros();
273 avg_loop_time = ( t - prev_loop_time + avg_loop_time ) / 2;
274 prev_loop_time = t;
275 }
276 #endif
277
278 // Whoa! Slow down partner! Let everything settle down before proceeding.
279 delay(5);
280 }
281
282 // ----- Simple support functions used by more complex functions ----
283
284 void set_ppm_output( bool state )
285 {
286 digitalWrite(A5, state); // Hard coded PPM output
287 }
288
289 void set_timer(long time)
290 {
291 Timer1.detachInterrupt();
292 Timer1.attachInterrupt(ISR_timer, time);
293 }
294
295 boolean check_key( int key)
296 {
297 return ( !keys[key] && prev_keys[key] );
298 }
299
300 void mplx_select(int pin)
301 {
302 digitalWrite(5, 1);
303 delayMicroseconds(24);
304
305 digitalWrite(2, bitRead(pin,0)); // Arduino alias for non-modifying bitshift operation
306 digitalWrite(3, bitRead(pin,1)); // us used to extract individual bits from the int (0..7)
307 digitalWrite(4, bitRead(pin,2)); // Select the appropriate input by setting s1,s2,s3 and e
308 digitalWrite(5, 0); // on the 4051 multiplexer.
309
310 // May need to slow the following read down to be able to
311 // get fully reliable values from the 4051 multiplex.
312 delayMicroseconds(24);
313
314 }
315
316 // ----- "Complex" functions follow ---------------------------------
317
318 void calibrate()
319 {
320 int i, adc_in;
321 int num_calibrations = 200;
322
323 lcd.clear();
324 lcd.print("Move controls to");
325 lcd.setCursor(0,1);
326 lcd.print("their extremes..");
327 Serial.print("Calibration. Move all controls to their extremes.");
328
329 for (i=0; i<MAX_INPUTS; i++)
330 {
331 input_cal.min[i] = 1024;
332 input_cal.center[i] = 512;
333 input_cal.max[i] = 0;
334 }
335
336 while ( num_calibrations-- )
337 {
338 for (i=0; i<MAX_INPUTS; i++)
339 {
340 mplx_select(i);
341 adc_in = analogRead(0);
342
343 // Naive min/max calibration
344 if ( adc_in < input_cal.min[i] )
345 input_cal.min[i] = adc_in;
346
347 if ( adc_in > input_cal.max[i] )
348 input_cal.max[i] = adc_in;
349
350 delay(10);
351 }
352 }
353
354 // TODO: WILL need to do center-point calibration after min-max...
355
356 lcd.clear();
357 lcd.print("Saving to EEPROM");
358 write_calibration();
359 lcd.setCursor(0 , 1);
360 lcd.print("Done calibrating");
361
362 Serial.print("Done calibrating");
363 delay(2000);
364 }
365
366 void write_calibration(void)
367 {
368 int i;
369 unsigned char v;
370 const byte *p;
371
372 // Set p to be a pointer to the start of the input calibration struct.
373 p = (const byte*)(const void*)&input_cal;
374
375 // Iterate through the bytes of the struct...
376 for (i = 0; i < sizeof(input_cal_t); i++)
377 {
378 // Get a byte of data from the struct...
379 v = (unsigned char) *p;
380 // write it to EEPROM
381 EEPROM.write( EE_BASE_ADDR + i, v);
382 // and move the pointer to the next byte in the struct.
383 *p++;
384 }
385 }
386
387 void read_settings(void)
388 {
389 int i;
390 unsigned char v;
391 byte *p;
392
393 v = EEPROM.read(0);
394 if ( v != EEPROM_VERSION )
395 {
396 // All models have been reset. Set the current model to 0
397 current_model = 0;
398 EEPROM.write(1, current_model);
399
400 calibrate();
401 model_defaults();
402 // The following does not yet work...
403 for ( i = 0; i < MAX_MODELS; i++)
404 write_model_settings(i);
405
406
407 // After saving calibration data and model defaults,
408 // update the saved version-identifier to the current ver.
409 EEPROM.write(0, EEPROM_VERSION);
410 }
411
412 // Read calibration values from EEPROM.
413 // This uses simple pointer-arithmetic and byte-by-byte
414 // to put bytes read from EEPROM to the data-struct.
415 p = (byte*)(void*)&input_cal;
416 for (i = 0; i < sizeof(input_cal_t); i++)
417 *p++ = EEPROM.read( EE_BASE_ADDR + i);
418
419 // Get the previously selected model from EEPROM.
420 current_model = EEPROM.read(1);
421 read_model_settings( current_model );
422 }
423
424 void read_model_settings(unsigned char mod_no)
425 {
426 int model_address;
427 int i;
428 unsigned char v;
429 byte *p;
430
431 // Calculate the EEPROM start adress for the given model (mod_no)
432 model_address = EE_MDL_BASE_ADDR + (mod_no * sizeof(model_t));
433
434 // Do not try to write the model to EEPROM if it won't fit.
435 if ( INT_EEPROM_SIZE < (model_address + sizeof(model_t)) )
436 {
437 lcd.clear();
438 lcd.print("Aborting READ");
439 lcd.setCursor(0 , 1);
440 lcd.print("Invalid location");
441 delay(2000);
442 return;
443 }
444
445 lcd.clear();
446 lcd.print("Reading model ");
447 lcd.print( (int)mod_no );
448
449 // Pointer to the start of the model_t data struct,
450 // used for byte-by-byte reading of data...
451 p = (byte*)(void*)&model;
452 for (i = 0; i < sizeof(model_t); i++)
453 *p++ = EEPROM.read( model_address++ );
454
455 #ifdef DEBUG
456 serial_dump_model();
457 #endif
458
459 lcd.setCursor(0 , 1);
460 lcd.print("... Loaded.");
461 delay(1000);
462 }
463
464 void write_model_settings(unsigned char mod_no)
465 {
466 int model_address;
467 int i;
468 unsigned char v;
469 byte *p;
470
471 // Calculate the EEPROM start adress for the given model (mod_no)
472 model_address = EE_MDL_BASE_ADDR + (mod_no * sizeof(model_t));
473
474 // Do not try to write the model to EEPROM if it won't fit.
475 if ( INT_EEPROM_SIZE < (model_address + sizeof(model_t)) )
476 {
477 lcd.clear();
478 lcd.print("Aborting SAVE");
479 lcd.setCursor(0 , 1);
480 lcd.print("No room for data");
481 delay(2000);
482 return;
483 }
484
485 lcd.clear();
486 lcd.print("Saving model ");
487 lcd.print( (int)mod_no);
488
489 // Pointer to the start of the model_t data struct,
490 // used for byte-by-byte reading of data...
491 p = (byte*)(void*)&model;
492
493 // Write/serialize the model data struct to EEPROM...
494 for (i = 0; i < sizeof(model_t); i++)
495 EEPROM.write( model_address++, *p++);
496
497 lcd.setCursor(0 , 1);
498 lcd.print(".. done saving.");
499 delay(200);
500 }
501
502 #ifdef DEBUG
503 void serial_dump_model ( void )
504 {
505 int i;
506 int model_address;
507 // Calculate the EEPROM start adress for the given model (mod_no)
508 model_address = EE_MDL_BASE_ADDR + (current_model * sizeof(model_t));
509 Serial.print("Current model: ");
510 Serial.println( (int)current_model );
511 Serial.print("Models base addr: ");
512 Serial.println( EE_MDL_BASE_ADDR );
513 Serial.print("Model no: ");
514 Serial.println( current_model, 10 );
515 Serial.print("Size of struct: ");
516 Serial.println( sizeof( model_t) );
517 Serial.print("Model address: ");
518 Serial.println( model_address );
519 Serial.print("End of model: ");
520 Serial.println( model_address + sizeof(model_t) );
521
522 Serial.println();
523
524 Serial.print("Channel reversions: ");
525 for ( i = 0; i<8; i++)
526 {
527 Serial.print(i);
528 Serial.print("=");
529 Serial.print(model.rev[i], 10);
530 Serial.print(" ");
531 }
532 Serial.println();
533
534 Serial.print("DR1 inp 0: ");
535 Serial.println(model.dr[0]);
536 Serial.print("DR1 inp 1: ");
537 Serial.println(model.dr[1]);
538 Serial.print("DR1 LO val: ");
539 Serial.println(model.dr[4]);
540 Serial.print("DR1 HI val: ");
541 Serial.println(model.dr[5]);
542 Serial.print("DR2 inp 0: ");
543 Serial.println(model.dr[2]);
544 Serial.print("DR2 inp 1: ");
545 Serial.println(model.dr[3]);
546 Serial.print("DR2 LO val: ");
547 Serial.println(model.dr[6]);
548 Serial.print("DR2 HI val: ");
549 Serial.println(model.dr[7]);
550
551 for (i=0; i<MAX_INPUTS; i++)
552 {
553 Serial.print("Input #");
554 Serial.print(i);
555 Serial.print(" pct: ");
556 Serial.print(model.stick[i]);
557 Serial.print(" min: ");
558 Serial.print(input_cal.min[i]);
559 Serial.print(" max: ");
560 Serial.print(input_cal.max[i]);
561 Serial.println();
562 }
563 }
564 #endif
565
566 void scan_keys ( void )
567 {
568 boolean key_in;
569
570 // To get more inputs, another 4051 analog multiplexer is used,
571 // but this time it is used for digital inputs. 8 digital inputs
572 // on one input line, as long as proper debouncing and filtering
573 // is done in hardware :P
574 for (int i=0; i<=7; i++)
575 {
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
595 mplx_select(current_input);
596 adc_in = analogRead(0);
597
598 model.raw[current_input] = adc_in;
599 // New format on stick values
600 // The calculations happen around the center point, the values
601 // need to arrive at 0...100 of the range "center-to-edge",
602 // and must end up as negative on the ... negative side of center.
603
604 if ( adc_in < input_cal.center[current_input] )
605 {
606 // The stick is on the negative side, so the range is
607 // from the lowest possible value to center, and we must
608 // make this a negative percentage value.
609 max = input_cal.min[current_input];
610 min = input_cal.center[current_input];
611 fact = -100;
612 }
613 else
614 {
615 // The stick is at center, or on the positive side.
616 // Thus, the range is from center to max, and
617 // we need positive percentages.
618 min = input_cal.center[current_input];
619 max = input_cal.max[current_input];
620 fact = 100;
621 }
622 // Calculate the percentage that the current stick position is at
623 // in the given range, referenced to or from center, depending :P
624 model.stick[current_input] = fact * ((float)adc_in - min ) / (max - min);
625
626 // If this input is configured to be reversed, simply do a sign-flip :D
627 if ( model.rev[current_input] ) model.stick[current_input] *= -1;
628
629 // Dual-rate calculation :D
630 // This is very repetitive code. It should be fast, but it may waste code-space.
631 float dr_val;
632 // Test to see if dualrate-switch #1 applies to channel...
633 if ( ( current_input == ( model.dr[0]-1) ) || ( current_input == ( model.dr[1]-1) ) )
634 {
635 if ( !keys[KEY_DR1] )
636 dr_val = ((float)model.dr[4])/100.0;
637 else
638 dr_val = ((float)model.dr[5])/100.0;
639
640 model.stick[current_input] *= dr_val;
641 }
642 else
643 // Test to see if dualrate-switch #1 applies to channel...
644 if ( ( current_input == ( model.dr[2]-1) ) || ( current_input == ( model.dr[3]-1) ) )
645 {
646 if ( !keys[KEY_DR2] )
647 dr_val = ((float)model.dr[6])/100.0;
648 else
649 dr_val = ((float)model.dr[7])/100.0;
650
651 model.stick[current_input] *= dr_val;
652 }
653 }
654 }
655
656
657 void ISR_timer(void)
658 {
659 Timer1.stop(); // Make sure we do not run twice while working :P
660
661 if ( !do_channel )
662 {
663 set_ppm_output( LOW );
664 sum += seplength;
665 do_channel = true;
666 set_timer(seplength);
667 return;
668 }
669
670 if ( cchannel >= model.channels )
671 {
672 set_ppm_output( HIGH );
673 long framesep = framelength - sum;
674
675 sum = 0;
676 do_channel = false;
677 cchannel = 0;
678 set_timer ( framesep );
679 return;
680 }
681
682 if ( do_channel )
683 {
684 set_ppm_output( HIGH );
685
686 // New format on stick values
687 // model.stick contains percentages, -100% to 100% in float. To make the timer-handling
688 // here as simple as possible. We want to calc the channel value as a "ratio-value",
689 // a float in the range 0..1.0. So, by moving the lower bound to 0, then cutting the
690 // range in half, and finally dividing by 100, we should get the ratio value.
691 // Some loss of presicion occurs, perhaps the algo' should be reconsidered :P
692 long next_timer = (( chwidht * ((model.stick[cchannel]+100)/200) ) + chmin);
693
694 // Do sanity-check of next_timer compared to chmax and chmin...
695 while ( chmax < next_timer ) next_timer--;
696 while ( next_timer < chmin ) next_timer++;
697
698 // Update the sum of elapsed time
699 sum += next_timer;
700
701 // Done with channel separator and value,
702 // prepare for next channel...
703 cchannel++;
704 do_channel = false;
705 set_timer ( next_timer );
706 return;
707 }
708 }
709
710
711 #ifdef DEBUG
712 void serial_debug()
713 {
714 int current_input;
715 for (current_input=0; current_input<MAX_INPUTS; current_input++)
716 {
717 Serial.print("Input #");
718 Serial.print(current_input);
719 Serial.print(" pct: ");
720 Serial.print(model.stick[current_input]);
721 Serial.print(" raw value: ");
722 Serial.print(model.raw[current_input]);
723 Serial.print(" min: ");
724 Serial.print(input_cal.min[current_input]);
725 Serial.print(" max: ");
726 Serial.print(input_cal.max[current_input]);
727 Serial.println();
728 }
729 Serial.print("Battery level is: ");
730 Serial.println(battery_val);
731
732 Serial.print("Average loop time:");
733 Serial.println(avg_loop_time);
734
735 Serial.print("Free RAM:");
736 Serial.print( FreeRam() );
737 Serial.println();
738 }
739 #endif
740
741 void dr_inputselect( int no, int in )
742 {
743 if ( model.dr[menu_substate] < 0 ) model.dr[menu_substate] = 4;
744 if ( model.dr[menu_substate] > 4 ) model.dr[menu_substate] = 0;
745
746 lcd.setCursor(0 , 0);
747 lcd.print("D/R switch ");
748 lcd.print( no + 1 );
749 //lcd.print(" ");
750
751 lcd.setCursor(0 , 1);
752 lcd.print(" ");
753 lcd.setCursor(0 , 1);
754 lcd.print("Input ");
755 lcd.print(in+1);
756
757 lcd.print(": ");
758 if ( ! model.dr[menu_substate] ) lcd.print("Off");
759 else lcd.print(model.dr[menu_substate]);
760
761 if ( check_key(KEY_INC) ) {
762 model.dr[menu_substate]++;
763 return;
764 }
765 else if ( check_key(KEY_DEC) ) {
766 model.dr[menu_substate]--;
767 return;
768 }
769 // Wrap around.
770 return;
771
772 }
773
774 void dr_value()
775 {
776 int pos;
777 int state;
778
779 if ( menu_substate == 4) state = keys[KEY_DR1];
780 else state = keys[KEY_DR2];
781
782 pos = 4 + (menu_substate - 4) * 2;
783 if (state) pos++;
784
785 lcd.setCursor(0 , 0);
786 lcd.print("D/R switch ");
787 lcd.print( menu_substate - 3 );
788
789
790 lcd.setCursor(0 , 1);
791 lcd.print(" ");
792 lcd.setCursor(0 , 1);
793 lcd.print( state ? "HI" : "LO" );
794 lcd.print(" Value :");
795
796 lcd.print( model.dr[pos] );
797
798 if ( !keys[KEY_INC] ) {
799 if ( model.dr[pos] < 100) model.dr[pos] += 5;
800 return;
801 }
802 else if ( !keys[KEY_DEC] ) {
803 if ( model.dr[pos] > -100) model.dr[pos] -= 5;
804 return;
805 }
806
807 return;
808 }
809 void ui_handler()
810 {
811 int row;
812 int col;
813 scan_keys();
814
815 if ( check_key( KEY_UP) || check_key(KEY_DOWN))
816 lcd.clear();
817
818 if ( displaystate != MENU )
819 {
820 menu_substate = 0;
821 if ( check_key(KEY_UP) && displaystate == VALUES ) {
822 displaystate = BATTERY;
823 return;
824 }
825 else if ( check_key(KEY_UP) && displaystate == BATTERY ) {
826 displaystate = TIMER;
827 return;
828 }
829 else if ( check_key(KEY_UP) && displaystate == TIMER ) {
830 displaystate = CURMODEL;
831 return;
832 }
833 else if ( check_key(KEY_UP) && displaystate == CURMODEL ) {
834 displaystate = VALUES;
835 return;
836 }
837
838 else if ( check_key(KEY_DOWN) ) {
839 displaystate = MENU;
840 return;
841 }
842 }
843
844 digitalWrite(13, digitalRead(13) ^ 1 );
845
846 switch ( displaystate )
847 {
848 case VALUES:
849 int current_input;
850
851 row = 0; col = 0;
852 lcd.setCursor(col, row);
853 lcd.print(" ");
854 lcd.setCursor(col, row);
855
856 lcd.print("S1:");
857 lcd.print( keys[KEY_DR1] ? "On " : "Off" );
858 lcd.print(" S2:");
859 lcd.print( keys[KEY_DR2] ? "On " : "Off" );
860
861 row = 2; col = 0;
862 for (current_input=0; current_input<MAX_INPUTS; current_input++) {
863 if (row == 6)
864 {
865 row = 2;
866 col = 40;
867 }
868
869 // Overwriting the needed positions with
870 // blanks cause less display-flicker than
871 // actually clearing the display...
872 lcd.setCursor(col, row);
873 lcd.print(" ");
874 lcd.setCursor(col, row);
875
876 char mod_indicator = NULL;
877 if (( keys[KEY_DR1] ) && (( model.dr[0] == current_input+1) || ( model.dr[1] == current_input+1)))
878 mod_indicator = '/';
879 if (( keys[KEY_DR2] ) && (( model.dr[2] == current_input+1) || ( model.dr[3] == current_input+1)))
880 if (mod_indicator) mod_indicator = '|';
881 else mod_indicator = '\\';
882
883 if ( mod_indicator) lcd.print(mod_indicator);
884 else lcd.print(" ");
885
886 lcd.print( current_input+1);
887 lcd.print(":");
888 // Display uses percents, while PPM uses ratio....
889 // New format on stick values
890 lcd.print( (int)model.stick[current_input] );
891
892 row++;
893 }
894 break;
895
896 case BATTERY:
897 lcd.setCursor(0 , 0);
898 lcd.print("Battery level: ");
899 lcd.setCursor(0 , 1);
900 lcd.print( " ");
901 lcd.setCursor(0 , 1);
902 lcd.print( (float)battery_val/10);
903 lcd.print("V");
904 if ( battery_val < BATTERY_LOW ) lcd.print(" - WARNING");
905 else lcd.print(" - OK");
906 break;
907
908
909
910 case TIMER:
911 unsigned long delta;
912 int hours;
913 int minutes;
914 int seconds;
915
916 lcd.setCursor(0 , 0);
917 lcd.print("Timer: ");
918 lcd.print( clock_timer.running ? "Running" : "Stopped" );
919 lcd.setCursor(5 , 1);
920 lcd.print(" ");
921 lcd.setCursor(5 , 1);
922 if ( clock_timer.running )
923 {
924 clock_timer.value = millis() - (clock_timer.start + clock_timer.init);
925 }
926 hours = ( clock_timer.value / 1000 ) / 3600;
927 clock_timer.value = clock_timer.value % 3600000;
928 minutes = ( clock_timer.value / 1000 ) / 60;
929 seconds = ( clock_timer.value / 1000 ) % 60;
930 if ( hours )
931 {
932 lcd.print(hours);
933 lcd.print(":");
934 }
935 if ( minutes < 10 ) lcd.print("0");
936 lcd.print( minutes );
937 lcd.print(":");
938 if ( seconds < 10 ) lcd.print("0");
939 lcd.print( seconds );
940
941 if ( check_key(KEY_INC) )
942 {
943 if ( !clock_timer.running && !clock_timer.start )
944 {
945 clock_timer.start = millis();
946 clock_timer.value = 0;
947 clock_timer.running = true;
948 }
949 else if ( !clock_timer.running && clock_timer.start )
950 {
951 clock_timer.start = millis() - clock_timer.value;
952 clock_timer.running = true;
953 }
954 else if ( clock_timer.running )
955 clock_timer.running = false;
956
957 return;
958
959 }
960 else if ( check_key(KEY_DEC) )
961 {
962 if ( !clock_timer.running && clock_timer.start )
963 {
964 clock_timer.value = 0;
965 clock_timer.start = 0;
966 clock_timer.init = 0;
967 }
968 return;
969 }
970 break;
971
972
973 case CURMODEL:
974 lcd.setCursor(0 , 0);
975 lcd.print("Model #: ");
976 lcd.print( (int)current_model );
977 lcd.setCursor(0 , 1);
978 lcd.print("NAME (not impl)");
979 break;
980
981
982
983 case MENU:
984 lcd.setCursor(0 , 0);
985 switch ( menu_mainstate )
986 {
987 case TOP:
988 lcd.setCursor(0 , 0);
989 lcd.print("In MENU mode!");
990 lcd.setCursor(0 , 1);
991 lcd.print("UP to quit.");
992 lcd.setCursor(0 , 2);
993 lcd.print("DOWN to scroll");
994
995 menu_substate = 0;
996 if ( check_key(KEY_UP) )
997 {
998 displaystate = VALUES;
999 lcd.clear();
1000 return;
1001 }
1002 else if ( check_key(KEY_DOWN) )
1003 {
1004 lcd.clear();
1005 menu_mainstate = INVERTS;
1006 return;
1007 }
1008 break;
1009
1010
1011 case INVERTS:
1012 if ( menu_substate >= model.channels ) menu_substate = 0;
1013 if ( menu_substate < 0) menu_substate = (model.channels - 1);
1014 lcd.print("Channel invert");
1015 lcd.setCursor(0 , 1);
1016 lcd.print("Ch ");
1017 lcd.print(menu_substate+1);
1018 lcd.print( (model.rev[menu_substate] ? ": Invert" : ": Normal"));
1019
1020 if ( check_key(KEY_UP) )
1021 {
1022 menu_mainstate = TOP;
1023 lcd.clear();
1024 return;
1025 }
1026 else if ( check_key(KEY_DOWN) )
1027 {
1028 menu_mainstate = DUALRATES;
1029 lcd.clear();
1030 return;
1031 }
1032
1033 if ( check_key(KEY_RIGHT) )
1034 {
1035 menu_substate++;
1036 return;
1037 }
1038 else if ( check_key(KEY_LEFT) )
1039 {
1040 menu_substate--;
1041 return;
1042 }
1043 else if ( check_key(KEY_INC) || check_key(KEY_DEC) )
1044 {
1045 model.rev[menu_substate] ^= 1;
1046 return;
1047 }
1048 break;
1049
1050 case DUALRATES:
1051 if ( menu_substate > 5 ) menu_substate = 0;
1052 if ( menu_substate < 0) menu_substate = 5;
1053
1054 if ( check_key(KEY_UP) )
1055 {
1056 menu_mainstate = INVERTS;
1057 lcd.clear();
1058 return;
1059 }
1060 if ( check_key(KEY_DOWN) )
1061 {
1062 menu_mainstate = EXPOS;
1063 lcd.clear();
1064 return;
1065 }
1066 if ( check_key(KEY_RIGHT) )
1067 {
1068 menu_substate++;
1069 return;
1070 }
1071 else if ( check_key(KEY_LEFT) )
1072 {
1073 menu_substate--;
1074 return;
1075 }
1076
1077 switch (menu_substate)
1078 {
1079 case 0:
1080 dr_inputselect(0, 0);
1081 return;
1082 case 1:
1083 dr_inputselect(0, 1);
1084 return;
1085 case 2:
1086 dr_inputselect(1, 0);
1087 return;
1088 case 3:
1089 dr_inputselect(1, 1);
1090 return;
1091 case 4:
1092 case 5:
1093 dr_value();
1094 return;
1095 default:
1096 menu_substate = 0;
1097 break;
1098 }
1099 break;
1100
1101 case EXPOS:
1102 //________________
1103 lcd.print("Input expo curve");
1104 lcd.setCursor(0 , 1);
1105 lcd.print("Not implemented");
1106 // Possible, if input values are mapped to +/- 100 rather than 0..1 ..
1107 // plot ( x*(1 - 1.0*cos (x/(20*PI)) )) 0 to 100
1108 // Run in wolfram to see result, adjust the 1.0 factor to inc/red effect.
1109 // Problem: -100 to 100 is terribly bad presicion, esp. considering that
1110 // the values started as 0...1024, and we have 1000usec to "spend" on channels.
1111
1112 // NEW IDEA provided my ivarf @ hig: use bezier curves og hermite curves!
1113 // Looks like a promising idea, but the implementation is still a bitt off
1114 // on the time-horizon :P
1115 if ( check_key(KEY_UP ) )
1116 {
1117 menu_mainstate = DUALRATES;
1118 lcd.clear();
1119 return;
1120 }
1121 #ifdef DEBUG
1122 if ( check_key(KEY_DOWN ) )
1123 {
1124 menu_mainstate = DEBUG_DUMP;
1125 lcd.clear();
1126 return;
1127 }
1128 #else
1129 if ( check_key(KEY_DOWN ) )
1130 {
1131 menu_mainstate = TOP;
1132 lcd.clear();
1133 return;
1134 }
1135
1136 #endif
1137 break;
1138
1139 #ifdef DEBUG
1140 case DEBUG_DUMP:
1141 lcd.setCursor(0 , 0);
1142 lcd.print("Dumping debug to");
1143 lcd.setCursor(0 , 1);
1144 lcd.print("serial port 0");
1145 serial_debug();
1146 if ( check_key(KEY_UP ) )
1147 {
1148 // FIXME: Remember to update the "Scroll up" state!
1149 menu_mainstate = EXPOS;
1150 lcd.clear();
1151 return;
1152 } else if ( check_key(KEY_DOWN ) )
1153 {
1154 menu_mainstate = SAVE;
1155 lcd.clear();
1156 return;
1157 }
1158 break;
1159 #endif
1160 default:
1161 lcd.print("Not implemented");
1162 lcd.setCursor(0 , 1);
1163 lcd.print("Press DOWN...");
1164 if ( check_key(KEY_DOWN ) ) menu_mainstate = TOP;
1165
1166 } // End of settings menu / MENU
1167 break;
1168
1169
1170 default:
1171 // Invalid
1172 return;
1173 } // End of main UI switch
1174 return;
1175 }
1176
1177 #ifdef DEBUG
1178 /* The following code is taken from the
1179 Arduino FAT16 Library by William Greiman
1180 The code may or may-not survive in the long run,
1181 depending on what licensing-terms we decide on.
1182 The license will be open source, but the FAT16lib
1183 is GPL v3, and I (fishy) am personally not so sure about that...
1184
1185 On the other hand... This code is a very "intuitive approach",
1186 so contacting the author may give us the option of relicencing just this bit...
1187 */
1188 static int FreeRam(void) {
1189 extern int __bss_end;
1190 extern int* __brkval;
1191 int free_memory;
1192 if (reinterpret_cast<int>(__brkval) == 0)
1193 {
1194 // if no heap use from end of bss section
1195 free_memory = reinterpret_cast<int>(&free_memory)
1196 - reinterpret_cast<int>(&__bss_end);
1197 }
1198 else
1199 {
1200 // use from top of stack to heap
1201 free_memory = reinterpret_cast<int>(&free_memory)
1202 - reinterpret_cast<int>(__brkval);
1203 }
1204 return free_memory;
1205 }
1206 #endif
1207
1208
1209
1210