1 #include <LiquidCrystal.h>
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
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
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))
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
35 #define MAX_MODELS 4 // Nice and random number..
38 // --------------- ADC related stuffs.... --------------------
40 struct input_cal_t // Struct type for input calibration values
44 int center[MAX_INPUTS];
46 input_cal_t input_cal;
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.
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.
65 volatile model_t model;
66 unsigned char current_model; // Using uchar to spend a single byte of mem..
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.
72 // ----------------- PPM related stuffs ------------------------
73 // The PPM generation is handled by Timer0 interrupts, and needs
74 // all modifiable variables to be global and volatile...
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
81 // All time values in usecs
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...
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
92 // ----------------- Menu/IU related stuffs --------------------
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.
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
123 EXPOS, // Some radios have "drawn curves", i.e. loopup tables stored in external EEPROM ...
131 boolean prev_keys[8];
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;
148 // ----------------- DEBUG-STUFF --------------------
149 unsigned long prev_loop_time;
150 unsigned long avg_loop_time;
154 // ---------- CODE! -----------------------------------
156 // ---------- Arduino SETUP code ----------------------
158 pinMode(13, OUTPUT); // led
160 pinMode(2, OUTPUT); // s0
161 pinMode(3, OUTPUT); // s1
162 pinMode(4, OUTPUT); // s2
163 pinMode(5, OUTPUT); // e
166 lcd.print("Starting....");
169 Serial.println("Starting....");
175 displaystate = VALUES;
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
181 digitalWrite(A2, HIGH);
186 // Debugging: how long does the main loop take on avg...
192 // Initializing the stopwatch timer/clock values...
193 clock_timer = (clock_timer_t){0, 0, 0, false};
195 pinMode(A5, OUTPUT); // PPM output pin
197 set_timer( seplength );
198 Timer1.initialize(framelength);
199 Timer1.attachInterrupt(ISR_timer);
203 void model_defaults( void )
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.
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 ...)
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.
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;
226 // ---------- Arduino main loop -----------------------
232 // Wasting a full I/O pin on battery status monitoring!
233 battery_val = analogRead(1) * BATTERY_CONV;
234 if ( battery_val < BATTERY_LOW ) {
235 digitalWrite(13, 1); // Simulate alarm :P
236 displaystate = BATTERY;
239 if ( millis() - last > UI_INTERVAL )
246 if ( displaystate != MENU )
248 // Debugging: how long does the main loop take on avg,
249 // when not handling the UI...
251 avg_loop_time = ( t - prev_loop_time + avg_loop_time ) / 2;
255 // Whoa! Slow down partner! Let everything settle down before proceeding.
259 // ----- Simple support functions used by more complex functions ----
261 void set_ppm_output( bool state )
263 digitalWrite(A5, state); // Hard coded PPM output
266 void set_timer(long time)
268 Timer1.detachInterrupt();
269 Timer1.attachInterrupt(ISR_timer, time);
272 boolean check_key( int key)
274 return ( !keys[key] && prev_keys[key] );
277 void mplx_select(int pin)
280 delayMicroseconds(24);
282 digitalWrite(2, bitRead(pin,0)); // Arduino alias for non-modifying bitshift operation
283 digitalWrite(3, bitRead(pin,1)); // us used to extract individual bits from the int (0..7)
284 digitalWrite(4, bitRead(pin,2)); // Select the appropriate input by setting s1,s2,s3 and e
285 digitalWrite(5, 0); // on the 4051 multiplexer.
287 // May need to slow the following read down to be able to
288 // get fully reliable values from the 4051 multiplex.
289 delayMicroseconds(24);
293 // ----- "Complex" functions follow ---------------------------------
298 int num_calibrations = 200;
301 lcd.print("Move controls to");
303 lcd.print("their extremes..");
304 Serial.print("Calibration. Move all controls to their extremes.");
306 for (i=0; i<MAX_INPUTS; i++) {
307 input_cal.min[i] = 1024;
308 input_cal.center[i] = 512;
309 input_cal.max[i] = 0;
312 while ( num_calibrations-- )
314 for (i=0; i<MAX_INPUTS; i++) {
316 adc_in = analogRead(0);
318 // Naive min/max calibration
319 if ( adc_in < input_cal.min[i] ) {
320 input_cal.min[i] = adc_in;
322 if ( adc_in > input_cal.max[i] ) {
323 input_cal.max[i] = adc_in;
329 // TODO: WILL need to do center-point calibration after min-max...
332 lcd.print("Saving to EEPROM");
334 lcd.setCursor(0 , 1);
335 lcd.print("Done calibrating");
337 Serial.print("Done calibrating");
341 void write_calibration(void)
347 // Set p to be a pointer to the start of the input calibration struct.
348 p = (const byte*)(const void*)&input_cal;
350 // Iterate through the bytes of the struct...
351 for (i = 0; i < sizeof(input_cal_t); i++)
353 // Get a byte of data from the struct...
354 v = (unsigned char) *p;
355 // write it to EEPROM
356 EEPROM.write( EE_BASE_ADDR + i, v);
357 // and move the pointer to the next byte in the struct.
362 void read_settings(void)
369 if ( v != EEPROM_VERSION )
371 // All models have been reset. Set the current model to 0
373 EEPROM.write(1, current_model);
377 // The following does not yet work...
378 for ( i = 0; i < MAX_MODELS; i++)
379 write_model_settings(i);
382 // After saving calibration data and model defaults,
383 // update the saved version-identifier to the current ver.
384 EEPROM.write(0, EEPROM_VERSION);
387 // Read calibration values from EEPROM.
388 // This uses simple pointer-arithmetic and byte-by-byte
389 // to put bytes read from EEPROM to the data-struct.
390 p = (byte*)(void*)&input_cal;
391 for (i = 0; i < sizeof(input_cal_t); i++)
392 *p++ = EEPROM.read( EE_BASE_ADDR + i);
394 // Get the previously selected model from EEPROM.
395 current_model = EEPROM.read(1);
396 read_model_settings( current_model );
399 void read_model_settings(unsigned char mod_no)
406 // Calculate the EEPROM start adress for the given model (mod_no)
407 model_address = EE_MDL_BASE_ADDR + (mod_no * sizeof(model_t));
409 // Do not try to write the model to EEPROM if it won't fit.
410 if ( INT_EEPROM_SIZE < (model_address + sizeof(model_t)) )
413 lcd.print("Aborting READ");
414 lcd.setCursor(0 , 1);
415 lcd.print("Invalid location");
421 lcd.print("Reading model ");
422 lcd.print( (int)mod_no );
424 // Pointer to the start of the model_t data struct,
425 // used for byte-by-byte reading of data...
426 p = (byte*)(void*)&model;
427 for (i = 0; i < sizeof(model_t); i++)
428 *p++ = EEPROM.read( model_address++ );
432 lcd.setCursor(0 , 1);
433 lcd.print("... Loaded.");
437 void write_model_settings(unsigned char mod_no)
444 // Calculate the EEPROM start adress for the given model (mod_no)
445 model_address = EE_MDL_BASE_ADDR + (mod_no * sizeof(model_t));
447 // Do not try to write the model to EEPROM if it won't fit.
448 if ( INT_EEPROM_SIZE < (model_address + sizeof(model_t)) )
451 lcd.print("Aborting SAVE");
452 lcd.setCursor(0 , 1);
453 lcd.print("No room for data");
459 lcd.print("Saving model ");
460 lcd.print( (int)mod_no);
462 // Pointer to the start of the model_t data struct,
463 // used for byte-by-byte reading of data...
464 p = (byte*)(void*)&model;
466 // Write/serialize the model data struct to EEPROM...
467 for (i = 0; i < sizeof(model_t); i++)
468 EEPROM.write( model_address++, *p++);
470 lcd.setCursor(0 , 1);
471 lcd.print(".. done saving.");
475 void serial_dump_model ( void )
479 // Calculate the EEPROM start adress for the given model (mod_no)
480 model_address = EE_MDL_BASE_ADDR + (current_model * sizeof(model_t));
481 Serial.print("Current model: ");
482 Serial.println( (int)current_model );
483 Serial.print("Models base addr: ");
484 Serial.println( EE_MDL_BASE_ADDR );
485 Serial.print("Model no: ");
486 Serial.println( current_model, 10 );
487 Serial.print("Size of struct: ");
488 Serial.println( sizeof( model_t) );
489 Serial.print("Model address: ");
490 Serial.println( model_address );
491 Serial.print("End of model: ");
492 Serial.println( model_address + sizeof(model_t) );
496 Serial.print("Channel reversions: ");
497 for ( i = 0; i<8; i++)
501 Serial.print(model.rev[i], 10);
506 Serial.print("DR1 inp 0: ");
507 Serial.println(model.dr[0]);
508 Serial.print("DR1 inp 1: ");
509 Serial.println(model.dr[1]);
510 Serial.print("DR1 LO val: ");
511 Serial.println(model.dr[4]);
512 Serial.print("DR1 HI val: ");
513 Serial.println(model.dr[5]);
514 Serial.print("DR2 inp 0: ");
515 Serial.println(model.dr[2]);
516 Serial.print("DR2 inp 1: ");
517 Serial.println(model.dr[3]);
518 Serial.print("DR2 LO val: ");
519 Serial.println(model.dr[6]);
520 Serial.print("DR2 HI val: ");
521 Serial.println(model.dr[7]);
523 for (i=0; i<MAX_INPUTS; i++) {
524 Serial.print("Input #");
526 Serial.print(" pct: ");
527 Serial.print(model.stick[i]);
528 Serial.print(" min: ");
529 Serial.print(input_cal.min[i]);
530 Serial.print(" max: ");
531 Serial.print(input_cal.max[i]);
536 void scan_keys ( void )
540 // To get more inputs, another 4051 analog multiplexer is used,
541 // but this time it is used for digital inputs. 8 digital inputs
542 // on one input line, as long as proper debouncing and filtering
543 // is done in hardware :P
544 for (int i=0; i<=7; i++) {
545 // To be able to detect that a key has changed state, preserve the previous..
546 prev_keys[i] = keys[i];
548 // Select and read input.
550 keys[i] = digitalRead(A2);
556 void process_inputs(void )
558 int current_input, adc_in, fact;
561 for (current_input=0; current_input<MAX_INPUTS; current_input++) {
563 mplx_select(current_input);
564 adc_in = analogRead(0);
566 model.raw[current_input] = adc_in;
567 // New format on stick values
568 // The calculations happen around the center point, the values
569 // need to arrive at 0...100 of the range "center-to-edge",
570 // and must end up as negative on the ... negative side of center.
572 if ( adc_in < input_cal.center[current_input] )
574 // The stick is on the negative side, so the range is
575 // from the lowest possible value to center, and we must
576 // make this a negative percentage value.
577 max = input_cal.min[current_input];
578 min = input_cal.center[current_input];
583 // The stick is at center, or on the positive side.
584 // Thus, the range is from center to max, and
585 // we need positive percentages.
586 min = input_cal.center[current_input];
587 max = input_cal.max[current_input];
590 // Calculate the percentage that the current stick position is at
591 // in the given range, referenced to or from center, depending :P
592 model.stick[current_input] = fact * ((float)adc_in - min ) / (max - min);
594 // If this input is configured to be reversed, simply do a sign-flip :D
595 if ( model.rev[current_input] ) model.stick[current_input] *= -1;
597 // Dual-rate calculation :D
598 // This is very repetitive code. It should be fast, but it may waste code-space.
600 // Test to see if dualrate-switch #1 applies to channel...
601 if ( ( current_input == ( model.dr[0]-1) ) || ( current_input == ( model.dr[1]-1) ) )
603 if ( !keys[KEY_DR1] )
604 dr_val = ((float)model.dr[4])/100.0;
606 dr_val = ((float)model.dr[5])/100.0;
608 model.stick[current_input] *= dr_val;
611 // Test to see if dualrate-switch #1 applies to channel...
612 if ( ( current_input == ( model.dr[2]-1) ) || ( current_input == ( model.dr[3]-1) ) )
614 if ( !keys[KEY_DR1] )
615 dr_val = ((float)model.dr[6])/100.0;
617 dr_val = ((float)model.dr[7])/100.0;
619 model.stick[current_input] *= dr_val;
627 Timer1.stop(); // Make sure we do not run twice while working :P
631 set_ppm_output( LOW );
634 set_timer(seplength);
638 if ( cchannel >= model.channels )
640 set_ppm_output( HIGH );
641 long framesep = framelength - sum;
646 set_timer ( framesep );
652 set_ppm_output( HIGH );
654 // New format on stick values
655 // model.stick contains percentages, -100% to 100% in float. To make the timer-handling
656 // here as simple as possible. We want to calc the channel value as a "ratio-value",
657 // a float in the range 0..1.0. So, by moving the lower bound to 0, then cutting the
658 // range in half, and finally dividing by 100, we should get the ratio value.
659 // Some loss of presicion occurs, perhaps the algo' should be reconsidered :P
660 long next_timer = (( chwidht * ((model.stick[cchannel]+100)/200) ) + chmin);
661 // Do sanity-check of next_timer compared to chmax and chmin...
662 while ( chmax < next_timer ) next_timer--;
663 while ( next_timer < chmin ) next_timer++;
665 // Update the sum of elapsed time
668 // Done with channel separator and value,
669 // prepare for next channel...
672 set_timer ( next_timer );
680 for (current_input=0; current_input<MAX_INPUTS; current_input++) {
682 Serial.print("Input #");
683 Serial.print(current_input);
684 Serial.print(" pct: ");
685 Serial.print(model.stick[current_input]);
686 Serial.print(" raw value: ");
687 Serial.print(model.raw[current_input]);
688 Serial.print(" min: ");
689 Serial.print(input_cal.min[current_input]);
690 Serial.print(" max: ");
691 Serial.print(input_cal.max[current_input]);
694 Serial.print("Battery level is: ");
695 Serial.println(battery_val);
697 Serial.print("Average loop time:");
698 Serial.println(avg_loop_time);
703 void dr_inputselect( int no, int in )
705 if ( model.dr[menu_substate] < 0 ) model.dr[menu_substate] = 4;
706 if ( model.dr[menu_substate] > 4 ) model.dr[menu_substate] = 0;
708 lcd.setCursor(0 , 0);
709 lcd.print("D/R switch ");
712 lcd.setCursor(0 , 1);
717 if ( ! model.dr[menu_substate] ) lcd.print("Off");
718 else lcd.print(model.dr[menu_substate]);
720 if ( check_key(KEY_INC) ) {
721 model.dr[menu_substate]++;
724 else if ( check_key(KEY_DEC) ) {
725 model.dr[menu_substate]--;
738 if ( menu_substate == 4) state = keys[KEY_DR1];
739 else state = keys[KEY_DR2];
741 pos = 4 + (menu_substate - 4) * 2;
744 lcd.setCursor(0 , 0);
745 lcd.print("D/R switch ");
746 lcd.print( menu_substate - 3 );
748 lcd.setCursor(0 , 1);
749 lcd.print( state ? "HI" : "LO" );
750 lcd.print(" Value :");
752 lcd.print( model.dr[pos] );
754 if ( !keys[KEY_INC] ) {
755 if ( model.dr[pos] < 100) model.dr[pos] += 5;
758 else if ( !keys[KEY_DEC] ) {
759 if ( model.dr[pos] > -100) model.dr[pos] -= 5;
771 if ( displaystate != MENU )
774 if ( check_key(KEY_UP) && displaystate == VALUES ) {
775 displaystate = BATTERY;
778 else if ( check_key(KEY_UP) && displaystate == BATTERY ) {
779 displaystate = TIMER;
782 else if ( check_key(KEY_UP) && displaystate == TIMER ) {
783 displaystate = CURMODEL;
786 else if ( check_key(KEY_UP) && displaystate == CURMODEL ) {
787 displaystate = VALUES;
791 else if ( check_key(KEY_DOWN) ) {
797 digitalWrite(13, digitalRead(13) ^ 1 );
799 switch ( displaystate )
803 for (current_input=0; current_input<MAX_INPUTS; current_input++) {
804 // In channel value display, do a simple calc
805 // of the LCD row & column location. With 8 channels
806 // we can fit eight channels as percentage values on
807 // a simple 16x2 display...
808 if ( current_input < 4 )
810 col = current_input * 4;
815 col = (current_input-4) * 4;
818 // Overwriting the needed positions with
819 // blanks cause less display-flicker than
820 // actually clearing the display...
821 lcd.setCursor(col, row);
823 lcd.setCursor(col, row);
824 // Display uses percents, while PPM uses ratio....
825 // New format on stick values
826 lcd.print( (int)model.stick[current_input] );
833 lcd.print("Battery level: ");
834 lcd.setCursor(0 , 1);
835 lcd.print( (float)battery_val/10);
837 if ( battery_val < BATTERY_LOW ) lcd.print(" - WARNING");
838 else lcd.print(" - OK");
850 lcd.print("Timer: ");
851 lcd.print( clock_timer.running ? "Running" : "Stopped" );
852 lcd.setCursor(5 , 1);
853 if ( clock_timer.running )
855 clock_timer.value = millis() - (clock_timer.start + clock_timer.init);
857 hours = ( clock_timer.value / 1000 ) / 3600;
858 clock_timer.value = clock_timer.value % 3600000;
859 minutes = ( clock_timer.value / 1000 ) / 60;
860 seconds = ( clock_timer.value / 1000 ) % 60;
865 if ( minutes < 10 ) lcd.print("0");
866 lcd.print( minutes );
868 if ( seconds < 10 ) lcd.print("0");
869 lcd.print( seconds );
871 if ( check_key(KEY_INC) ) {
872 if ( !clock_timer.running && !clock_timer.start )
874 clock_timer.start = millis();
875 clock_timer.value = 0;
876 clock_timer.running = true;
877 } else if ( !clock_timer.running && clock_timer.start ) {
878 clock_timer.start = millis() - clock_timer.value;
879 clock_timer.running = true;
880 } else if ( clock_timer.running ) {
881 clock_timer.running = false;
884 } else if ( check_key(KEY_DEC) ) {
885 if ( !clock_timer.running && clock_timer.start ) {
886 clock_timer.value = 0;
887 clock_timer.start = 0;
888 clock_timer.init = 0;
898 lcd.print("Model #: ");
899 lcd.print( (int)current_model );
900 lcd.setCursor(0 , 1);
901 lcd.print("NAME (not impl)");
908 switch ( menu_mainstate )
911 lcd.print("In MENU mode!");
912 lcd.setCursor(0 , 1);
913 lcd.print("Esc UP. Scrl DN.");
915 if ( check_key(KEY_UP) ) {
916 displaystate = VALUES;
919 else if ( check_key(KEY_DOWN) ) {
920 menu_mainstate = INVERTS;
927 if ( menu_substate >= model.channels ) menu_substate = 0;
928 if ( menu_substate < 0) menu_substate = (model.channels - 1);
929 lcd.print("Channel invert");
930 lcd.setCursor(0 , 1);
932 lcd.print(menu_substate+1);
933 lcd.print( (model.rev[menu_substate] ? ": Invert" : ": Normal"));
935 if ( check_key(KEY_UP) ) {
936 menu_mainstate = TOP;
939 else if ( check_key(KEY_DOWN) ) {
940 menu_mainstate = DUALRATES;
944 if ( check_key(KEY_RIGHT) ) {
948 else if ( check_key(KEY_LEFT) ) {
952 else if ( check_key(KEY_INC) || check_key(KEY_DEC) ) {
953 model.rev[menu_substate] ^= 1;
959 if ( menu_substate > 5 ) menu_substate = 0;
960 if ( menu_substate < 0) menu_substate = 5;
962 if ( check_key(KEY_UP) ) {
963 menu_mainstate = INVERTS;
966 if ( check_key(KEY_DOWN) ) {
967 menu_mainstate = EXPOS;
970 if ( check_key(KEY_RIGHT) ) {
974 else if ( check_key(KEY_LEFT) ) {
978 switch (menu_substate)
981 dr_inputselect(0, 0);
984 dr_inputselect(0, 1);
987 dr_inputselect(1, 0);
990 dr_inputselect(1, 1);
1004 lcd.print("Input expo curve");
1005 lcd.setCursor(0 , 1);
1006 lcd.print("Not implemented");
1007 // Possible, if input values are mapped to +/- 100 rather than 0..1 ..
1008 // plot ( x*(1 - 1.0*cos (x/(20*PI)) )) 0 to 100
1009 // Run in wolfram to see result, adjust the 1.0 factor to inc/red effect.
1010 // Problem: -100 to 100 is terribly bad presicion, esp. considering that
1011 // the values started as 0...1024, and we have 1000usec to "spend" on channels.
1013 // NEW IDEA provided my ivarf @ hig: use bezier curves og hermite curves!
1014 // Looks like a promising idea, but the implementation is still a bitt off
1015 // on the time-horizon :P
1016 if ( check_key(KEY_UP ) ) {
1017 menu_mainstate = DUALRATES;
1020 if ( check_key(KEY_DOWN ) ) {
1021 menu_mainstate = DEBUG;
1027 lcd.setCursor(0 , 0);
1028 lcd.print("Dumping debug to");
1029 lcd.setCursor(0 , 1);
1030 lcd.print("serial port 0");
1032 if ( check_key(KEY_UP ) ) {
1033 // FIXME: Remember to update the "Scroll up" state!
1034 menu_mainstate = EXPOS;
1036 } else if ( check_key(KEY_DOWN ) ) {
1037 menu_mainstate = SAVE;
1043 lcd.print("Not implemented");
1044 lcd.setCursor(0 , 1);
1045 lcd.print("Press DOWN...");
1046 if ( check_key(KEY_DOWN ) ) menu_mainstate = TOP;