void ee_writeStr(char *s, int n, int addr)
{
  while(lockset(eei2cLock));
  ee_putStr(s, n, addr);
  lockclr(eei2cLock);
  return;
}
void da_setupScale()
{
  high(pinCh0);
  high(pinCh1);

  pause(5);

  float vA = ad_volts(0);
  float vB = ad_volts(1);

  //print("%f %f\n", vA, vB);

  if( (vA > 3.1 && vA < 3.5 && vB > 3.1 && vB < 3.5))
  {
    for(int i = 0; i < 39; i++)
    {
      vA += ad_volts(0);
      vB += ad_volts(1);
    }
    vA /= 40;
    vB /= 40;

    vA = 3.3 / vA;
    vB = 3.3 / vB;

    int addr = _abvolts_EE_start_;

    ee_putStr("abvolts", 8, addr);
    addr += 8;

    ee_putFloat32(vA, addr);
    addr += 4;

    ee_putFloat32(vB, addr);
    addr += 4;

    low(pinCh0);
    low(pinCh1);

    input(pinCh0);
    input(pinCh1);

    putStr("Ch0 scalar = ");
    putFloat(vA);
    putStr("\nCh1 scalar = ");
    putFloat(vB);
    putChar('\n');
    putChar('\n');

    abvolts_scale[0] = vA;
    abvolts_scale[1] = vB;
  }
  else
  {
    putStr("Error! Something went wrong. Check your circuit and power source.");
  }
}
int main(void)                                // main function
{
  int addr = 64000;                           // Pick EEPROM base address. 

  ee_putInt(42, addr);                        // 42 -> EEPROM address 64000
  int eeVal = ee_getInt(addr);                // EEPROM address 64000 -> eeVal
  print("myVal = %d\n", eeVal);               // Display result

  ee_putStr("hello!\n", 7, addr + 4);         // hello!\n -> EEPROM 64004..64010
  char s[7];                                  // Character array to hold string
  ee_getStr(s, 7, addr + 4);                  // EEPROM 64004..64010 -> s[0]..s[5]
  print("s = %s", s);                         // Display s array
}
int main(void)                                // main function
{
  int addr = 32769;                           // Pick EEPROM base address. 

  ee_putInt(42, addr);                        // 42 -> EEPROM address 32769
  int eeVal = ee_getInt(addr);                // EEPROM address 32769 -> eeVal
  print("myVal = %d\n", eeVal);               // Display result

  ee_putStr("hello!\n", 8, addr + 4);         // hello!\n -> EEPROM 32773..32780
  char s[8];                                  // Character array to hold string
  ee_getStr(s, 8, addr + 4);                  // EEPROM 32773..32780 -> s[0]..s[7]
  print("s = %s", s);                         // Display s array
}
void drive_servoPins(int servoPinLeft, int servoPinRight)          // drivePins function
{
  //abd_sPinL = servoPinLeft;                                       // Local to global assignments
  //abd_sPinR = servoPinRight;
  //if(!abd_us) abd_us = CLKFREQ/1000000; 

  int eeAddr = _ActivityBot_EE_Start_  + _ActivityBot_EE_Pins_;
  unsigned char pinInfo[8] = {'s', 'p', 'L', 12, ' ', 'R', 13, ' '};  
  pinInfo[3] = (char) servoPinLeft;
  pinInfo[6] = (char) servoPinRight;

  ee_putStr(pinInfo, 8, eeAddr);
  /*
  if(!abd_intTabSetup)
  {
    interpolation_table_setup();
  }
  */
}
void drive_encoderPins(int encPinLeft, int encPinRight)          // drivePins function
{
  //abd_ePinL = encPinLeft;
  //abd_ePinR = encPinRight;
  //if(!abd_us) abd_us = CLKFREQ/1000000; 

  int eeAddr = 8 + _ActivityBot_EE_Start_  + _ActivityBot_EE_Pins_;
  unsigned char pinInfo[8] = {'e', 'p', 'L', 14, ' ', 'R', 15, ' '};  
  pinInfo[3] = (char) encPinLeft;
  pinInfo[6] = (char) encPinRight;

  ee_putStr(pinInfo, 8, eeAddr);

  /*
  if(!abd_intTabSetup)
  {
    interpolation_table_setup();
  }
  */
}