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