]> git.defcon.no Git - rctxduino/commitdiff
Moved code to using the PCD8544 Arduino library from http://code.google.com/p/pcd8544/
authorJon Langseth <jon.langseth@lilug.no>
Wed, 7 Sep 2011 22:47:45 +0000 (00:47 +0200)
committerJon Langseth <jon.langseth@lilug.no>
Wed, 7 Sep 2011 22:47:45 +0000 (00:47 +0200)
Download the latest and greatest version of the library, dump the PCD8544 directory to your Arduino libraries folder, restart the Arduino IDE. The display needs to be connected as follows: SCLK 8, SDIN 9, D/C 10, RST 11, SCE 12.

source/RCTXDuino/RCTXDuino.pde

index 0c63499223ca8dee79159714bc4524884a98476c..f4661da586946b160b07bce027fcb1ee5c7e145f 100644 (file)
@@ -1,4 +1,8 @@
-#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>
 
@@ -71,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
@@ -176,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();
@@ -212,6 +219,8 @@ void setup(){
   set_timer( seplength );
   Timer1.initialize(framelength);
   Timer1.attachInterrupt(ISR_timer);  
+
+  lcd.clear();
   
 }
 
@@ -735,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);
@@ -771,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 :");
@@ -795,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;
@@ -820,45 +838,46 @@ void ui_handler()
       return; 
     }
   }
-
+       
   digitalWrite(13, digitalRead(13) ^ 1 );
 
   switch ( displaystate )
   {
     case VALUES:
       int current_input;
+         row = 1;
+         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 == 5)
+               {
+                       row = 1;
+                       col = 44;
+               }
+
         // 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);
+               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");
@@ -873,10 +892,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);
@@ -921,7 +942,7 @@ void ui_handler()
 
                
        case CURMODEL:    
-      lcd.clear();
+      lcd.setCursor(0 , 0);
       lcd.print("Model #: ");
          lcd.print( (int)current_model );
       lcd.setCursor(0 , 1);
@@ -931,19 +952,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; 
           }
@@ -961,10 +988,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; 
           }
 
@@ -988,10 +1017,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) ) { 
@@ -1042,16 +1073,19 @@ 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 = TOP;
+                       lcd.clear();
             return;
           }
 
@@ -1068,9 +1102,11 @@ 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;