]> git.defcon.no Git - rctxduino/blob - source/RCTXDuino/RCTXDuino.pde
Changed for HIGH to LOW logic, and enabled internal pullups for the UI-buttons
[rctxduino] / source / RCTXDuino / RCTXDuino.pde
1 #include <LiquidCrystal.h>
2 #include <TimerOne.h>
3
4 #define MAX_INPUTS 8
5
6 // --------------- ADC related stuffs.... --------------------
7
8 struct input_cal_t // Struct type for input calibration values
9 {
10 int min[MAX_INPUTS];
11 int max[MAX_INPUTS];
12 int center[MAX_INPUTS];
13 } ;
14 input_cal_t input_cal;
15
16 struct model_t
17 {
18 int channels; // How many channels should PPM generate for this model ...
19 float stick[8]; // The (potentially recalc'ed) value of stick/input channel.
20 boolean rev[8];
21 int dr[8]; // The Dual-rate array uses magic numbers :P
22 /* dr[0] = Input channel #1 of 2 for D/R switch #1. 0 means off, 1-4 valid values.
23 dr[1] = Input channel #2 of 2 for D/R switch #1. 0 means off, 1-4 valid values.
24 dr[2] = Input channel #1 of 2 for D/R switch #2. 0 means off, 1-4 valid values.
25 dr[3] = Input channel #2 of 2 for D/R switch #2. 0 means off, 1-4 valid values.
26 dr[4] = D/R value for switch # 1 LOW(off). Value -100 to 100 in steps of 5.
27 dr[5] = D/R value for switch # 1 HIGH(on). Value -100 to 100 in steps of 5.
28 dr[6] = D/R value for switch # 1 LOW(off). Value -100 to 100 in steps of 5.
29 dr[7] = D/R value for switch # 1 HIGH(on). Value -100 to 100 in steps of 5.
30 */
31 };
32 volatile model_t model;
33
34 // ----------------- Display related stuffs --------------------
35 LiquidCrystal lcd( 12, 11, 10, 6, 7, 8, 9);
36 // Parameters are: rs, rw, enable, d4, d5, d6, d7 pin numbers.
37
38 // ----------------- PPM related stuffs ------------------------
39 // The PPM generation is handled by Timer0 interrupts, and needs
40 // all modifiable variables to be global and volatile...
41
42 //int max_channels = 6; // How many channels should PPM generate ...
43 // Moved to model_t struct...
44
45 volatile long sum = 0; // Frame-time spent so far
46 volatile int cchannel = 0; // Current channnel
47 volatile bool do_channel = true; // Is next operation a channel or a separator
48
49
50 // All time values in usecs
51 // TODO:
52 // The timing here (and/or in the ISR) needs to be tweaked to provide valid
53 // RC PPM signals accepted by standard RC RX'es and the Microcopter...
54
55 #define framelength 21500 // Max length of frame
56 #define seplength 400 // Lenght of a channel separator
57 #define chmax 1700 // Max lenght of channel pulse
58 #define chmin 600 // Min length of channel
59 #define chwidht (chmax - chmin)// Useable time of channel pulse
60
61 // ----------------- Menu/IU related stuffs --------------------
62
63 // Keys/buttons/switches for UI use, including dual-rate/expo
64 // are digital inputs connected to a 4051 multiplexer, giving
65 // 8 inputs on a single input pin.
66 #define KEY_UP 0
67 #define KEY_DOWN 1
68 #define KEY_RIGHT 2
69 #define KEY_LEFT 3
70 #define KEY_INC 4
71 #define KEY_DEC 5
72 #define KEY_DR1 6
73 #define KEY_DR2 7
74
75 // Voltage sense pin is connected to a 1/3'd voltage divider.
76 #define BATTERY_CONV (10 * 3 * (5.0f/1024.0f))
77 #define BATTERY_LOW 92
78
79 enum {
80 VALUES,
81 BATTERY,
82 TIMER,
83 MENU
84 }
85 displaystate;
86
87 enum {
88 TOP,
89 INVERTS,
90 DUALRATES,
91 EXPOS, // Some radios have "drawn curves", i.e. loopup tables stored in external EEPROM ...
92 DEBUG,
93 SAVE
94 }
95 menu_mainstate;
96 int menu_substate;
97
98 boolean keys[8];
99 boolean prev_keys[8];
100
101 int battery_val;
102
103 // The display/UI is handled only when more
104 // than UI_INTERVAL milliecs has passed since last...
105 #define UI_INTERVAL 250
106 unsigned long last = 0;
107
108 struct clock_timer_t
109 {
110 unsigned long start;
111 unsigned long init;
112 unsigned long value;
113 boolean running;
114 } clock_timer;
115
116 // ----------------- DEBUG-STUFF --------------------
117 unsigned long prev_loop_time;
118 unsigned long avg_loop_time;
119 unsigned long t;
120
121
122 // ---------- CODE! -----------------------------------
123
124 // ---------- Arduino SETUP code ----------------------
125 void setup(){
126 pinMode(13, OUTPUT); // led
127
128 pinMode(2, OUTPUT); // s0
129 pinMode(3, OUTPUT); // s1
130 pinMode(4, OUTPUT); // s2
131 pinMode(5, OUTPUT); // e
132
133 lcd.begin(16,2);
134 lcd.print("Starting....");
135
136 Serial.begin(9600);
137 Serial.println("Starting....");
138 delay(500);
139 read_settings();
140 scan_keys();
141 if ( keys[KEY_UP])
142 calibrate();
143
144 pinMode(A5, OUTPUT); // PPM output pin
145 do_channel = false;
146 set_timer( seplength );
147 Timer1.initialize(framelength);
148 Timer1.attachInterrupt(ISR_timer);
149
150 displaystate = VALUES;
151
152 // Arduino believes all pins on Port C are Analog.
153 // In reality they are tri-purpose; ADC, Digital, Digital Interrupts
154 // Unfortunately the interrupt mode is unusable in this scenario, but digital I/O works :P
155 pinMode(A2, INPUT);
156 digitalWrite(A2, HIGH);
157
158 // Debugging: how long does the main loop take on avg...
159 t = micros();
160 avg_loop_time = t;
161 prev_loop_time = t;
162
163 // Setting this here to be sure I do not forget to init' it....
164 // These initializations should be done by read_settings from eeprom,
165 // and this "default model values" should probably be moved
166 // out to a section of read_settings when handling "new model", or
167 // to a separate model_defaults function...
168 model.channels = 8;
169 model.rev[0] = model.rev[1] = model.rev[2] = model.rev[3] =
170 model.rev[4] = model.rev[5] = model.rev[6] = model.rev[7] = false;
171 model.dr[0] = model.dr[1] = model.dr[2] = model.dr[3] = 0;
172 model.dr[4] = model.dr[5] = model.dr[6] = model.dr[7] = 100;
173
174 // Initializing the stopwatch timer/clock values...
175 clock_timer = (clock_timer_t){0, 0, 0, false};
176 }
177
178 // ---------- Arduino main loop -----------------------
179 void loop () {
180
181 // Determine if the UI needs to run...
182 boolean disp;
183 if ( millis() - last > UI_INTERVAL ) {
184 last = millis();
185 disp = true;
186 }
187 else disp = false;
188
189 process_inputs();
190
191 // Wasting a full I/O pin on battery status monitoring!
192 battery_val = analogRead(1) * BATTERY_CONV;
193 if ( battery_val < BATTERY_LOW ) {
194 digitalWrite(13, 1); // Simulate alarm :P
195 displaystate = BATTERY;
196 }
197
198 if ( disp )
199 {
200 ui_handler();
201 }
202 if ( displaystate != MENU )
203 {
204 // Debugging: how long does the main loop take on avg,
205 // when not handling the UI...
206 t = micros();
207 avg_loop_time = ( t - prev_loop_time + avg_loop_time ) / 2;
208 prev_loop_time = t;
209 }
210
211 // Whoa! Slow down partner! Let everything settle down before proceeding.
212 delay(5);
213 }
214
215 // ----- Simple support functions used by more complex functions ----
216
217 void set_ppm_output( bool state )
218 {
219 digitalWrite(A5, state); // Hard coded PPM output
220 }
221
222 void set_timer(long time)
223 {
224 Timer1.detachInterrupt();
225 Timer1.attachInterrupt(ISR_timer, time);
226 }
227
228 boolean check_key( int key)
229 {
230 return ( !keys[key] && prev_keys[key] );
231 }
232
233 void mplx_select(int pin)
234 {
235 digitalWrite(5, 1);
236 delayMicroseconds(24);
237
238 digitalWrite(2, bitRead(pin,0)); // Arduino alias for non-modifying bitshift operation
239 digitalWrite(3, bitRead(pin,1)); // us used to extract individual bits from the int (0..7)
240 digitalWrite(4, bitRead(pin,2)); // Select the appropriate input by setting s1,s2,s3 and e
241 digitalWrite(5, 0); // on the 4051 multiplexer.
242
243 // May need to slow the following read down to be able to
244 // get fully reliable values from the 4051 multiplex.
245 delayMicroseconds(24);
246
247 }
248
249 // ----- "Complex" functions follow ---------------------------------
250
251 void calibrate()
252 {
253 int i, r0, r1, r2, adc_in;
254 int calcount = 0;
255 int num_calibrations = 200;
256
257 lcd.clear();
258 lcd.print("Move controls to");
259 lcd.setCursor(0,1);
260 lcd.print("their extremes..");
261 Serial.print("Calibration. Move all controls to their extremes.");
262
263 for (i=0; i< MAX_INPUTS; i++) {
264 input_cal.min[i] = 1024;
265 input_cal.max[i] = 0;
266 }
267 while ( calcount <= num_calibrations )
268 {
269 for (i=0; i<=MAX_INPUTS; i++) {
270 mplx_select(i);
271 adc_in = analogRead(0);
272
273 // Naive min/max calibration
274 if ( adc_in < input_cal.min[i] ) {
275 input_cal.min[i] = adc_in;
276 }
277 if ( adc_in > input_cal.max[i] ) {
278 input_cal.max[i] = adc_in;
279 }
280 delay(10);
281 }
282
283 calcount++;
284 }
285
286 // TODO: WILL need to do center-point calibration after min-max...
287
288 lcd.clear();
289 lcd.print("Done calibrating");
290
291 Serial.print("Done calibrating");
292 delay(2000);
293 }
294
295 void read_settings(void)
296 {
297 // Dummy. Will be modified to read model settings from EEPROM
298 for (int i=0; i<=7; i++) {
299 input_cal.min[i] = 0;
300 input_cal.center[i] = 512;
301 input_cal.max[i] = 1024;
302 }
303 }
304
305 void write_settings(void)
306 {
307 // Dummy. Not used anywhere. Will be fleshed out to save settings to EEPROM.
308 }
309
310 void scan_keys ( void )
311 {
312 int i, r0, r1, r2;
313 boolean key_in;
314
315 // To get more inputs, another 4051 analog multiplexer is used,
316 // but this time it is used for digital inputs. 8 digital inputs
317 // on one input line, as long as proper debouncing and filtering
318 // is done in hardware :P
319 for (i=0; i<=7; i++) {
320 // To be able to detect that a key has changed state, preserve the previous..
321 prev_keys[i] = keys[i];
322
323 // Select and read input.
324 mplx_select(i);
325 keys[i] = digitalRead(A2);
326 delay(2);
327 }
328 }
329
330
331 void process_inputs(void )
332 {
333 int current_input, r0, r1, r2, adc_in;
334 for (current_input=0; current_input<=7; current_input++) {
335
336 mplx_select(current_input);
337 adc_in = analogRead(0);
338
339 model.stick[current_input] = ((float)adc_in - (float)input_cal.min[current_input]) / (float)(input_cal.max[current_input]-input_cal.min[current_input]);
340 if ( model.rev[current_input] ) model.stick[current_input] = 1.0f - model.stick[current_input];
341 }
342 }
343
344
345 void ISR_timer(void)
346 {
347 Timer1.stop(); // Make sure we do not run twice while working :P
348
349 if ( !do_channel )
350 {
351 set_ppm_output( LOW );
352 sum += seplength;
353 do_channel = true;
354 set_timer(seplength);
355 return;
356 }
357
358 if ( cchannel >= model.channels )
359 {
360 set_ppm_output( HIGH );
361 long framesep = framelength - sum;
362
363 sum = 0;
364 do_channel = false;
365 cchannel = 0;
366 set_timer ( framesep );
367 return;
368 }
369
370 if ( do_channel )
371 {
372 set_ppm_output( HIGH );
373 long next_timer = (( chwidht * model.stick[cchannel] ) + chmin);
374 // Do sanity-check of next_timer compared to chmax ...
375 while ( chmax < next_timer ) next_timer--;
376 sum += next_timer;
377
378 // Done with channel separator and value,
379 // prepare for next channel...
380 cchannel++;
381 do_channel = false;
382 set_timer ( next_timer );
383 return;
384 }
385 }
386
387 void serial_debug()
388 {
389 int current_input;
390 for (current_input=0; current_input<=7; current_input++) {
391 int v = (int)(model.stick[current_input] * 100);
392
393 Serial.print("Input #");
394 Serial.print(current_input);
395 Serial.print(" value: ");
396 Serial.print(model.stick[current_input]);
397 Serial.print(" pct: ");
398 Serial.print(v);
399 Serial.print(" min: ");
400 Serial.print(input_cal.min[current_input]);
401 Serial.print(" max: ");
402 Serial.print(input_cal.max[current_input]);
403 Serial.println();
404 }
405 Serial.print("Battery level is: ");
406 Serial.println(battery_val);
407
408 Serial.print("Average loop time:");
409 Serial.println(avg_loop_time);
410
411 Serial.println();
412 }
413 void dr_inputselect( int no, int in )
414 {
415 if ( model.dr[menu_substate] < 0 ) model.dr[menu_substate] = 4;
416 if ( model.dr[menu_substate] > 4 ) model.dr[menu_substate] = 0;
417
418 lcd.setCursor(0 , 0);
419 lcd.print("D/R switch ");
420 lcd.print( no + 1 );
421 lcd.print(" ");
422 lcd.setCursor(0 , 1);
423 lcd.print("Input ");
424 lcd.print(in+1);
425
426 lcd.print(": ");
427 if ( ! model.dr[menu_substate] ) lcd.print("Off");
428 else lcd.print(model.dr[menu_substate]);
429
430 if ( check_key(KEY_INC) ) {
431 model.dr[menu_substate]++;
432 return;
433 }
434 else if ( check_key(KEY_DEC) ) {
435 model.dr[menu_substate]--;
436 return;
437 }
438 // Wrap around.
439 return;
440
441 }
442
443 void dr_value()
444 {
445 int pos;
446 int state;
447
448 if ( menu_substate == 4) state = keys[KEY_DR1];
449 else state = keys[KEY_DR2];
450
451 pos = 4 + (menu_substate - 4) * 2;
452 if (state) pos++;
453
454 lcd.setCursor(0 , 0);
455 lcd.print("D/R switch ");
456 lcd.print( menu_substate - 3 );
457 lcd.print(" ");
458 lcd.setCursor(0 , 1);
459 lcd.print( state ? "HI" : "LO" );
460 lcd.print(" Value :");
461
462 lcd.print( model.dr[pos] );
463
464 if ( !keys[KEY_INC] ) {
465 if ( model.dr[pos] < 100) model.dr[pos] += 5;
466 return;
467 }
468 else if ( !keys[KEY_DEC] ) {
469 if ( model.dr[pos] > -100) model.dr[pos] -= 5;
470 return;
471 }
472
473 return;
474 }
475 void ui_handler()
476 {
477 int row;
478 int col;
479 scan_keys();
480
481 if ( displaystate != MENU )
482 {
483 menu_substate = 0;
484 if ( check_key(KEY_UP) && displaystate == VALUES ) {
485 displaystate = BATTERY;
486 return;
487 }
488 else if ( check_key(KEY_UP) && displaystate == BATTERY ) {
489 displaystate = TIMER;
490 return;
491 }
492 else if ( check_key(KEY_UP) && displaystate == TIMER ) {
493 displaystate = VALUES;
494 return;
495 }
496
497 else if ( check_key(KEY_DOWN) ) {
498 displaystate = MENU;
499 return;
500 }
501 }
502
503 digitalWrite(13, digitalRead(13) ^ 1 );
504
505 switch ( displaystate )
506 {
507 case VALUES:
508 int current_input;
509 for (current_input=0; current_input<=7; current_input++) {
510 // In channel value display, do a simple calc
511 // of the LCD row & column location. With 8 channels
512 // we can fit eight channels as percentage values on
513 // a simple 16x2 display...
514 if ( current_input < 4 )
515 {
516 col = current_input * 4;
517 row = 0;
518 }
519 else
520 {
521 col = (current_input-4) * 4;
522 row = 1;
523 }
524 // Overwriting the needed positions with
525 // blanks cause less display-flicker than
526 // actually clearing the display...
527 lcd.setCursor(col, row);
528 lcd.print(" ");
529 lcd.setCursor(col, row);
530 // Display uses percents, while PPM uses ratio....
531 int v = (int)(model.stick[current_input] * 100);
532 lcd.print(v);
533 }
534 break;
535
536
537 case BATTERY:
538 lcd.clear();
539 lcd.print("Battery level: ");
540 lcd.setCursor(0 , 1);
541 lcd.print( (float)battery_val/10);
542 lcd.print("V");
543 if ( battery_val < BATTERY_LOW ) lcd.print(" - WARNING");
544 else lcd.print(" - OK");
545 break;
546
547
548
549 case TIMER:
550 unsigned long delta;
551 int hours;
552 int minutes;
553 int seconds;
554
555 lcd.clear();
556 lcd.print("Timer: ");
557 lcd.print( clock_timer.running ? "Running" : "Stopped" );
558 lcd.setCursor(5 , 1);
559 if ( clock_timer.running )
560 {
561 clock_timer.value = millis() - (clock_timer.start + clock_timer.init);
562 }
563 hours = ( clock_timer.value / 1000 ) / 3600;
564 clock_timer.value = clock_timer.value % 3600000;
565 minutes = ( clock_timer.value / 1000 ) / 60;
566 seconds = ( clock_timer.value / 1000 ) % 60;
567 if ( hours ) {
568 lcd.print(hours);
569 lcd.print(":");
570 }
571 if ( minutes < 10 ) lcd.print("0");
572 lcd.print( minutes );
573 lcd.print(":");
574 if ( seconds < 10 ) lcd.print("0");
575 lcd.print( seconds );
576
577 if ( check_key(KEY_INC) ) {
578 if ( !clock_timer.running && !clock_timer.start )
579 {
580 clock_timer.start = millis();
581 clock_timer.value = 0;
582 clock_timer.running = true;
583 } else if ( !clock_timer.running && clock_timer.start ) {
584 clock_timer.start = millis() - clock_timer.value;
585 clock_timer.running = true;
586 } else if ( clock_timer.running ) {
587 clock_timer.running = false;
588 }
589 return;
590 } else if ( check_key(KEY_DEC) ) {
591 if ( !clock_timer.running && clock_timer.start ) {
592 clock_timer.value = 0;
593 clock_timer.start = 0;
594 clock_timer.init = 0;
595 }
596 return;
597 }
598 break;
599
600 case MENU:
601 lcd.clear();
602 switch ( menu_mainstate )
603 {
604 case TOP:
605 lcd.print("In MENU mode!");
606 lcd.setCursor(0 , 1);
607 lcd.print("Esc UP. Scrl DN.");
608 menu_substate = 0;
609 if ( check_key(KEY_UP) ) {
610 displaystate = VALUES;
611 return;
612 }
613 else if ( check_key(KEY_DOWN) ) {
614 menu_mainstate = INVERTS;
615 return;
616 }
617 break;
618
619
620 case INVERTS:
621 if ( menu_substate >= model.channels ) menu_substate = 0;
622 if ( menu_substate < 0) menu_substate = (model.channels - 1);
623 lcd.print("Channel invert");
624 lcd.setCursor(0 , 1);
625 lcd.print("Ch ");
626 lcd.print(menu_substate+1);
627 lcd.print( (model.rev[menu_substate] ? ": Invert" : ": Normal"));
628
629 if ( check_key(KEY_UP) ) {
630 menu_mainstate = TOP;
631 return;
632 }
633 else if ( check_key(KEY_DOWN) ) {
634 menu_mainstate = DUALRATES;
635 return;
636 }
637
638 if ( check_key(KEY_RIGHT) ) {
639 menu_substate++;
640 return;
641 }
642 else if ( check_key(KEY_LEFT) ) {
643 menu_substate--;
644 return;
645 }
646 else if ( check_key(KEY_INC) || check_key(KEY_DEC) ) {
647 model.rev[menu_substate] ^= 1;
648 return;
649 }
650 break;
651
652 case DUALRATES:
653 if ( menu_substate > 5 ) menu_substate = 0;
654 if ( menu_substate < 0) menu_substate = 5;
655
656 if ( check_key(KEY_UP) ) {
657 menu_mainstate = INVERTS;
658 return;
659 }
660 if ( check_key(KEY_DOWN) ) {
661 menu_mainstate = EXPOS;
662 return;
663 }
664 if ( check_key(KEY_RIGHT) ) {
665 menu_substate++;
666 return;
667 }
668 else if ( check_key(KEY_LEFT) ) {
669 menu_substate--;
670 return;
671 }
672 switch (menu_substate)
673 {
674 case 0:
675 dr_inputselect(0, 0);
676 return;
677 case 1:
678 dr_inputselect(0, 1);
679 return;
680 case 2:
681 dr_inputselect(1, 0);
682 return;
683 case 3:
684 dr_inputselect(1, 1);
685 return;
686 case 4:
687 case 5:
688 dr_value();
689 return;
690 default:
691 menu_substate = 0;
692 break;
693 }
694 break;
695
696 case EXPOS:
697 //________________
698 lcd.print("Input expo curve");
699 lcd.setCursor(0 , 1);
700 lcd.print("Not implemented");
701 // Possible, if input values are mapped to +/- 100 rather than 0..1 ..
702 // plot ( x*(1 - 1.0*cos (x/(20*PI)) )) 0 to 100
703 // Run in wolfram to see result, adjust the 1.0 factor to inc/red effect.
704 // Problem: -100 to 100 is terribly bad presicion, esp. considering that
705 // the values started as 0...1024, and we have 1000usec to "spend" on channels.
706 if ( check_key(KEY_UP ) ) {
707 menu_mainstate = DUALRATES;
708 return;
709 }
710 if ( check_key(KEY_DOWN ) ) {
711 menu_mainstate = DEBUG;
712 return;
713 }
714 break;
715
716 case DEBUG:
717 lcd.setCursor(0 , 0);
718 lcd.print("Dumping debug to");
719 lcd.setCursor(0 , 1);
720 lcd.print("serial port 0");
721 serial_debug();
722 if ( check_key(KEY_UP ) ) {
723 // FIXME: Remember to update the "Scroll up" state!
724 menu_mainstate = EXPOS;
725 return;
726 } else if ( check_key(KEY_DOWN ) ) {
727 menu_mainstate = SAVE;
728 return;
729 }
730 break;
731
732 default:
733 lcd.print("Not implemented");
734 lcd.setCursor(0 , 1);
735 lcd.print("Press DOWN...");
736 if ( check_key(KEY_DOWN ) ) menu_mainstate = TOP;
737 }
738 break;
739
740
741 default:
742 // Invalid
743 return;
744 }
745
746 return;
747 }
748
749
750
751
752