]> git.defcon.no Git - rctxduino/blobdiff - source/RCTXDuino/RCTXDuino.pde
Removed a nasty bug caused my a misplaced ';'. Also: added a debug-dumper serial_dump...
[rctxduino] / source / RCTXDuino / RCTXDuino.pde
index 134526e76780d63e880c1a93521df7e7606d8a98..5254bb67a3748c03345a63be32f9541f78d612c4 100644 (file)
@@ -1,8 +1,40 @@
 #include <LiquidCrystal.h>
 #include <TimerOne.h>
+#include <EEPROM.h>
 
 #define MAX_INPUTS 8
 
+// Update this _every_ time a change in datastructures that
+// can/will ber written to EEPROM is done. EEPROM data is
+// read/written torectly into/from the data structures using
+// pointers, so every time a data-set change occurs, the EEPROM
+// format changes as well..
+#define EEPROM_VERSION 7
+
+// Some data is stored in fixed locations, e.g.:
+//  * The EEPROM version number for the stored data (loc 0)
+//  * The selected model configuration number (loc 1)
+//  * (add any other fixed-loc's here for doc-purpose)
+// This means that any pointer-math-operations need a BASE
+// adress to start calc'ing from. This is defined as:
+#define EE_BASE_ADDR 10 
+
+// Having to repeat tedious base-address-calculations for the
+// start of model data should be unnessecary. Plus, updating
+// what data is stored before the models will mean that each
+// of those calculations must be updated. A better approach is
+// to define the calculation in a define!
+// NOTE: If new data is added in front of the model data,
+// this define must be updated!
+#define EE_MDL_BASE_ADDR (EE_BASE_ADDR+(sizeof(input_cal_t)+ 10))
+
+// Just as a safety-precaution, update/change this if a chip with
+// a different internal EEPROM size is used. Atmega328p has 1024 bytes.
+#define INT_EEPROM_SIZE 1024
+
+#define MAX_MODELS 4 // Nice and random number..
+
+
 // --------------- ADC related stuffs.... --------------------
 
 struct input_cal_t // Struct type for input calibration values
@@ -17,6 +49,7 @@ struct model_t
 {
        int channels; // How many channels should PPM generate for this model ...
        float stick[8]; // The (potentially recalc'ed) value of stick/input channel.
+       int raw[8];
        boolean rev[8];
        int dr[8];        // The Dual-rate array uses magic numbers :P
        /*      dr[0] = Input channel #1 of 2 for D/R switch #1. 0 means off, 1-4 valid values.
@@ -30,6 +63,7 @@ struct model_t
        */
 };
 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);
@@ -39,9 +73,6 @@ LiquidCrystal lcd( 12, 11, 10,     6,  7,  8,  9);
 // The PPM generation is handled by Timer0 interrupts, and needs
 // all modifiable variables to be global and volatile...
 
-//int max_channels = 6;  // How many channels should PPM generate ...
-// Moved to model_t struct...
-
 volatile long sum = 0;                 // Frame-time spent so far
 volatile int cchannel = 0;             // Current channnel
 volatile bool do_channel = true;        // Is next operation a channel or a separator
@@ -52,10 +83,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      400             // Lenght of a channel separator
-#define chmax         1700             // Max lenght of channel pulse
-#define chmin          600             // Min length of channel
+#define framelength  21000             // Max length of frame
+#define seplength      300             // Lenght of a channel separator
+#define chmax         1550             // Max lenght of channel pulse
+#define chmin          620             // Min length of channel
 #define chwidht  (chmax - chmin)// Useable time of channel pulse
 
 // ----------------- Menu/IU related stuffs --------------------
@@ -80,6 +111,7 @@ enum {
   VALUES,
   BATTERY,
   TIMER,
+  CURMODEL,
   MENU
 } 
 displaystate;
@@ -136,16 +168,9 @@ void setup(){
   Serial.begin(9600);
   Serial.println("Starting....");
   delay(500);
+  
+  model_defaults();
   read_settings();
-  scan_keys();
-  if ( keys[KEY_UP])
-    calibrate();
-
-  pinMode(A5, OUTPUT);  // PPM output pin  
-  do_channel = false;
-  set_timer( seplength );
-  Timer1.initialize(framelength);
-  Timer1.attachInterrupt(ISR_timer);  
 
   displaystate = VALUES;
   
@@ -153,25 +178,49 @@ void setup(){
   // In reality they are tri-purpose; ADC, Digital, Digital Interrupts
   // Unfortunately the interrupt mode is unusable in this scenario, but digital I/O works :P
   pinMode(A2, INPUT); 
+  digitalWrite(A2, HIGH);
+  scan_keys();
+  if ( !keys[KEY_UP])
+    calibrate();
   
   // Debugging: how long does the main loop take on avg...  
   t = micros();
   avg_loop_time = t;
   prev_loop_time = t;    
 
-  // Setting this here to be sure I do not forget to init' it....
-  // These initializations should be done by read_settings from eeprom,
-  // and this "default model values" should probably be moved
-  // out to a section of read_settings when handling "new model", or
-  // to a separate model_defaults function...
-  model.channels = 8;
+  
+  // Initializing the stopwatch timer/clock values...
+  clock_timer = (clock_timer_t){0, 0, 0, false};
+
+  pinMode(A5, OUTPUT);  // PPM output pin  
+  do_channel = false;
+  set_timer( seplength );
+  Timer1.initialize(framelength);
+  Timer1.attachInterrupt(ISR_timer);  
+  
+}
+
+void model_defaults( void )
+{
+  // This function provides default values for model data
+  // that is not a result of stick input, or in other words:
+  // provides defautls for all user-configurable model options.
+  
+  // Remember to update this when a new option/element is added
+  // to the model_t struct (preferably before implementing the
+  // menu code that sets those options ...)
+
+  // This is used when a user wants a new, blank model, a reset
+  // of a configured model, and (most important) when EEPROM
+  // data format changes.
+  // NOTE: This means that stored model conficuration is reset
+  // to defaults when the EEPROM version/format changes.
+  model.channels = 6;
   model.rev[0] = model.rev[1] = model.rev[2] = model.rev[3] = 
   model.rev[4] = model.rev[5] = model.rev[6] = model.rev[7] = false;
   model.dr[0] = model.dr[1] = model.dr[2] = model.dr[3] = 0;
   model.dr[4] = model.dr[5] = model.dr[6] = model.dr[7] = 100;
 
-  // Initializing the stopwatch timer/clock values...
-  clock_timer = (clock_timer_t){0, 0, 0, false};
 }
 
 // ---------- Arduino main loop -----------------------
@@ -226,7 +275,7 @@ void set_timer(long time)
 
 boolean check_key( int key)
 {
-  return ( keys[key] && !prev_keys[key] );
+  return ( !keys[key] && prev_keys[key] );
 }
 
 void mplx_select(int pin)
@@ -250,7 +299,6 @@ void mplx_select(int pin)
 void calibrate()
 {
   int i, r0, r1, r2, adc_in;
-  int calcount = 0;
   int num_calibrations = 200;
 
   lcd.clear();
@@ -259,13 +307,15 @@ void calibrate()
   lcd.print("their extremes..");
   Serial.print("Calibration. Move all controls to their extremes.");
 
-  for (i=0; i< MAX_INPUTS; i++) {
+  for (i=0; i<MAX_INPUTS; i++) {
     input_cal.min[i] = 1024;
+       input_cal.center[i] = 512;
     input_cal.max[i] = 0;
   }
-  while ( calcount <= num_calibrations )
+
+  while ( num_calibrations-- )
   {
-    for (i=0; i<=MAX_INPUTS; i++) {
+    for (i=0; i<MAX_INPUTS; i++) {
       mplx_select(i);
       adc_in = analogRead(0);
 
@@ -278,32 +328,213 @@ void calibrate()
       }
       delay(10);
     }
-
-    calcount++;
   }
 
   // TODO: WILL need to do center-point calibration after min-max...
 
   lcd.clear();
+  lcd.print("Saving to EEPROM");
+  write_calibration();
+  lcd.setCursor(0 , 1);
   lcd.print("Done calibrating");
-
+  
   Serial.print("Done calibrating");
   delay(2000);  
 }
 
+void write_calibration(void)
+{
+  int i;
+  unsigned char v;
+  const byte *p;
+  
+  // Set p to be a pointer to the start of the input calibration struct.
+  p = (const byte*)(const void*)&input_cal;
+  
+  // Iterate through the bytes of the struct...
+  for (i = 0; i < sizeof(input_cal_t); i++)
+  {
+    // Get a byte of data from the struct...
+       v = (unsigned char) *p;
+       // write it to EEPROM
+       EEPROM.write( EE_BASE_ADDR + i, v);
+       // and move the pointer to the next byte in the struct.
+       *p++;
+  }
+}
+
 void read_settings(void)
 {
-  // Dummy. Will be modified to read model settings from EEPROM
-  for (int i=0; i<=7; i++) {
-    input_cal.min[i] = 0;
-       input_cal.center[i] = 512;
-    input_cal.max[i] = 1024;
+  int i;
+  unsigned char v;
+  byte *p;
+
+  v = EEPROM.read(0);
+  if ( v != EEPROM_VERSION )
+  {
+       // All models have been reset. Set the current model to 0
+       current_model = 0;
+       EEPROM.write(1, current_model);
+
+       calibrate();
+       model_defaults();
+       // The following does not yet work...
+       for ( i = 0; i < MAX_MODELS; i++)
+               write_model_settings(i);
+
+       
+       // After saving calibration data and model defaults,
+       // update the saved version-identifier to the current ver.
+       EEPROM.write(0, EEPROM_VERSION);
   }
+
+  // Read calibration values from EEPROM.
+  // This uses simple pointer-arithmetic and byte-by-byte
+  // to put bytes read from EEPROM to the data-struct.
+  p = (byte*)(void*)&input_cal;
+  for (i = 0; i < sizeof(input_cal_t); i++)
+               *p++ = EEPROM.read( EE_BASE_ADDR + i);
+
+  // Get the previously selected model from EEPROM.
+  current_model = EEPROM.read(1);
+  read_model_settings( current_model );
 }
 
-void write_settings(void)
+void read_model_settings(unsigned char mod_no)
 {
-  // Dummy. Not used anywhere. Will be fleshed out to save settings to EEPROM.
+  int model_address;
+  int i;
+  unsigned char v;
+  byte *p;
+
+  // Calculate the EEPROM start adress for the given model (mod_no)
+  model_address = EE_MDL_BASE_ADDR + (mod_no * sizeof(model_t));
+
+  // Do not try to write the model to EEPROM if it won't fit.
+  if ( INT_EEPROM_SIZE < (model_address + sizeof(model_t)) )
+  {
+       lcd.clear();
+       lcd.print("Aborting READ");
+    lcd.setCursor(0 , 1);
+    lcd.print("Invalid location");
+    delay(2000);  
+       return;
+  }
+  
+  lcd.clear();
+  lcd.print("Reading model ");
+  lcd.print( (int)mod_no );
+  
+  // Pointer to the start of the model_t data struct,
+  // used for byte-by-byte reading of data...
+  p = (byte*)(void*)&model;
+  for (i = 0; i < sizeof(model_t); i++)
+               *p++ = EEPROM.read( model_address++ );
+
+  serial_dump_model();
+
+  lcd.setCursor(0 , 1);
+  lcd.print("... Loaded.");
+  delay(1000);    
+}
+
+void write_model_settings(unsigned char mod_no)
+{
+  int model_address;
+  int i;
+  unsigned char v;
+  byte *p;
+
+  // Calculate the EEPROM start adress for the given model (mod_no)
+  model_address = EE_MDL_BASE_ADDR + (mod_no * sizeof(model_t));
+  
+  // Do not try to write the model to EEPROM if it won't fit.
+  if ( INT_EEPROM_SIZE < (model_address + sizeof(model_t)) )
+  {
+       lcd.clear();
+       lcd.print("Aborting SAVE");
+    lcd.setCursor(0 , 1);
+    lcd.print("No room for data");
+    delay(2000);  
+       return;
+  }
+  
+  lcd.clear();
+  lcd.print("Saving model ");
+  lcd.print( (int)mod_no);
+  
+  // Pointer to the start of the model_t data struct,
+  // used for byte-by-byte reading of data...
+  p = (byte*)(void*)&model;
+  
+  // Write/serialize the model data struct to EEPROM...
+  for (i = 0; i < sizeof(model_t); i++)
+               EEPROM.write( model_address++, *p++);
+               
+  lcd.setCursor(0 , 1);
+  lcd.print(".. done saving.");
+  delay(200);    
+}
+
+void serial_dump_model ( void )
+{
+  int i;
+  int model_address;
+  // Calculate the EEPROM start adress for the given model (mod_no)
+  model_address = EE_MDL_BASE_ADDR + (current_model * sizeof(model_t));
+  Serial.print("Current model:    ");
+  Serial.println( (int)current_model );
+  Serial.print("Models base addr: ");
+  Serial.println( EE_MDL_BASE_ADDR );
+  Serial.print("Model no:         ");
+  Serial.println( current_model, 10 );
+  Serial.print("Size of struct:   ");
+  Serial.println( sizeof( model_t) );
+  Serial.print("Model address:    ");
+  Serial.println( model_address );
+  Serial.print("End of model:     ");
+  Serial.println( model_address + sizeof(model_t) );
+
+  Serial.println();
+  
+  Serial.print("Channel reversions: ");
+  for ( i = 0; i<8; i++)
+  {
+       Serial.print(i);
+       Serial.print("=");
+       Serial.print(model.rev[i], 10);
+       Serial.print(" ");
+  }
+  Serial.println();
+  
+  Serial.print("DR1 inp 0: ");
+  Serial.println(model.dr[0]);
+  Serial.print("DR1 inp 1: ");
+  Serial.println(model.dr[1]);
+  Serial.print("DR1 LO val: ");
+  Serial.println(model.dr[4]);
+  Serial.print("DR1 HI val: ");
+  Serial.println(model.dr[5]);
+  Serial.print("DR2 inp 0: ");
+  Serial.println(model.dr[2]);
+  Serial.print("DR2 inp 1: ");
+  Serial.println(model.dr[3]);
+  Serial.print("DR2 LO val: ");
+  Serial.println(model.dr[6]);
+  Serial.print("DR2 HI val: ");
+  Serial.println(model.dr[7]);
+  
+  for (i=0; i<MAX_INPUTS; i++) {
+    Serial.print("Input #");
+    Serial.print(i);
+    Serial.print(" pct: ");
+    Serial.print(model.stick[i]);
+    Serial.print(" min: ");
+    Serial.print(input_cal.min[i]);
+    Serial.print(" max: ");
+    Serial.print(input_cal.max[i]);
+    Serial.println();
+  }  
 }
 
 void scan_keys ( void )
@@ -329,14 +560,61 @@ void scan_keys ( void )
 
 void process_inputs(void )
 {
-  int current_input, r0, r1, r2, adc_in;
-  for (current_input=0; current_input<=7; current_input++) {
+  int current_input, adc_in, fact;
+  float min, max;
+
+  for (current_input=0; current_input<MAX_INPUTS; current_input++) {
 
     mplx_select(current_input);
     adc_in = analogRead(0);
 
+       model.raw[current_input] = adc_in;
+       // New format on stick values
+    if ( adc_in < input_cal.center[current_input] )
+    {
+            max = input_cal.min[current_input];
+            min = input_cal.center[current_input];
+                       fact = -100;
+    } 
+    else 
+    {
+            min = input_cal.center[current_input];
+            max = input_cal.max[current_input];
+                       fact = 100;
+    }
+    model.stick[current_input] =  fact * ((float)adc_in - min ) / (max - min);
+    if ( model.rev[current_input] ) model.stick[current_input] *= -1;
+
+    // Old format on stick values...
+    /*
     model.stick[current_input] = ((float)adc_in - (float)input_cal.min[current_input]) / (float)(input_cal.max[current_input]-input_cal.min[current_input]);    
     if ( model.rev[current_input] ) model.stick[current_input] = 1.0f - model.stick[current_input];  
+    */
+
+    // Dual-rate calculation :D
+    // This is very repetitive code. It should be fast, but it may waste code-space.
+    float dr_val;
+    // Test to see if dualrate-switch #1 applies to channel...
+    if ( ( current_input == ( model.dr[0]-1) ) || ( current_input == ( model.dr[1]-1) ) )
+    {
+            if ( !keys[KEY_DR1] )
+                    dr_val = ((float)model.dr[4])/100.0; 
+            else
+                    dr_val = ((float)model.dr[5])/100.0;
+
+            model.stick[current_input] *= dr_val; 
+    }
+    else
+    // 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] )
+                    dr_val = ((float)model.dr[6])/100.0; 
+            else
+                    dr_val = ((float)model.dr[7])/100.0;
+
+            model.stick[current_input] *= dr_val; 
+    }
   }
 }
 
@@ -369,9 +647,17 @@ void ISR_timer(void)
   if ( do_channel )
   {
     set_ppm_output( HIGH );
-    long next_timer = (( chwidht * model.stick[cchannel] ) + chmin);
+
+       // New format on stick values
+    // model.stick contains percentages, -100% to 100% in float. To make the timer-handling
+    // here as simple as possible. We want to calc the channel value as a  "ratio-value",
+    // a float in the range 0..1.0. So, by moving the lower bound to 0, then cutting the
+    // range in half, and finally dividing by 100, we should get the ratio value.
+    // Some loss of presicion occurs, perhaps the algo' should be reconsidered :P
+    long next_timer = (( chwidht * ((model.stick[cchannel]+100)/200) ) + chmin);
     // Do sanity-check of next_timer compared to chmax ...
     while ( chmax < next_timer ) next_timer--;
+    while ( next_timer < chmin ) next_timer++;
     sum += next_timer;
 
     // Done with channel separator and value,
@@ -387,14 +673,13 @@ void serial_debug()
 {
   int current_input;
   for (current_input=0; current_input<=7; current_input++) {
-    int v = (int)(model.stick[current_input] * 100);
 
     Serial.print("Input #");
     Serial.print(current_input);
-    Serial.print(" value: ");
-    Serial.print(model.stick[current_input]);
     Serial.print(" pct: ");
-    Serial.print(v);
+    Serial.print(model.stick[current_input]);
+    Serial.print(" raw value: ");
+    Serial.print(model.raw[current_input]);
     Serial.print(" min: ");
     Serial.print(input_cal.min[current_input]);
     Serial.print(" max: ");
@@ -460,11 +745,11 @@ void dr_value()
        
        lcd.print( model.dr[pos] );
        
-       if ( keys[KEY_INC] ) {
+       if ( !keys[KEY_INC] ) {
                if ( model.dr[pos] < 100) model.dr[pos] += 5;
                return;
        }
-       else if ( keys[KEY_DEC] ) {
+       else if ( !keys[KEY_DEC] ) {
                if ( model.dr[pos] > -100) model.dr[pos] -= 5;
                return;
        }
@@ -489,6 +774,10 @@ void ui_handler()
       return; 
     }
     else if ( check_key(KEY_UP) && displaystate == TIMER ) { 
+      displaystate = CURMODEL; 
+      return; 
+    }
+    else if ( check_key(KEY_UP) && displaystate == CURMODEL ) { 
       displaystate = VALUES; 
       return; 
     }
@@ -527,8 +816,8 @@ void ui_handler()
         lcd.print("    ");
         lcd.setCursor(col, row);
         // Display uses percents, while PPM uses ratio....
-        int v = (int)(model.stick[current_input] * 100);
-        lcd.print(v);
+               // New format on stick values
+               lcd.print( (int)model.stick[current_input] );
       }
       break;
 
@@ -596,6 +885,18 @@ void ui_handler()
         }
                break;
 
+
+               
+       case CURMODEL:    
+      lcd.clear();
+      lcd.print("Model #: ");
+         lcd.print( (int)current_model );
+      lcd.setCursor(0 , 1);
+      lcd.print("NAME (not impl)");
+      break;
+
+
+         
     case MENU:
       lcd.clear();
       switch ( menu_mainstate )
@@ -748,4 +1049,4 @@ void ui_handler()
 
 
 
-\r
+