]> git.defcon.no Git - rctxduino/blob - source/RCTXDuino/RCTXDuino.pde
Mainly data-structure changes:
[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
157 // Debugging: how long does the main loop take on avg...
158 t = micros();
159 avg_loop_time = t;
160 prev_loop_time = t;
161
162 // Setting this here to be sure I do not forget to init' it....
163 // These initializations should be done by read_settings from eeprom,
164 // and this "default model values" should probably be moved
165 // out to a section of read_settings when handling "new model", or
166 // to a separate model_defaults function...
167 model.channels = 8;
168 model.rev[0] = model.rev[1] = model.rev[2] = model.rev[3] =
169 model.rev[4] = model.rev[5] = model.rev[6] = model.rev[7] = false;
170 model.dr[0] = model.dr[1] = model.dr[2] = model.dr[3] = 0;
171 model.dr[4] = model.dr[5] = model.dr[6] = model.dr[7] = 100;
172
173 // Initializing the stopwatch timer/clock values...
174 clock_timer = (clock_timer_t){0, 0, 0, false};
175 }
176
177 // ---------- Arduino main loop -----------------------
178 void loop () {
179
180 // Determine if the UI needs to run...
181 boolean disp;
182 if ( millis() - last > UI_INTERVAL ) {
183 last = millis();
184 disp = true;
185 }
186 else disp = false;
187
188 process_inputs();
189
190 // Wasting a full I/O pin on battery status monitoring!
191 battery_val = analogRead(1) * BATTERY_CONV;
192 if ( battery_val < BATTERY_LOW ) {
193 digitalWrite(13, 1); // Simulate alarm :P
194 displaystate = BATTERY;
195 }
196
197 if ( disp )
198 {
199 ui_handler();
200 }
201 if ( displaystate != MENU )
202 {
203 // Debugging: how long does the main loop take on avg,
204 // when not handling the UI...
205 t = micros();
206 avg_loop_time = ( t - prev_loop_time + avg_loop_time ) / 2;
207 prev_loop_time = t;
208 }
209
210 // Whoa! Slow down partner! Let everything settle down before proceeding.
211 delay(5);
212 }
213
214 // ----- Simple support functions used by more complex functions ----
215
216 void set_ppm_output( bool state )
217 {
218 digitalWrite(A5, state); // Hard coded PPM output
219 }
220
221 void set_timer(long time)
222 {
223 Timer1.detachInterrupt();
224 Timer1.attachInterrupt(ISR_timer, time);
225 }
226
227 boolean check_key( int key)
228 {
229 return ( keys[key] && !prev_keys[key] );
230 }
231
232 void mplx_select(int pin)
233 {
234 digitalWrite(5, 1);
235 delayMicroseconds(24);
236
237 digitalWrite(2, bitRead(pin,0)); // Arduino alias for non-modifying bitshift operation
238 digitalWrite(3, bitRead(pin,1)); // us used to extract individual bits from the int (0..7)
239 digitalWrite(4, bitRead(pin,2)); // Select the appropriate input by setting s1,s2,s3 and e
240 digitalWrite(5, 0); // on the 4051 multiplexer.
241
242 // May need to slow the following read down to be able to
243 // get fully reliable values from the 4051 multiplex.
244 delayMicroseconds(24);
245
246 }
247
248 // ----- "Complex" functions follow ---------------------------------
249
250 void calibrate()
251 {
252 int i, r0, r1, r2, adc_in;
253 int calcount = 0;
254 int num_calibrations = 200;
255
256 lcd.clear();
257 lcd.print("Move controls to");
258 lcd.setCursor(0,1);
259 lcd.print("their extremes..");
260 Serial.print("Calibration. Move all controls to their extremes.");
261
262 for (i=0; i< MAX_INPUTS; i++) {
263 input_cal.min[i] = 1024;
264 input_cal.max[i] = 0;
265 }
266 while ( calcount <= num_calibrations )
267 {
268 for (i=0; i<=MAX_INPUTS; i++) {
269 mplx_select(i);
270 adc_in = analogRead(0);
271
272 // Naive min/max calibration
273 if ( adc_in < input_cal.min[i] ) {
274 input_cal.min[i] = adc_in;
275 }
276 if ( adc_in > input_cal.max[i] ) {
277 input_cal.max[i] = adc_in;
278 }
279 delay(10);
280 }
281
282 calcount++;
283 }
284
285 // TODO: WILL need to do center-point calibration after min-max...
286
287 lcd.clear();
288 lcd.print("Done calibrating");
289
290 Serial.print("Done calibrating");
291 delay(2000);
292 }
293
294 void read_settings(void)
295 {
296 // Dummy. Will be modified to read model settings from EEPROM
297 for (int i=0; i<=7; i++) {
298 input_cal.min[i] = 0;
299 input_cal.center[i] = 512;
300 input_cal.max[i] = 1024;
301 }
302 }
303
304 void write_settings(void)
305 {
306 // Dummy. Not used anywhere. Will be fleshed out to save settings to EEPROM.
307 }
308
309 void scan_keys ( void )
310 {
311 int i, r0, r1, r2;
312 boolean key_in;
313
314 // To get more inputs, another 4051 analog multiplexer is used,
315 // but this time it is used for digital inputs. 8 digital inputs
316 // on one input line, as long as proper debouncing and filtering
317 // is done in hardware :P
318 for (i=0; i<=7; i++) {
319 // To be able to detect that a key has changed state, preserve the previous..
320 prev_keys[i] = keys[i];
321
322 // Select and read input.
323 mplx_select(i);
324 keys[i] = digitalRead(A2);
325 delay(2);
326 }
327 }
328
329
330 void process_inputs(void )
331 {
332 int current_input, r0, r1, r2, adc_in;
333 for (current_input=0; current_input<=7; current_input++) {
334
335 mplx_select(current_input);
336 adc_in = analogRead(0);
337
338 model.stick[current_input] = ((float)adc_in - (float)input_cal.min[current_input]) / (float)(input_cal.max[current_input]-input_cal.min[current_input]);
339 if ( model.rev[current_input] ) model.stick[current_input] = 1.0f - model.stick[current_input];
340 }
341 }
342
343
344 void ISR_timer(void)
345 {
346 Timer1.stop(); // Make sure we do not run twice while working :P
347
348 if ( !do_channel )
349 {
350 set_ppm_output( LOW );
351 sum += seplength;
352 do_channel = true;
353 set_timer(seplength);
354 return;
355 }
356
357 if ( cchannel >= model.channels )
358 {
359 set_ppm_output( HIGH );
360 long framesep = framelength - sum;
361
362 sum = 0;
363 do_channel = false;
364 cchannel = 0;
365 set_timer ( framesep );
366 return;
367 }
368
369 if ( do_channel )
370 {
371 set_ppm_output( HIGH );
372 long next_timer = (( chwidht * model.stick[cchannel] ) + chmin);
373 // Do sanity-check of next_timer compared to chmax ...
374 while ( chmax < next_timer ) next_timer--;
375 sum += next_timer;
376
377 // Done with channel separator and value,
378 // prepare for next channel...
379 cchannel++;
380 do_channel = false;
381 set_timer ( next_timer );
382 return;
383 }
384 }
385
386 void serial_debug()
387 {
388 int current_input;
389 for (current_input=0; current_input<=7; current_input++) {
390 int v = (int)(model.stick[current_input] * 100);
391
392 Serial.print("Input #");
393 Serial.print(current_input);
394 Serial.print(" value: ");
395 Serial.print(model.stick[current_input]);
396 Serial.print(" pct: ");
397 Serial.print(v);
398 Serial.print(" min: ");
399 Serial.print(input_cal.min[current_input]);
400 Serial.print(" max: ");
401 Serial.print(input_cal.max[current_input]);
402 Serial.println();
403 }
404 Serial.print("Battery level is: ");
405 Serial.println(battery_val);
406
407 Serial.print("Average loop time:");
408 Serial.println(avg_loop_time);
409
410 Serial.println();
411 }
412 void dr_inputselect( int no, int in )
413 {
414 if ( model.dr[menu_substate] < 0 ) model.dr[menu_substate] = 4;
415 if ( model.dr[menu_substate] > 4 ) model.dr[menu_substate] = 0;
416
417 lcd.setCursor(0 , 0);
418 lcd.print("D/R switch ");
419 lcd.print( no + 1 );
420 lcd.print(" ");
421 lcd.setCursor(0 , 1);
422 lcd.print("Input ");
423 lcd.print(in+1);
424
425 lcd.print(": ");
426 if ( ! model.dr[menu_substate] ) lcd.print("Off");
427 else lcd.print(model.dr[menu_substate]);
428
429 if ( check_key(KEY_INC) ) {
430 model.dr[menu_substate]++;
431 return;
432 }
433 else if ( check_key(KEY_DEC) ) {
434 model.dr[menu_substate]--;
435 return;
436 }
437 // Wrap around.
438 return;
439
440 }
441
442 void dr_value()
443 {
444 int pos;
445 int state;
446
447 if ( menu_substate == 4) state = keys[KEY_DR1];
448 else state = keys[KEY_DR2];
449
450 pos = 4 + (menu_substate - 4) * 2;
451 if (state) pos++;
452
453 lcd.setCursor(0 , 0);
454 lcd.print("D/R switch ");
455 lcd.print( menu_substate - 3 );
456 lcd.print(" ");
457 lcd.setCursor(0 , 1);
458 lcd.print( state ? "HI" : "LO" );
459 lcd.print(" Value :");
460
461 lcd.print( model.dr[pos] );
462
463 if ( keys[KEY_INC] ) {
464 if ( model.dr[pos] < 100) model.dr[pos] += 5;
465 return;
466 }
467 else if ( keys[KEY_DEC] ) {
468 if ( model.dr[pos] > -100) model.dr[pos] -= 5;
469 return;
470 }
471
472 return;
473 }
474 void ui_handler()
475 {
476 int row;
477 int col;
478 scan_keys();
479
480 if ( displaystate != MENU )
481 {
482 menu_substate = 0;
483 if ( check_key(KEY_UP) && displaystate == VALUES ) {
484 displaystate = BATTERY;
485 return;
486 }
487 else if ( check_key(KEY_UP) && displaystate == BATTERY ) {
488 displaystate = TIMER;
489 return;
490 }
491 else if ( check_key(KEY_UP) && displaystate == TIMER ) {
492 displaystate = VALUES;
493 return;
494 }
495
496 else if ( check_key(KEY_DOWN) ) {
497 displaystate = MENU;
498 return;
499 }
500 }
501
502 digitalWrite(13, digitalRead(13) ^ 1 );
503
504 switch ( displaystate )
505 {
506 case VALUES:
507 int current_input;
508 for (current_input=0; current_input<=7; current_input++) {
509 // In channel value display, do a simple calc
510 // of the LCD row & column location. With 8 channels
511 // we can fit eight channels as percentage values on
512 // a simple 16x2 display...
513 if ( current_input < 4 )
514 {
515 col = current_input * 4;
516 row = 0;
517 }
518 else
519 {
520 col = (current_input-4) * 4;
521 row = 1;
522 }
523 // Overwriting the needed positions with
524 // blanks cause less display-flicker than
525 // actually clearing the display...
526 lcd.setCursor(col, row);
527 lcd.print(" ");
528 lcd.setCursor(col, row);
529 // Display uses percents, while PPM uses ratio....
530 int v = (int)(model.stick[current_input] * 100);
531 lcd.print(v);
532 }
533 break;
534
535
536 case BATTERY:
537 lcd.clear();
538 lcd.print("Battery level: ");
539 lcd.setCursor(0 , 1);
540 lcd.print( (float)battery_val/10);
541 lcd.print("V");
542 if ( battery_val < BATTERY_LOW ) lcd.print(" - WARNING");
543 else lcd.print(" - OK");
544 break;
545
546
547
548 case TIMER:
549 unsigned long delta;
550 int hours;
551 int minutes;
552 int seconds;
553
554 lcd.clear();
555 lcd.print("Timer: ");
556 lcd.print( clock_timer.running ? "Running" : "Stopped" );
557 lcd.setCursor(5 , 1);
558 if ( clock_timer.running )
559 {
560 clock_timer.value = millis() - (clock_timer.start + clock_timer.init);
561 }
562 hours = ( clock_timer.value / 1000 ) / 3600;
563 clock_timer.value = clock_timer.value % 3600000;
564 minutes = ( clock_timer.value / 1000 ) / 60;
565 seconds = ( clock_timer.value / 1000 ) % 60;
566 if ( hours ) {
567 lcd.print(hours);
568 lcd.print(":");
569 }
570 if ( minutes < 10 ) lcd.print("0");
571 lcd.print( minutes );
572 lcd.print(":");
573 if ( seconds < 10 ) lcd.print("0");
574 lcd.print( seconds );
575
576 if ( check_key(KEY_INC) ) {
577 if ( !clock_timer.running && !clock_timer.start )
578 {
579 clock_timer.start = millis();
580 clock_timer.value = 0;
581 clock_timer.running = true;
582 } else if ( !clock_timer.running && clock_timer.start ) {
583 clock_timer.start = millis() - clock_timer.value;
584 clock_timer.running = true;
585 } else if ( clock_timer.running ) {
586 clock_timer.running = false;
587 }
588 return;
589 } else if ( check_key(KEY_DEC) ) {
590 if ( !clock_timer.running && clock_timer.start ) {
591 clock_timer.value = 0;
592 clock_timer.start = 0;
593 clock_timer.init = 0;
594 }
595 return;
596 }
597 break;
598
599 case MENU:
600 lcd.clear();
601 switch ( menu_mainstate )
602 {
603 case TOP:
604 lcd.print("In MENU mode!");
605 lcd.setCursor(0 , 1);
606 lcd.print("Esc UP. Scrl DN.");
607 menu_substate = 0;
608 if ( check_key(KEY_UP) ) {
609 displaystate = VALUES;
610 return;
611 }
612 else if ( check_key(KEY_DOWN) ) {
613 menu_mainstate = INVERTS;
614 return;
615 }
616 break;
617
618
619 case INVERTS:
620 if ( menu_substate >= model.channels ) menu_substate = 0;
621 if ( menu_substate < 0) menu_substate = (model.channels - 1);
622 lcd.print("Channel invert");
623 lcd.setCursor(0 , 1);
624 lcd.print("Ch ");
625 lcd.print(menu_substate+1);
626 lcd.print( (model.rev[menu_substate] ? ": Invert" : ": Normal"));
627
628 if ( check_key(KEY_UP) ) {
629 menu_mainstate = TOP;
630 return;
631 }
632 else if ( check_key(KEY_DOWN) ) {
633 menu_mainstate = DUALRATES;
634 return;
635 }
636
637 if ( check_key(KEY_RIGHT) ) {
638 menu_substate++;
639 return;
640 }
641 else if ( check_key(KEY_LEFT) ) {
642 menu_substate--;
643 return;
644 }
645 else if ( check_key(KEY_INC) || check_key(KEY_DEC) ) {
646 model.rev[menu_substate] ^= 1;
647 return;
648 }
649 break;
650
651 case DUALRATES:
652 if ( menu_substate > 5 ) menu_substate = 0;
653 if ( menu_substate < 0) menu_substate = 5;
654
655 if ( check_key(KEY_UP) ) {
656 menu_mainstate = INVERTS;
657 return;
658 }
659 if ( check_key(KEY_DOWN) ) {
660 menu_mainstate = EXPOS;
661 return;
662 }
663 if ( check_key(KEY_RIGHT) ) {
664 menu_substate++;
665 return;
666 }
667 else if ( check_key(KEY_LEFT) ) {
668 menu_substate--;
669 return;
670 }
671 switch (menu_substate)
672 {
673 case 0:
674 dr_inputselect(0, 0);
675 return;
676 case 1:
677 dr_inputselect(0, 1);
678 return;
679 case 2:
680 dr_inputselect(1, 0);
681 return;
682 case 3:
683 dr_inputselect(1, 1);
684 return;
685 case 4:
686 case 5:
687 dr_value();
688 return;
689 default:
690 menu_substate = 0;
691 break;
692 }
693 break;
694
695 case EXPOS:
696 //________________
697 lcd.print("Input expo curve");
698 lcd.setCursor(0 , 1);
699 lcd.print("Not implemented");
700 // Possible, if input values are mapped to +/- 100 rather than 0..1 ..
701 // plot ( x*(1 - 1.0*cos (x/(20*PI)) )) 0 to 100
702 // Run in wolfram to see result, adjust the 1.0 factor to inc/red effect.
703 // Problem: -100 to 100 is terribly bad presicion, esp. considering that
704 // the values started as 0...1024, and we have 1000usec to "spend" on channels.
705 if ( check_key(KEY_UP ) ) {
706 menu_mainstate = DUALRATES;
707 return;
708 }
709 if ( check_key(KEY_DOWN ) ) {
710 menu_mainstate = DEBUG;
711 return;
712 }
713 break;
714
715 case DEBUG:
716 lcd.setCursor(0 , 0);
717 lcd.print("Dumping debug to");
718 lcd.setCursor(0 , 1);
719 lcd.print("serial port 0");
720 serial_debug();
721 if ( check_key(KEY_UP ) ) {
722 // FIXME: Remember to update the "Scroll up" state!
723 menu_mainstate = EXPOS;
724 return;
725 } else if ( check_key(KEY_DOWN ) ) {
726 menu_mainstate = SAVE;
727 return;
728 }
729 break;
730
731 default:
732 lcd.print("Not implemented");
733 lcd.setCursor(0 , 1);
734 lcd.print("Press DOWN...");
735 if ( check_key(KEY_DOWN ) ) menu_mainstate = TOP;
736 }
737 break;
738
739
740 default:
741 // Invalid
742 return;
743 }
744
745 return;
746 }
747
748
749
750
751