]> git.defcon.no Git - rctxduino/blobdiff - source/RCTXDuino/RCTXDuino.pde
Added debug/status display of DR switches to display/UI
[rctxduino] / source / RCTXDuino / RCTXDuino.pde
index 0bc85626db0fc0992c86333e0fbb1029ae1a0151..1afb5ea66db2dfa7184ce33b5f5ac159f8c60540 100644 (file)
@@ -1,7 +1,16 @@
-#include <LiquidCrystal.h>
+// No longer using HD44780-comaptible display,
+// Moving to a brand new world of dot-matrix display tech!
+// Using LCD library from http://code.google.com/p/pcd8544/
+#include <PCD8544.h>
+
 #include <TimerOne.h>
 #include <EEPROM.h>
 
+// Undefine this whenever a "release" or "flight-test" build is made.
+// Defining DEBUG sets some crazy values for things like battery warning,
+// and includes a whole bunch of debugging-related code ...
+#define DEBUG 1
+
 #define MAX_INPUTS 8
 
 // Update this _every_ time a change in datastructures that
@@ -66,8 +75,8 @@ volatile model_t model;
 unsigned char current_model; // Using uchar to spend a single byte of mem..
 
 // ----------------- Display related stuffs --------------------
-LiquidCrystal lcd( 12, 11, 10,     6,  7,  8,  9);
-// Parameters are: rs, rw, enable, d4, d5, d6, d7 pin numbers.
+PCD8544 lcd( 8,  9,   10, 11,    12);
+// Param:   sclk, sdin, dc, reset, sce
 
 // ----------------- PPM related stuffs ------------------------
 // The PPM generation is handled by Timer0 interrupts, and needs
@@ -83,10 +92,10 @@ volatile bool do_channel = true;        // Is next operation a channel or a sepa
 // The timing here (and/or in the ISR) needs to be tweaked to provide valid
 // RC PPM signals accepted by standard RC RX'es and the Microcopter...
 
-#define framelength  21500             // Max length of frame
-#define seplength      250             // Lenght of a channel separator
+#define framelength  21000             // Max length of frame
+#define seplength      300             // Lenght of a channel separator
 #define chmax         1600             // Max lenght of channel pulse
-#define chmin          480             // Min length of channel
+#define chmin          495             // Min length of channel
 #define chwidht  (chmax - chmin)// Useable time of channel pulse
 
 // ----------------- Menu/IU related stuffs --------------------
@@ -105,7 +114,15 @@ volatile bool do_channel = true;        // Is next operation a channel or a sepa
 
 // Voltage sense pin is connected to a 1/3'd voltage divider.
 #define BATTERY_CONV (10 * 3 * (5.0f/1024.0f))
+
+#ifdef DEBUG
+// The following values are for DEBUGGING ONLY!!
+#define BATTERY_LOW 92
+#define BATTERY_CRITICAL 0
+#else
 #define BATTERY_LOW 92
+#define BATTERY_CRITICAL 92
+#endif
 
 enum {
   VALUES,
@@ -121,7 +138,7 @@ enum {
   INVERTS,
   DUALRATES,
   EXPOS, // Some radios have "drawn curves", i.e. loopup tables stored in external EEPROM ...
-  DEBUG,
+  DEBUG_DUMP,
   SAVE
 } 
 menu_mainstate;
@@ -145,11 +162,12 @@ struct clock_timer_t
        boolean running;
 } clock_timer;
 
+#ifdef DEBUG
 // -----------------  DEBUG-STUFF --------------------
 unsigned long prev_loop_time;
 unsigned long avg_loop_time;
 unsigned long t;
-
+#endif
 
 // ---------- CODE! -----------------------------------
 
@@ -162,11 +180,14 @@ void setup(){
   pinMode(4, OUTPUT);    // s2
   pinMode(5, OUTPUT);    // e
 
-  lcd.begin(16,2);
+  lcd.begin(84, 48);
   lcd.print("Starting....");
 
+#ifdef DEBUG  
   Serial.begin(9600);
   Serial.println("Starting....");
+#endif
+  
   delay(500);
   
   model_defaults();
@@ -183,11 +204,12 @@ void setup(){
   if ( !keys[KEY_UP])
     calibrate();
   
+#ifdef DEBUG
   // Debugging: how long does the main loop take on avg...  
   t = micros();
   avg_loop_time = t;
   prev_loop_time = t;    
-
+#endif
   
   // Initializing the stopwatch timer/clock values...
   clock_timer = (clock_timer_t){0, 0, 0, false};
@@ -197,6 +219,8 @@ void setup(){
   set_timer( seplength );
   Timer1.initialize(framelength);
   Timer1.attachInterrupt(ISR_timer);  
+
+  lcd.clear();
   
 }
 
@@ -224,15 +248,8 @@ void model_defaults( void )
 }
 
 // ---------- Arduino main loop -----------------------
-void loop () {
-  
-  // Determine if the UI needs to run...
-  boolean disp;
-  if ( millis() - last > UI_INTERVAL ) { 
-    last = millis(); 
-    disp = true; 
-  }
-  else disp = false;
+void loop ()
+{  
 
   process_inputs();
 
@@ -240,13 +257,18 @@ void loop () {
   battery_val = analogRead(1) * BATTERY_CONV;
   if ( battery_val < BATTERY_LOW ) {
     digitalWrite(13, 1); // Simulate alarm :P
+  }
+  if ( battery_val < BATTERY_CRITICAL ) {
     displaystate = BATTERY;
   }
 
-  if ( disp )
-  {
+  if ( millis() - last > UI_INTERVAL ) 
+  { 
+    last = millis(); 
     ui_handler(); 
   }
+  
+#ifdef DEBUG
   if ( displaystate != MENU )
   {
     // Debugging: how long does the main loop take on avg,
@@ -255,6 +277,7 @@ void loop () {
     avg_loop_time = ( t - prev_loop_time + avg_loop_time ) / 2;
     prev_loop_time = t;    
   }
+#endif
 
   // Whoa! Slow down partner! Let everything settle down before proceeding.
   delay(5);
@@ -431,7 +454,9 @@ void read_model_settings(unsigned char mod_no)
   for (i = 0; i < sizeof(model_t); i++)
                *p++ = EEPROM.read( model_address++ );
 
+#ifdef DEBUG
   serial_dump_model();
+#endif
 
   lcd.setCursor(0 , 1);
   lcd.print("... Loaded.");
@@ -476,6 +501,7 @@ void write_model_settings(unsigned char mod_no)
   delay(200);    
 }
 
+#ifdef DEBUG
 void serial_dump_model ( void )
 {
   int i;
@@ -536,6 +562,7 @@ void serial_dump_model ( void )
     Serial.println();
   }  
 }
+#endif
 
 void scan_keys ( void )
 {
@@ -615,7 +642,7 @@ void process_inputs(void )
     // Test to see if dualrate-switch #1 applies to channel...
     if ( ( current_input == ( model.dr[2]-1) ) || ( current_input == ( model.dr[3]-1) ) )
     {
-            if ( !keys[KEY_DR1] )
+            if ( !keys[KEY_DR2] )
                     dr_val = ((float)model.dr[6])/100.0; 
             else
                     dr_val = ((float)model.dr[7])/100.0;
@@ -678,6 +705,8 @@ void ISR_timer(void)
   }
 }
 
+
+#ifdef DEBUG
 void serial_debug()
 {
   int current_input;
@@ -701,8 +730,11 @@ void serial_debug()
   Serial.print("Average loop time:");
   Serial.println(avg_loop_time);
 
+  Serial.print("Free RAM:");
+  Serial.print( FreeRam() );
   Serial.println();
 }
+#endif
 
 void dr_inputselect( int no, int in )
 {
@@ -712,7 +744,10 @@ void dr_inputselect( int no, int in )
        lcd.setCursor(0 , 0);
        lcd.print("D/R switch ");
        lcd.print( no + 1 );
-       lcd.print("    ");
+       //lcd.print("    ");
+       
+       lcd.setCursor(0 , 1);
+       lcd.print("              ");
        lcd.setCursor(0 , 1);
        lcd.print("Input ");
        lcd.print(in+1);
@@ -748,7 +783,10 @@ void dr_value()
        lcd.setCursor(0 , 0);
        lcd.print("D/R switch ");
        lcd.print( menu_substate - 3 );
-       lcd.print("    ");
+
+
+       lcd.setCursor(0 , 1);
+       lcd.print("              ");
        lcd.setCursor(0 , 1);
        lcd.print( state ? "HI" : "LO" );
        lcd.print(" Value :");
@@ -772,6 +810,9 @@ void ui_handler()
   int col;
   scan_keys();
 
+  if ( check_key( KEY_UP) || check_key(KEY_DOWN))
+       lcd.clear();
+
   if ( displaystate != MENU )
   {
        menu_substate = 0;
@@ -797,45 +838,74 @@ void ui_handler()
       return; 
     }
   }
-
+       
   digitalWrite(13, digitalRead(13) ^ 1 );
 
   switch ( displaystate )
   {
     case VALUES:
-      int current_input;
+         int current_input;
+
+
+         row = 0;
+         col = 0;
+         
+         lcd.setCursor(col, row);
+         lcd.print("            ");
+       
+         lcd.setCursor(col, row);
+         lcd.print("S1:");
+         lcd.print( keys[KEY_DR1] ? "On " : "Off" );
+         lcd.print(" S2:");
+         lcd.print( keys[KEY_DR2] ? "On " : "Off" );
+
+         row = 2;
+         col = 0;
+         
       for (current_input=0; current_input<MAX_INPUTS; current_input++) {
-        // In channel value display, do a simple calc
-        // of the LCD row & column location. With 8 channels
-        // we can fit eight channels as percentage values on
-        // a simple 16x2 display...
-        if ( current_input < 4 )
-        {
-          col = current_input * 4; 
-          row = 0;
-        } 
-        else 
-        {
-          col = (current_input-4) * 4;      
-          row = 1;
-        }
+               if (row == 6)
+               {
+                       row = 2;
+                       col = 40;
+               }
+
         // Overwriting the needed positions with
         // blanks cause less display-flicker than
         // actually clearing the display...
         lcd.setCursor(col, row);
-        lcd.print("    ");
+        lcd.print("      ");
+
         lcd.setCursor(col, row);
+               
+               char mod_indicator = NULL;
+               
+               if (( keys[KEY_DR1] ) && (( model.dr[0] == current_input+1) || ( model.dr[1] == current_input+1)))
+                       mod_indicator = '/';
+
+               if (( keys[KEY_DR2] ) && (( model.dr[2] == current_input+1) || ( model.dr[3] == current_input+1)))
+                       if (mod_indicator) mod_indicator = '|';
+                       else mod_indicator = '\\';
+               
+               if ( mod_indicator) lcd.print(mod_indicator);
+               else lcd.print(" ");
+               
+               lcd.print( current_input+1);
+               lcd.print(":");
         // Display uses percents, while PPM uses ratio....
                // New format on stick values
                lcd.print( (int)model.stick[current_input] );
+
+               row++;
       }
       break;
 
 
     case BATTERY:    
-      lcd.clear();
+      lcd.setCursor(0 , 0);
       lcd.print("Battery level: ");
       lcd.setCursor(0 , 1);
+      lcd.print( "            ");
+      lcd.setCursor(0 , 1);
       lcd.print( (float)battery_val/10);
       lcd.print("V");
       if ( battery_val < BATTERY_LOW ) lcd.print(" - WARNING");
@@ -850,10 +920,12 @@ void ui_handler()
                int minutes;
                int seconds;
                
-               lcd.clear();
+        lcd.setCursor(0 , 0);
                lcd.print("Timer: ");
                lcd.print( clock_timer.running ? "Running" : "Stopped" );
                lcd.setCursor(5 , 1);
+               lcd.print("         ");
+               lcd.setCursor(5 , 1);
                if ( clock_timer.running )
                {
                        clock_timer.value = millis() - (clock_timer.start + clock_timer.init);
@@ -898,7 +970,7 @@ void ui_handler()
 
                
        case CURMODEL:    
-      lcd.clear();
+      lcd.setCursor(0 , 0);
       lcd.print("Model #: ");
          lcd.print( (int)current_model );
       lcd.setCursor(0 , 1);
@@ -908,19 +980,25 @@ void ui_handler()
 
          
     case MENU:
-      lcd.clear();
+      lcd.setCursor(0 , 0);
       switch ( menu_mainstate )
       {
         case TOP:
+          lcd.setCursor(0 , 0);
           lcd.print("In MENU mode!");
           lcd.setCursor(0 , 1);
-          lcd.print("Esc UP. Scrl DN.");
+          lcd.print("UP to quit.");
+          lcd.setCursor(0 , 2);
+                 lcd.print("DOWN to scroll");
+
           menu_substate = 0;
           if ( check_key(KEY_UP) ) { 
             displaystate = VALUES; 
+            lcd.clear();
             return; 
           }
           else if ( check_key(KEY_DOWN) ) { 
+                       lcd.clear();
             menu_mainstate = INVERTS; 
             return; 
           }
@@ -938,10 +1016,12 @@ void ui_handler()
 
           if ( check_key(KEY_UP) ) { 
             menu_mainstate = TOP; 
+                       lcd.clear();
             return; 
           }
           else if ( check_key(KEY_DOWN) ) { 
             menu_mainstate = DUALRATES; 
+                       lcd.clear();
             return; 
           }
 
@@ -965,10 +1045,12 @@ void ui_handler()
                
           if ( check_key(KEY_UP) ) { 
             menu_mainstate = INVERTS; 
+                       lcd.clear();
             return; 
           }          
           if ( check_key(KEY_DOWN) ) {
             menu_mainstate = EXPOS;
+                       lcd.clear();
             return;
           }
           if ( check_key(KEY_RIGHT) ) { 
@@ -1019,15 +1101,27 @@ void ui_handler()
                  // on the time-horizon :P
           if ( check_key(KEY_UP ) ) { 
             menu_mainstate = DUALRATES; 
+                       lcd.clear();
             return; 
           }          
+#ifdef DEBUG          
+          if ( check_key(KEY_DOWN ) ) {
+            menu_mainstate = DEBUG_DUMP;
+                       lcd.clear();
+            return;
+          }
+#else
           if ( check_key(KEY_DOWN ) ) {
-            menu_mainstate = DEBUG;
+            menu_mainstate = TOP;
+                       lcd.clear();
             return;
           }
+
+#endif
           break;
-          
-        case DEBUG:
+
+#ifdef DEBUG          
+        case DEBUG_DUMP:
           lcd.setCursor(0 , 0);
           lcd.print("Dumping debug to");
           lcd.setCursor(0 , 1);
@@ -1036,13 +1130,15 @@ void ui_handler()
           if ( check_key(KEY_UP ) ) { 
             // FIXME: Remember to update the "Scroll up" state!
             menu_mainstate = EXPOS; 
+                       lcd.clear();
             return; 
           } else if ( check_key(KEY_DOWN ) ) {
             menu_mainstate = SAVE;
+                       lcd.clear();
             return;
           }
           break;
-    
+#endif    
         default:
           lcd.print("Not implemented");
           lcd.setCursor(0 , 1);
@@ -1060,6 +1156,33 @@ void ui_handler()
   return;
 }
 
+#ifdef DEBUG
+/* The following code is taken from the 
+   Arduino FAT16 Library by William Greiman 
+   The code may or may-not survive in the long run,
+   depending on what licensing-terms we decide on.
+   The license will be open source, but the FAT16lib
+   is GPL v3, and I (fishy) am personally not so sure about that... 
+   
+   On the other hand... This code is a very "intuitive approach",
+   so contacting the author may give us the option of relicencing just this bit...
+*/
+static int FreeRam(void) {
+  extern int  __bss_end;
+  extern int* __brkval;
+  int free_memory;
+  if (reinterpret_cast<int>(__brkval) == 0) {
+    // if no heap use from end of bss section
+    free_memory = reinterpret_cast<int>(&free_memory)
+                  - reinterpret_cast<int>(&__bss_end);
+  } else {
+    // use from top of stack to heap
+    free_memory = reinterpret_cast<int>(&free_memory)
+                  - reinterpret_cast<int>(__brkval);
+  }
+  return free_memory;
+}
+#endif