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