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