this version has all of Jim's fixes for reading the GPS and IMU data synchronously

Dependencies:   MODSERIAL SDFileSystem mbed SDShell CRC CommHandler FP LinkedList LogUtil

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers ADIS16488.h Source File

ADIS16488.h

00001 
00002 
00003 
00004 //set up the SPI on pins 5, 6, 7 to read from the ADIS16488
00005 SPI spi(p5, p6, p7); // mosi (DIN), miso (DOUT), sclk (CLK)
00006 DigitalOut ADIS_CS(p8);     //Chip Select for the ADIS SPI
00007 InterruptIn ADIS_DR(p28);   //DataReady interrupt connected to DIO2 for ADIS
00008 DigitalOut ADIS_RST(p20);   //ADIS reset pin
00009 
00010 bool IMUDataReady = false;
00011 int IMURecordCounter = 0;
00012 //see Table 9 from page 11 of the ADIS16488 spec 
00013 //see fig 15 of spec -- note the low byte of the regsiter word is always zero
00014 // X_DELTANG_LOW, Y_DELTANG_LOW, X_DETANG_LOW, X_DELTVEL_LOW, Y_DELTVEL_LOW, Z_DELTVEL_LOW
00015 unsigned short LOW_REGISTER[]  = {0x4000, 0x4400, 0x4800, 0x4C00, 0x5000, 0x5400};   
00016 // X_DELTANG_HIGH, Y_DELTANG_HIGH, X_DETANG_HIGH, X_DELTVEL_HIGH, Y_DELTVEL_HIGH, Z_DELTVEL_HIGH
00017 unsigned short HIGH_REGISTER[] = {0x4200, 0x4600, 0x4A00, 0x4E00, 0x5200, 0x5600}; 
00018 
00019 volatile unsigned long IMUtimeFrom1PPS = 0;
00020 volatile int IMUClockCounter = 0;            //counter for IMU samples per sec
00021 
00022 union WD { long dataWord; unsigned short pt[2];} wd;
00023 
00024 //IMU records are buffered in the IMUDataReady ISR
00025 const unsigned char IMUrecArraySize = 5;
00026 
00027 #pragma pack(1)
00028 struct IMUREC
00029 {
00030     unsigned long GPSTime;
00031     long dataWord[6];
00032 };
00033 
00034 IMUREC imuPing[IMUrecArraySize];
00035 IMUREC imuPong[IMUrecArraySize];
00036 IMUREC tempRec;
00037 volatile bool fillingPingWritingPong = true;
00038 
00039 unsigned long maxDelIMUmsecs = 0;
00040 unsigned long delIMUmsecs = 0;      
00041 unsigned long lastIMUmsecs = 0; 
00042 
00043 void IMUDataReadyISR(void)
00044 {   
00045     IMURecordCounter++;
00046    
00047     IMUtimeFrom1PPS = timeFromPPS.read_us();    //timer reset to zero in the the GPS 1PPS
00048     
00049     //    GPSTimemsecs is taken from the GPS message -- but that may follow the 1PPS by several millisecs
00050     //    PPSTimeOffset is set to zero after the time becomes available
00051     //    so PPSTimeOffset accounts for the possible >1sec between the current IMU time and the time of the last PPS
00052     //    this also accounts for a missed GPS time message that holds the GPS time  
00053     tempRec.GPSTime = GPSTimemsecs + PPSTimeOffset*1000 + IMUtimeFrom1PPS/1000.0;
00054     
00055     //tempRec.GPSTime = PPSCounter*1000 + timeFromPPS.read_us()/1000;
00056     
00057     //test to see if we are ready to write the current IMU data buffer and swap the ping-pong buffer
00058     if (IMUClockCounter == IMUrecArraySize ) 
00059     {
00060         IMUDataReady = true;  //signals the write in the main loop
00061         fillingPingWritingPong = !fillingPingWritingPong; //swap the ping-pong buffer
00062         IMUClockCounter = 0;  //reset the IMU record counter
00063     }
00064   
00065     //
00066     spi.write((int) HIGH_REGISTER[0]); //next read will return results from HIGH_REGITER[0]
00067     for (int i=0; i<6; i++)  //read the 6 rate and accel variables
00068     {
00069         wd.pt[1] = (unsigned short)spi.write((int) LOW_REGISTER[i]); 
00070         if (i<5)  // dont this on the last because this was pre-called
00071         {   wd.pt[0] = (unsigned short)spi.write((int) HIGH_REGISTER[i+1]); }
00072         
00073         if ( fillingPingWritingPong) tempRec.dataWord[i] = wd.dataWord; //data word is a signed long
00074         else                         tempRec.dataWord[i] = wd.dataWord; //data word is a signed long
00075     }          
00076     //
00077     
00078     //fill the correct buffer ping or pong
00079     if (fillingPingWritingPong)  imuPing[IMUClockCounter] = tempRec;
00080     else                         imuPong[IMUClockCounter] = tempRec;
00081     //
00082     
00083     IMUClockCounter++;
00084  
00085     
00086     return;
00087 } 
00088 
00089 void setupADIS(void)
00090 {
00091     ADIS_DR.mode(PullDown);
00092     ADIS_RST = 0;
00093     
00094     //  set the IMU dataReady ISR
00095     ADIS_DR.rise(&IMUDataReadyISR);
00096     
00097     // Setup the mbed SPI for 16 bit data, high steady state clock,
00098     // second edge capture, with a 1MHz clock rate
00099     spi.format(16,3);
00100     spi.frequency(5000000);   
00101     
00102     ADIS_CS = 1;  //CS must be set high before it goes low cause the enable is the transition
00103     ADIS_RST = 1;
00104     wait(0.5);
00105     ADIS_CS = 0; //set the Chip select low to enable the IMU SPI access
00106     
00107     spi.write((int)0x8003);  //change to page 3
00108     
00109     //change the DECRATE to 98.4 Hz (this is also in page 3)
00110     //the 8 sets the high bit to 1 indicating a write to a register
00111     // The C abd D designate the registers for the DECRATE of Page 3
00112     // The 0x17 sets the rate to:  2460/(23+1) = 102.5Hz
00113     // The 0x18 sets the rate to:  2460/(24+1) =  98.4Hz
00114     //spi.write((int)0x8C17);    //write high byte  (only page number can be written in a single byte)
00115     spi.write((int)0x8C30);    //write high byte  (only page number can be written in a single byte)
00116     spi.write((int)0x8D00);    //write the low byte of DECRATE 
00117     
00118     //to set the GPS VARF clock as the input synch clock for the IMU
00119     //the high byte is CD indicating the synch is enabled on the rising edge of the input clock  
00120     //spi.write((int)0x86CD);    //write high byte to register 0x06
00121     //spi.write((int)0x8700);    //write the low byte of 00 to registed 0x07
00122     
00123     //change the page to 0 to get the data
00124     spi.write((int)0x8000);  //change to page 0
00125 
00126 }
00127 
00128