smart sensor code initial version

Dependencies:   mbed-src-KL05Z-smart-sensor

kl05-smart-sensor.cpp

Committer:
vincenxp
Date:
2019-03-26
Revision:
4:a2f83fac24bc
Parent:
3:d908dc9882d2

File content as of revision 4:a2f83fac24bc:

/****************************************************************************************
* 
*   MIT License (https://spdx.org/licenses/MIT.html)
*   Copyright 2018 NXP
*
*   MBED code for KL05Z-based "smart" current sensor, which measures current in 
*   three ranges. Intended to be used with an aggregator board which triggers sensors
*   on all instrumented rails and then sequentially reads the data from each out over I2C.
*   
*   Because there is no crystal on the board, need to edit source mbed-dev library
*   to use internal oscillator with pound-define:
*   change to "#define CLOCK_SETUP     0" in file:
*   mbed-dev/targets/TARGET_Freescale/TARGET_KLXX/TARGET_KL05Z/device/system_MKL05Z4.c
*
****************************************************************************************/

/****************************************************************************************
* Add a uart trace instead of I2C
* For the uart trace:
*   * add a timestamp (returns the timestamp of the current measure)
*   * do not average the measures:
*       + add a paramter to the existing function to set the number of samples to be
*           averaged (I2C legacy)
*   * set to 0 the different settling time:
*       + do not see dysfunction so far for the FET settling time neither for the voltage
*           divider
*       + do not see the need in case of the voltage or current measurement. It is
*           mentionned that this is for the B2902A settling time, so i guess this when the
*           SMU is used. It should not be the case by default anyway!
*
* Use few defines to instrument the code as below:
*
* | USEI2CNOTUART  |  DEBUG  |  TRACEPRINT  |  BUFFMEASURES  | comment
* | 1              |  0      |  0           |  0             | legacy mode - modify the KL25Z code to output the sensor number, voltage and current information
* | 0              |  0      |  0           |  0             | uart trace: print thru the uart console the result of the measures: timestamp, voltage, current
* | 0              |  0      |  1           |  0             | same as above but print also the time consumes to print those data!
* | 0              |  1      |  0           |  0             | uart trace: print thru the uart console many measures (see define below) but impact the sampling rate
* | 0              |  1      |  1           |  0             | same as above but uprint also the time consumes to print those data!
* | 0              |  0      |  0           |  1             | use a buffer to store the measures and print the entire buffer one it is full; improve the sampling rate but the buffer size is limited
*
****************************************************************************************/
#include <mbed.h>

// Select the I2C trace or the uart trace for debug
#define USEI2CNOTUART 0

// Custom setup in case of I2C
#define I2CCUSTOM 0

// If BUFFMEASURES == 1 : fill up a buffer of measures (timestamp, vdd & current only) and then send the whole buffer thru the uart console & loop
//                          * buffer size is limited to the 4k of RAM (1 measure of timestamp or volt or current is a float, each of 4 bytes)
#define BUFFMEASURES 0

// If TRACEPRINT == 1 : trace the time comnsumes by the printf to the uart console
#define TRACEPRINT 0

// If DEBUG == 1 : do not buffer the measures but send the measures thru the uart console (measures duration (volt + current), sensor number, timestamps, voltage, current, high current, mid current, low current
#define DEBUG 0

// set things up...
#if (USEI2CNOTUART == 1) 
I2CSlave slave(PTB4, PTB3);
#if (I2CCUSTOM == 1)
int n_meas=1; // number of averages when measuring...
#else
int n_meas=25; // number of averages when measuring...
#endif
#else
Serial uart(PTB3, PTB4); // tx, rx
int n_meas=1; // number of averages when measuring...
Timer timer; // I2C trace isn't prototype with timestamp
float timestamp;
#endif

#if (BUFFMEASURES == 1)
// Define BUFFERSIZE to 250
//   * 250 * 3 (float) * 4 (4 bytes for each float) = 3000 bytes almost 3kBytes out of the 4
#define BUFFERSIZE 200

// buffer to store timestamp, voltage & current
float buffer[BUFFERSIZE][3];
#endif

#ifndef BUFFERSIZE
#define BUFFERSIZE 0
#endif

// These will be used for identifying smart sensor build options:
// voltage range (0-3.3V, 0-6.6V, and 12V), and 
// current range (high: 4A max, and low: 1.65A max)
// (default pin pulls are pull up...)
// But this still needs to be implemented per schematic... 
DigitalIn gpio0(PTA3); // R8
DigitalIn C_RANGE(PTA4); // R9
DigitalIn V_RANGE0(PTA5); // R10
DigitalIn V_RANGE1(PTA6); // R11

// configure pins for measurements...
// analog inputs from sense amps and rail voltage (divider)...
AnalogIn HIGH_ADC(PTB10);
AnalogIn VRAIL_ADC(PTB11);
AnalogIn LOW1_ADC(PTA9);
AnalogIn LOW2_ADC(PTA8);
// outputs which control switching FETs...
DigitalOut VRAIL_MEAS(PTA7);    // turns on Q7, connecting voltage divider 
DigitalOut LOW_ENABLE(PTB0);    // turns on Q4, turning off Q1, enabling low measurement
DigitalOut LOW1(PTB2);          // turns on Q5, turning off Q2, disconnecting shunt R1
DigitalOut LOW2(PTB1);          // turns on Q6, turning off Q3, disconnecting shunt R2

//VB
//DigitalOut OPT3(PTB13);

// set initial, default I2C listening address...
// same one for all sensors so we don't need to individually program each one...
int address = 0x48 << 1;
// buffers for I2C communication
char buf[15], inbuf[10];
char obuf[10], cbuf[10]; // another buf for compressed output...

// variables...
int i, j, n=0;
bool waiting;
bool big_data = false; // flag to save time during ISR 
                        // only process uncompressed data if explicitly called for...

// these unions enable converting float val to bytes for transmission over I2C...
union u_tag {
     char b[4];
     float fval;
     int ival;
   } u, v;


// define measurement result and status variables...
float measurement1;
float measurement2;
char status=0;

float vref =3.3;
float factor_H  = vref / 0.8;
float factor_L1 = vref / (0.05 * 1000);
float factor_L2 = vref / (2 * 1000);

#if (USEI2CNOTUART == 1)
#if (I2CCUSTOM == 1)
int wait_mbbb = 0;
int wait_high = 0;
int wait_low1 = 0;
int wait_low2 = 0;
int wait_vrail = 0;
#else
int wait_mbbb = 5;
int wait_high = 250;
int wait_low1 = 250;
int wait_low2 = 500;
int wait_vrail = 200;
#endif
#else
int wait_mbbb = 5;//VB
int wait_high = 250;//VB
int wait_low1 = 250;//VB
int wait_low2 = 500;//VB
int wait_vrail = 200;//VB
#endif

// Store the 3 current sensors' value
float current[3];

/***********************************************************************************
*
*  FUNCTIONS FOR MEASURING CURRENT AND VOLTAGE
*
************************************************************************************/

void enableHighRange(){
    LOW_ENABLE = 0;     // short both low current shunts, close Q1
//VB    #if (USEI2CNOTUART == 1 && CUSTOM == 0)
    wait_us(wait_mbbb);         // delay for FET to settle... (make before break)
//VB    #endif
    LOW1 = 0; LOW2 = 0; // connect both shunts to make lower series resistance
    VRAIL_MEAS = 0;     // disconnect rail voltage divider 
//VB    #if (USEI2CNOTUART == 1 && CUSTOM == 0)   
    wait_us(wait_high);       // wait for B2902A settling... 
//VB    #endif
}

void enableLow1Range(){
    LOW1 = 0; LOW2 = 1; // disconnect LOW2 shunt so LOW1 can measure
//VB    #if (USEI2CNOTUART == 1 && CUSTOM == 0)
    wait_us(wait_mbbb);         // delay for FET to settle... (make before break)
//VB    #endif
    LOW_ENABLE = 1;     // unshort low current shunts, open Q1
    VRAIL_MEAS = 0;     // disconnect rail voltage divider
//VB    #if (USEI2CNOTUART == 1 && CUSTOM == 0)
    wait_us(wait_low1);       // wait for B2902A settling...
//VB    #endif
}

void enableLow2Range(){
    LOW1 = 1; LOW2 = 0; // disconnect LOW1 shunt so LOW2 can measure
//VB    #if (USEI2CNOTUART == 1 && CUSTOM == 0)
    wait_us(wait_mbbb);         // delay for FET to settle... (make before break)
//VB    #endif
    LOW_ENABLE = 1;     // unshort low current shunts, open Q1
    VRAIL_MEAS = 0;     // disconnect rail voltage divider    
//VB    #if (USEI2CNOTUART == 1 && CUSTOM == 0)
    wait_us(wait_low2);       // wait for B2902A settling...
//VB    #endif
}

void enableRailV(){
    VRAIL_MEAS = 1;     // turn on Q7, to enable R3-R4 voltage divider    
//VB    #if (USEI2CNOTUART == 1 && CUSTOM == 0)
    wait_us(wait_vrail);       // wait for divider to settle... 
                        // Compensation cap can be used to make 
                        // voltage at ADC a "square wave" but it is
                        // rail voltage and FET dependent. Cap will
                        // need tuning if this wait time is to be 
                        // removed/reduced. 
                        //
                        // So, as it turns out, this settling time and 
                        // compensation capacitance are voltage dependent
                        // because of the depletion region changes in the 
                        // FET. Reminiscent of grad school and DLTS. 
                        // Gotta love device physics...
//VB   #endif
}

// when a divider is present, turn it off to remove the current it draws...
void disableRailV(){
    VRAIL_MEAS = 0;     // turn off Q7, disabling R3-R4 voltage divider    
}

// measure high range current...
float measureHigh(int nbMeas){
    float highI=0;
    enableHighRange();
    for (i = 0; i < nbMeas; i++){
        highI += HIGH_ADC;
    }
    highI = factor_H * highI/nbMeas;
    #if (USEI2CNOTUART == 0)
    timestamp = timer.read();
    #endif
    return highI;
}

// mesaure mid range current...
float measureLow1(bool autorange, int nbMeas){
    float low1I=0;
    if (!autorange) enableLow1Range();
    for (i = 0; i < nbMeas; i++){
        low1I += LOW1_ADC;
    }
//VBrun6+run7    if (!autorange) enableHighRange();
    low1I = factor_L1 * low1I/nbMeas;
    #if (USEI2CNOTUART == 0)
    timestamp = timer.read();
    #endif
    return low1I;
}

// measure low range current...
float measureLow2(bool autorange, int nbMeas){
    float low2I=0;
    if (!autorange) enableLow2Range();
    for (i = 0; i < nbMeas; i++){
        low2I += LOW2_ADC;
    }
//VBrun6+run7    if (!autorange) enableHighRange();
    low2I = factor_L2 * low2I/nbMeas;
    #if (USEI2CNOTUART == 0)
    timestamp = timer.read();
    #endif
    return low2I;
}

// this function measures current, autoranging as necessary 
// to get the best measurement...
// hard coded values for switching ranges needs to be made 
// dynamic so 4.125A/1.65A ranges can be used...


float measureAutoI(int nbMeas){
    float tempI;
//VBrun5+run6+run7    enableHighRange();  // this should already be the case, but do it anyway...
    #if (USEI2CNOTUART == 0)
    current[0] = 0;
    current[1] = 0;
    current[2] = 0;
    #endif
    tempI = measureHigh(nbMeas);
    #if (USEI2CNOTUART == 0)
    current[0] = tempI;
    #endif
    status = 1;
    // if current is below this threshold, use LOW1 to measure... 
    if (tempI < 0.060) {
//VBrun5+run6+run7        enableLow1Range();
        tempI = measureLow1(false, nbMeas); // call function 
        #if (USEI2CNOTUART == 0)
        current[1] = tempI;
        #endif
        status = 2;
        // if current is below this threshold, use LOW2 to measure...
//VBrun7        if (tempI < 0.0009){
        if (tempI < 0.0015){
//VBrun5+run6+run7            enableLow2Range();  // change FETs to enable LOW2 measurement...
            tempI = measureLow2(false, nbMeas);
            #if (USEI2CNOTUART == 0)
            current[2] = tempI;
            #endif
            status = 3;
        }
//VBrun5    enableHighRange();
    enableHighRange();
    }
    return tempI;
}


// measure the rail voltage, default being with 
// need to add logic for 5V/12V/arbitraryV range...
float measureRailV(int nbMeas){
    float railv=0;
    enableRailV();  // switch FETs so divider is connected...
    for (i = 0; i < nbMeas; i++){
        railv += VRAIL_ADC;  // read voltage at divider output...
    }
    disableRailV();     // now disconnect the voltage divider
    railv = vref * (railv/nbMeas);    // compute average 
                        // Convert to voltage by multiplying by "mult"
    if (vref==12.0) railv = railv * 0.24770642201;
    return railv;
}





#if (USEI2CNOTUART == 1) 
/***********************************************************************************
*
*  INTERRUPT SERVICE ROUTINE
* 
************************************************************************************/

// measurements are only taken during ISR, triggered by aggregator on IRQ line...
// this could have been implemented differently, but this was simple...
// If coulomb counting is desired, this code would probably need to change...
void interrupt_service(){
    // make measurement... (this is currently just a placeholder...)
    status = 0; // clear status byte.. allow measurement functions to modify...
    measurement1 = measureAutoI(n_meas);
    measurement2 = measureRailV(n_meas);
    n += 10; //increment interrupt counter...
    
    // prepare data for transport, in the event that aggregator asks for short format... 
    
    // compressed data format, 4 bytes total, with a status nibble
    // Each byte has form:  (s*128) + (digit1*10) + (digit2), which fits into 8 bits
    // Each value is composed of two bytes with form above, first three digits are 
    // the mantissa and the last digit is the exponent. Two values is four bytes, so 
    // that allows four status bits to be included.    
    sprintf(buf, "%4.2e", measurement1);
    buf[10] = (buf[0]-48)*10 + (buf[2]-48); // no decimal, we use fixed point... 
    buf[11] = (buf[3]-48)*10 + (buf[7]-48); // no 'e', and no exp sign, since we know that's negative...
    sprintf(buf, "%4.2e", measurement2);
    buf[12] = (buf[0]-48)*10 + (buf[2]-48); // no decimal, we use fixed point... 
    buf[13] = (buf[3]-48)*10 + (buf[7]-48); // no 'e', and no exp sign, since we know that's negative...
                
    // add in the four status bits... 
    buf[10] = buf[10] | (status & 1<<3)<<4;
    buf[11] = buf[11] | (status & 1<<2)<<5;
    buf[12] = buf[12] | (status & 1<<1)<<6;
    buf[13] = buf[13] | (status & 1<<0)<<7;

    // Convert each 32-bit floating point measurement value into 4 bytes 
    // using union, so we can send bytes over I2C...
    u.fval = measurement1; 
    v.fval = measurement2;
    
    // now fill the buffers with the stuff generated above so it can be sent over I2C:
    
    // stuff latest measurement float values into bytes of buf for next transmission...
    // buffer format: 4 bytes = (float) V, 4 bytes = (float) I, 1 byte status
    for (j=0; j<4; j++) buf[j] = u.b[j]; // voltage
    for (j=0; j<4; j++) buf[j+4] = v.b[j]; // current
    buf[8] = status; 

    // transfer compressed measurement data to output buffers...
    for (j=0; j<9; j++) obuf[j] = buf[j];
    for (j=0; j<4; j++) cbuf[j] = buf[j+10];
    
} //ISR
#endif




/***********************************************************************************
*
*  MAIN CODE
*
************************************************************************************/

// main...
int main() {

  buf[0] = 0;

  #if (USEI2CNOTUART == 0)
  float volt = 0;
  float curr_sensor = 0;
  #if (DEBUG == 1)
    int sensor = 0;
    int timeStart=0, timeEnd=0;
  #endif
  #if (TRACEPRINT == 1)
  float before_printf=0, after_printf=0;
  #endif

  uart.baud(115200);
  uart.printf("\r\nData from current sensor...\n");
  uart.printf("\r\nNumber of sample(s) for averaging measurement: %d", n_meas);
  uart.printf("\r\nModes:");
  if (DEBUG) {
    uart.printf("\r\n  DEBUG: YES");
  } else {
    uart.printf("\r\n  DEBUG: NO");
  }
  if (TRACEPRINT) {
    uart.printf("\r\n  TRACEPRINT: YES");
  } else {
    uart.printf("\r\n  TRACEPRINT: NO");
  }
  if (BUFFMEASURES) {
    uart.printf("\r\n  BUFFMEASURES: YES");
    uart.printf("\r\n    buffer size: %d\n", BUFFERSIZE);
  } else {
    uart.printf("\r\n  BUFFMEASURES: NO");
  }

  uart.printf("\r\nDelay for FET switching: %d us", wait_mbbb);
  uart.printf("\r\nDelay for HIGH current sensor switching: %d us", wait_high);
  uart.printf("\r\nDelay for MID current sensor switching: %d us", wait_low1);
  uart.printf("\r\nDelay for LOW current sensor switching: %d us", wait_low2);
  uart.printf("\r\nDelay for voltage sensor switching: %d us", wait_vrail);


  // turn on pull ups for option resistors, since resistors pull down pins
  C_RANGE.mode(PullUp);
  V_RANGE0.mode(PullUp);
  V_RANGE1.mode(PullUp);
  // change calculation multipliers according to option resistors:
  i = V_RANGE1*2 + V_RANGE0;
  if (i==1) vref = 6.6;
  if (i==2) vref = 12.0;
  if (C_RANGE==0) {
    factor_H  = vref / 2.0;
    factor_L1 = vref / (0.15 * 1000);
    factor_L2 = vref / (15 * 1000);
  }

  uart.printf("\r\n\nFactor_H: %f", factor_H);
  uart.printf("\r\nFactor_L1: %f", factor_L1);
  uart.printf("\r\nFactor_L2: %f", factor_L2);


//VB to debug the latency to compensate the FET peak current
#if 0
    float tempI=0;

    enableHighRange();  // this should already be the case, but do it anyway...
    #if (USEI2CNOTUART == 0)
    current[0] = 0;
    current[1] = 0;
    current[2] = 0;
    #endif
    tempI = measureHigh(1);
    #if (USEI2CNOTUART == 0)
    current[0] = tempI;
    #endif
    status = 1;
    // if current is below this threshold, use LOW1 to measure... 
    if (tempI < 0.060) {
      enableLow1Range();
      tempI = measureLow1(false, 1); // call function 
      #if (USEI2CNOTUART == 0)
      current[1] = tempI;
      #endif
      status = 2;
      // if current is below this threshold, use LOW2 to measure...
      if (tempI < 0.0009){
        while (1) {
          timer.reset();
          timer.start();
          volt = measureRailV(n_meas);
          enableLow2Range();  // change FETs to enable LOW2 measurement...
          for (int idx_meas = 0; idx_meas < BUFFERSIZE; idx_meas++) {
            enableLow2Range();
            wait_us(100);
            tempI = factor_L2 * LOW2_ADC;
            //wait_us(500);
            enableHighRange();
            timestamp = timer.read();
            buffer[idx_meas][0] = timestamp;
            buffer[idx_meas][1] = volt;
            buffer[idx_meas][2] = tempI;
          }
          for (int idx_meas = 0; idx_meas < BUFFERSIZE; idx_meas++) {
            uart.printf("\r\n%d %f %f %f", idx_meas, buffer[idx_meas][0], buffer[idx_meas][1], buffer[idx_meas][2]);
          }
        }
      }
    }
#else
//End of VB

  #if (DEBUG == 1)
    #if (TRACEPRINT == 0)
    uart.printf("\r\n\nMeasuresDuration(us)(V,I) sensor timestamp(s) Voltage(V) Current(A) HighSensor(A) MidSensor(A) LowSensor(A)");
    #else
    uart.printf("\r\n\nMeasuresDuration(us)(V,I) sensor timestamp(s) Voltage(V) Current(A) HighSensor(A) MidSensor(A) LowSensor(A) UartPrintDuration(us)");
    #endif
  #elif (BUFFMEASURES == 1)
    uart.printf("\r\n\nidx timestamp(s) Voltage(V) Current(A)");
  #else
    #if (TRACEPRINT == 0)
    uart.printf("\r\n\ntimestamp(s) Voltage(V) Current(A)");
    #else
    uart.printf("\r\n\ntimestamp(s) Voltage(V) Current(A) UartPrintDuration(us)");
    #endif
  #endif
  
  #if (BUFFMEASURES == 0)
  timer.reset();
  timer.start();
  #endif

  while (1) {

    #if (DEBUG == 1)
    timeStart = timer.read_us();
    #endif
    #if (BUFFMEASURES == 1)
    timer.reset();
    timer.start();
    for (int idx_meas = 0; idx_meas < BUFFERSIZE; idx_meas++) {
      volt = measureRailV(n_meas);
      curr_sensor = measureAutoI(n_meas);
      buffer[idx_meas][0] = timestamp;
      buffer[idx_meas][1] = volt;
      buffer[idx_meas][2] = curr_sensor;
    }
    #else
    volt = measureRailV(n_meas);
    curr_sensor = measureAutoI(n_meas);
    #endif
    #if (DEBUG == 1)
    timeEnd = timer.read_us();
    #endif
    #if (TRACEPRINT == 1)
    before_printf = timer.read();
    #endif
    #if (DEBUG == 1)
    uart.printf("\r\n%d %d %f %f %f %f %f %f", timeEnd-timeStart, sensor, timestamp, volt, curr_sensor, current[0], current[1], current[2]);
    #elif (BUFFMEASURES == 1)
    for (int idx_meas = 0; idx_meas < BUFFERSIZE; idx_meas++) {
      uart.printf("\r\n%d %f %f %f", idx_meas, buffer[idx_meas][0], buffer[idx_meas][1], buffer[idx_meas][2]);
    }
    #else
     uart.printf("\r\n%f %f %f", timestamp, volt, curr_sensor);
    #endif
    #if (TRACEPRINT == 1)
    after_printf = timer.read();
    uart.printf(" %f", after_printf - before_printf);
    #endif
  }
#endif
#else  
   
   wait_us(200);   // wait before reassigning SWD pin so as to not get locked out...
   DigitalIn my_select(PTA2); // this is the individual line to each sensor...

   
   while (my_select) {
       // wait here until aggregator signals us for address reassignment...  
   } // end while

   // Need to wait to set up I2C until after we've come out of wait loop above...
   // Setting up the I2C earlier starts it listening on the bus even if it's not 
   // being polled, which means that multiple sensors will respond, hanging the bus...
   slave.frequency(400000); // go as fast as possible...
   slave.address(address);  // listen on the default address...
   
   while (!my_select) {
      // listen for new address, then repeat it back aggregator...  
      waiting = true;
      while (waiting && !my_select){
         int i = slave.receive();
         switch (i) {
            case I2CSlave::WriteAddressed:
               slave.read(buf, 1);
               // we just got our new address, provided my_select subsequently changes...
               waiting = false;
               break;
            case I2CSlave::ReadAddressed:
               slave.write(buf, 1); 
               // write back our new address to confirm we go it...
               waiting = false;
               break;
         }
       }
   } // end while, waiting for address reassignment...  

   // we fell out of loop above, so now change our I2C address to the newly assigned one...
   // this newly assigned address will not change until we're reset...
   slave.address(buf[0]);
   
   // enable interrupts, need to wait until after getting new I2C address, 
   // since we cannot respond until we have our new address...
   InterruptIn triggerIRQ(PTA0);        // this is the ganged interrupt signal to all sensors
   triggerIRQ.rise(&interrupt_service); // attach the service routine...
   
   // make sure we can receive at the new address...
   // this isn't absolutely necessary, but it's a good check...
   // if this is removed, the corresponding write in the aggregator code needs to go, too
   waiting = true;
   while (waiting){
      i = slave.receive();
      switch (i) {
         case I2CSlave::ReadAddressed:
            slave.write(buf, 1);
            waiting = false;
            break;
         case I2CSlave::WriteAddressed:
            slave.read(buf, 1);
            waiting = false;
            break;
      }
   }
   

/******************************************************************************/
   // this is the main loop: 
   // We just sit here and wait for I2C commands and triggers on IRQ line...
   //
   // A triggerIRQ causes measurements in ISR, aggregator must wait at least  
   // long enough for it to finish before reading back the result(s).   
   //
   // results are sent in 9 byte packets: 4 for voltage, 4 for current, and one status,
   // where voltage and current are floats in units of V and A. Status byte will be 
   // packed with something later, yet to be defined. 
   // 
   // What should be implemented are additional things like setting and reading
   // back the delays in the GPIO control functions, turning on and off averaging
   // so we can see what the min and max values are (which also helps tell if we
   // don't have enough delay in the GPIO functions), and possibly other stuff 
   // not thought of yet... Definitely not an exercise for this pasta programmer...
   //
   while (1) {
         i = slave.receive();
         switch (i) {
            case I2CSlave::ReadAddressed:
              if (my_select){   // if high, send uncompressed format...             
                slave.write(obuf, 9);
                waiting = false;
              } else {          // if low, send compressed format...
                slave.write(cbuf, 4);
                waiting = false;
              }
              break;
            case I2CSlave::WriteAddressed:
//               slave.read(inbuf, 1);
//               waiting = false;
//               break;
              if (my_select){   // if high, receive two bytes...             
                 slave.read(inbuf, 2);
                 waiting = false;
                 // if we're here, we've recieved two words, so we update the 
                 // appropriate parameter.
                 switch (inbuf[0]) {
                    case 0:
                        wait_mbbb = inbuf[1];
                        break;
                    case 1:
                        wait_high = inbuf[1]*8;
                        break;
                    case 2:
                        wait_low1 = inbuf[1]*8;
                        break;
                    case 3:
                        wait_low2 = inbuf[1]*8;
                        break;
                    case 4: 
                        wait_vrail = inbuf[1]*8;
                        break;
                    case 5:
                        n_meas = inbuf[1];
                        break;
                 } // switch
                 // and since we're still here, place the new values
                 // in obuf so we can read back all paramters values
                 obuf[0] = wait_mbbb;
                 obuf[1] = wait_high/8;
                 obuf[2] = wait_low1/8;
                 obuf[3] = wait_low2/8;
                 obuf[4] = wait_vrail/8;
                 obuf[5] = n_meas;
                 obuf[6] = 0;
                 obuf[7] = 0;
                 obuf[8] = 0;
              } else {        ;// if low, receive one byte...
                slave.read(inbuf, 1);
                waiting = false;
              }
         } // switch         
   }  // while(1)
 #endif  
   
}