]> git.defcon.no Git - rctxduino/blob - source/RCTXDuino/RCTXDuino.pde
Trivial change: Comments preparing for value-change on model_t.stick[]
[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 // TODO: New format on stick values
340 model.stick[current_input] = ((float)adc_in - (float)input_cal.min[current_input]) / (float)(input_cal.max[current_input]-input_cal.min[current_input]);
341 if ( model.rev[current_input] ) model.stick[current_input] = 1.0f - model.stick[current_input];
342 }
343 }
344
345
346 void ISR_timer(void)
347 {
348 Timer1.stop(); // Make sure we do not run twice while working :P
349
350 if ( !do_channel )
351 {
352 set_ppm_output( LOW );
353 sum += seplength;
354 do_channel = true;
355 set_timer(seplength);
356 return;
357 }
358
359 if ( cchannel >= model.channels )
360 {
361 set_ppm_output( HIGH );
362 long framesep = framelength - sum;
363
364 sum = 0;
365 do_channel = false;
366 cchannel = 0;
367 set_timer ( framesep );
368 return;
369 }
370
371 if ( do_channel )
372 {
373 set_ppm_output( HIGH );
374 // TODO: New format on stick values
375 long next_timer = (( chwidht * model.stick[cchannel] ) + chmin);
376 // Do sanity-check of next_timer compared to chmax ...
377 while ( chmax < next_timer ) next_timer--;
378 sum += next_timer;
379
380 // Done with channel separator and value,
381 // prepare for next channel...
382 cchannel++;
383 do_channel = false;
384 set_timer ( next_timer );
385 return;
386 }
387 }
388
389 void serial_debug()
390 {
391 int current_input;
392 for (current_input=0; current_input<=7; current_input++) {
393 // TODO: New format on stick values
394 int v = (int)(model.stick[current_input] * 100);
395
396 Serial.print("Input #");
397 Serial.print(current_input);
398 Serial.print(" value: ");
399 Serial.print(model.stick[current_input]);
400 Serial.print(" pct: ");
401 Serial.print(v);
402 Serial.print(" min: ");
403 Serial.print(input_cal.min[current_input]);
404 Serial.print(" max: ");
405 Serial.print(input_cal.max[current_input]);
406 Serial.println();
407 }
408 Serial.print("Battery level is: ");
409 Serial.println(battery_val);
410
411 Serial.print("Average loop time:");
412 Serial.println(avg_loop_time);
413
414 Serial.println();
415 }
416 void dr_inputselect( int no, int in )
417 {
418 if ( model.dr[menu_substate] < 0 ) model.dr[menu_substate] = 4;
419 if ( model.dr[menu_substate] > 4 ) model.dr[menu_substate] = 0;
420
421 lcd.setCursor(0 , 0);
422 lcd.print("D/R switch ");
423 lcd.print( no + 1 );
424 lcd.print(" ");
425 lcd.setCursor(0 , 1);
426 lcd.print("Input ");
427 lcd.print(in+1);
428
429 lcd.print(": ");
430 if ( ! model.dr[menu_substate] ) lcd.print("Off");
431 else lcd.print(model.dr[menu_substate]);
432
433 if ( check_key(KEY_INC) ) {
434 model.dr[menu_substate]++;
435 return;
436 }
437 else if ( check_key(KEY_DEC) ) {
438 model.dr[menu_substate]--;
439 return;
440 }
441 // Wrap around.
442 return;
443
444 }
445
446 void dr_value()
447 {
448 int pos;
449 int state;
450
451 if ( menu_substate == 4) state = keys[KEY_DR1];
452 else state = keys[KEY_DR2];
453
454 pos = 4 + (menu_substate - 4) * 2;
455 if (state) pos++;
456
457 lcd.setCursor(0 , 0);
458 lcd.print("D/R switch ");
459 lcd.print( menu_substate - 3 );
460 lcd.print(" ");
461 lcd.setCursor(0 , 1);
462 lcd.print( state ? "HI" : "LO" );
463 lcd.print(" Value :");
464
465 lcd.print( model.dr[pos] );
466
467 if ( !keys[KEY_INC] ) {
468 if ( model.dr[pos] < 100) model.dr[pos] += 5;
469 return;
470 }
471 else if ( !keys[KEY_DEC] ) {
472 if ( model.dr[pos] > -100) model.dr[pos] -= 5;
473 return;
474 }
475
476 return;
477 }
478 void ui_handler()
479 {
480 int row;
481 int col;
482 scan_keys();
483
484 if ( displaystate != MENU )
485 {
486 menu_substate = 0;
487 if ( check_key(KEY_UP) && displaystate == VALUES ) {
488 displaystate = BATTERY;
489 return;
490 }
491 else if ( check_key(KEY_UP) && displaystate == BATTERY ) {
492 displaystate = TIMER;
493 return;
494 }
495 else if ( check_key(KEY_UP) && displaystate == TIMER ) {
496 displaystate = VALUES;
497 return;
498 }
499
500 else if ( check_key(KEY_DOWN) ) {
501 displaystate = MENU;
502 return;
503 }
504 }
505
506 digitalWrite(13, digitalRead(13) ^ 1 );
507
508 switch ( displaystate )
509 {
510 case VALUES:
511 int current_input;
512 for (current_input=0; current_input<=7; current_input++) {
513 // In channel value display, do a simple calc
514 // of the LCD row & column location. With 8 channels
515 // we can fit eight channels as percentage values on
516 // a simple 16x2 display...
517 if ( current_input < 4 )
518 {
519 col = current_input * 4;
520 row = 0;
521 }
522 else
523 {
524 col = (current_input-4) * 4;
525 row = 1;
526 }
527 // Overwriting the needed positions with
528 // blanks cause less display-flicker than
529 // actually clearing the display...
530 lcd.setCursor(col, row);
531 lcd.print(" ");
532 lcd.setCursor(col, row);
533 // Display uses percents, while PPM uses ratio....
534 // TODO: New format on stick values
535 int v = (int)(model.stick[current_input] * 100);
536 lcd.print(v);
537 }
538 break;
539
540
541 case BATTERY:
542 lcd.clear();
543 lcd.print("Battery level: ");
544 lcd.setCursor(0 , 1);
545 lcd.print( (float)battery_val/10);
546 lcd.print("V");
547 if ( battery_val < BATTERY_LOW ) lcd.print(" - WARNING");
548 else lcd.print(" - OK");
549 break;
550
551
552
553 case TIMER:
554 unsigned long delta;
555 int hours;
556 int minutes;
557 int seconds;
558
559 lcd.clear();
560 lcd.print("Timer: ");
561 lcd.print( clock_timer.running ? "Running" : "Stopped" );
562 lcd.setCursor(5 , 1);
563 if ( clock_timer.running )
564 {
565 clock_timer.value = millis() - (clock_timer.start + clock_timer.init);
566 }
567 hours = ( clock_timer.value / 1000 ) / 3600;
568 clock_timer.value = clock_timer.value % 3600000;
569 minutes = ( clock_timer.value / 1000 ) / 60;
570 seconds = ( clock_timer.value / 1000 ) % 60;
571 if ( hours ) {
572 lcd.print(hours);
573 lcd.print(":");
574 }
575 if ( minutes < 10 ) lcd.print("0");
576 lcd.print( minutes );
577 lcd.print(":");
578 if ( seconds < 10 ) lcd.print("0");
579 lcd.print( seconds );
580
581 if ( check_key(KEY_INC) ) {
582 if ( !clock_timer.running && !clock_timer.start )
583 {
584 clock_timer.start = millis();
585 clock_timer.value = 0;
586 clock_timer.running = true;
587 } else if ( !clock_timer.running && clock_timer.start ) {
588 clock_timer.start = millis() - clock_timer.value;
589 clock_timer.running = true;
590 } else if ( clock_timer.running ) {
591 clock_timer.running = false;
592 }
593 return;
594 } else if ( check_key(KEY_DEC) ) {
595 if ( !clock_timer.running && clock_timer.start ) {
596 clock_timer.value = 0;
597 clock_timer.start = 0;
598 clock_timer.init = 0;
599 }
600 return;
601 }
602 break;
603
604 case MENU:
605 lcd.clear();
606 switch ( menu_mainstate )
607 {
608 case TOP:
609 lcd.print("In MENU mode!");
610 lcd.setCursor(0 , 1);
611 lcd.print("Esc UP. Scrl DN.");
612 menu_substate = 0;
613 if ( check_key(KEY_UP) ) {
614 displaystate = VALUES;
615 return;
616 }
617 else if ( check_key(KEY_DOWN) ) {
618 menu_mainstate = INVERTS;
619 return;
620 }
621 break;
622
623
624 case INVERTS:
625 if ( menu_substate >= model.channels ) menu_substate = 0;
626 if ( menu_substate < 0) menu_substate = (model.channels - 1);
627 lcd.print("Channel invert");
628 lcd.setCursor(0 , 1);
629 lcd.print("Ch ");
630 lcd.print(menu_substate+1);
631 lcd.print( (model.rev[menu_substate] ? ": Invert" : ": Normal"));
632
633 if ( check_key(KEY_UP) ) {
634 menu_mainstate = TOP;
635 return;
636 }
637 else if ( check_key(KEY_DOWN) ) {
638 menu_mainstate = DUALRATES;
639 return;
640 }
641
642 if ( check_key(KEY_RIGHT) ) {
643 menu_substate++;
644 return;
645 }
646 else if ( check_key(KEY_LEFT) ) {
647 menu_substate--;
648 return;
649 }
650 else if ( check_key(KEY_INC) || check_key(KEY_DEC) ) {
651 model.rev[menu_substate] ^= 1;
652 return;
653 }
654 break;
655
656 case DUALRATES:
657 if ( menu_substate > 5 ) menu_substate = 0;
658 if ( menu_substate < 0) menu_substate = 5;
659
660 if ( check_key(KEY_UP) ) {
661 menu_mainstate = INVERTS;
662 return;
663 }
664 if ( check_key(KEY_DOWN) ) {
665 menu_mainstate = EXPOS;
666 return;
667 }
668 if ( check_key(KEY_RIGHT) ) {
669 menu_substate++;
670 return;
671 }
672 else if ( check_key(KEY_LEFT) ) {
673 menu_substate--;
674 return;
675 }
676 switch (menu_substate)
677 {
678 case 0:
679 dr_inputselect(0, 0);
680 return;
681 case 1:
682 dr_inputselect(0, 1);
683 return;
684 case 2:
685 dr_inputselect(1, 0);
686 return;
687 case 3:
688 dr_inputselect(1, 1);
689 return;
690 case 4:
691 case 5:
692 dr_value();
693 return;
694 default:
695 menu_substate = 0;
696 break;
697 }
698 break;
699
700 case EXPOS:
701 //________________
702 lcd.print("Input expo curve");
703 lcd.setCursor(0 , 1);
704 lcd.print("Not implemented");
705 // Possible, if input values are mapped to +/- 100 rather than 0..1 ..
706 // plot ( x*(1 - 1.0*cos (x/(20*PI)) )) 0 to 100
707 // Run in wolfram to see result, adjust the 1.0 factor to inc/red effect.
708 // Problem: -100 to 100 is terribly bad presicion, esp. considering that
709 // the values started as 0...1024, and we have 1000usec to "spend" on channels.
710 if ( check_key(KEY_UP ) ) {
711 menu_mainstate = DUALRATES;
712 return;
713 }
714 if ( check_key(KEY_DOWN ) ) {
715 menu_mainstate = DEBUG;
716 return;
717 }
718 break;
719
720 case DEBUG:
721 lcd.setCursor(0 , 0);
722 lcd.print("Dumping debug to");
723 lcd.setCursor(0 , 1);
724 lcd.print("serial port 0");
725 serial_debug();
726 if ( check_key(KEY_UP ) ) {
727 // FIXME: Remember to update the "Scroll up" state!
728 menu_mainstate = EXPOS;
729 return;
730 } else if ( check_key(KEY_DOWN ) ) {
731 menu_mainstate = SAVE;
732 return;
733 }
734 break;
735
736 default:
737 lcd.print("Not implemented");
738 lcd.setCursor(0 , 1);
739 lcd.print("Press DOWN...");
740 if ( check_key(KEY_DOWN ) ) menu_mainstate = TOP;
741 }
742 break;
743
744
745 default:
746 // Invalid
747 return;
748 }
749
750 return;
751 }
752
753
754
755
756