Here is that sketch with PPS added for reference. Using Pin 6 for PPS interrupt from GPS.
It runs as before starting at 17 then drops 8 SRD's to 9 to try to synch. Ends with 30 seconds of cycles on SRD==9, then continues showing the most recent count of CPU cycles between PPS reports.
In those 30 seconds my MPU9250 ends up slipping in 1, 2, and then 3 extra IMU data sets past the PPS signal.
This 180 Mhz Teensy only getting about this many between PPS's right now :: >>>>>>>>> ----- PPS !!!! >>>>>> 179997501
NOTE: While IMU reads are active it goes over "PPS !!!! >>>>>> 179997519" and when IMU data stops being pulled it drops as low as "PPS !!!! >>>>>> 179997471". Of course 50 parts in 179997501 is only about 0.2778 millisecond. And as noted using the system micros() clock would - slip based on the same crystal change over time, add 5-7 times more overhead to establish each time, and then could be high or low a full microsecond any time.
I quickly set up synchronization on the IMU reports as SRD is changed - the IMU crystal doesn't report on 'Space Seconds' ... i.e. as reported by the GPS you can see that in the end with SRD==9 the IMU reports that should be 10 ms apart are showing as arriving in 9.990 ms. NOTE: using 'measured' cycles between the PPS did make the IMU timed readings about 99% 9.990 ms rather than a higher percentage of 9.989 as with prior post code - where sample periods like the one shown are dominated by 9989 ( 9.989 ms ) .
Seems to show that using the cycle counter to track incoming IMU _isr() hits looks good. But trying to constrain those to the ticks of a clock would be chasing your tail. Best to know when they arrive and know how long between.
In this sketch I did adjust the cycle counts expected per second from F_CPU to those observed between PPS _isr()'s, not any average - just last observed updated each second as printed.
Let me know if this fails to properly show on your system, or if I made some faults in the process/analysis.
I should really tweak the crystal on this Teensy - as I'm getting cheated 2,500 cycles every second! I lose a whole CPU second every 20 hours! That number I noted 2,500 (post #2) above seems to be the right number I saw months back on this T_3.6 when it was powered down - so if I adjusted ( assuming it is an internal sticky adjustment ) - it should stay in that range.
Code:
#include "MPU9250.h"
// https://forum.pjrc.com/threads/53372-Microsecond-Level-Synced-Clock?p=184835&viewfull=1#post184835
// IMU Declares :: Adjust for your device
#define IMU_BUS Wire //Wire // SPI
#define IMU_ADDR 0x69 //0x69 // 0x68 // SPI 9
#define IMU_SCL 47 //47 // 0x255
#define IMU_SDA 48 //48 // 0x255
#define IMU_SPD 1200000 //1000000 // 0==NULL or other
#define IMU_INT_PIN 50 //50 // 1 // 14
const byte PPSinterruptPin = 6;
int pps = 0;
uint32_t CntPPS = 0; // debug
uint32_t CurrPPSsec = F_CPU; // debug
volatile bool PPS_set = false;
MPU9250 Imu(IMU_BUS, IMU_ADDR, IMU_SCL, IMU_SDA, IMU_SPD);
int status;
uint16_t vvIMU_SRD = 17;
uint16_t IMU_HZ = (1000 / (1 + vvIMU_SRD));
volatile int newIMUData;
volatile uint32_t ccTimeNow_IMU = 0;
volatile uint32_t Cnt_IMU = 0;
uint32_t CntIMU = 0; // debug
elapsedMillis emSec;
void setup() {
Serial.begin(19200);
while ( !Serial && millis() < 4000 );
Serial.println("\n" __FILE__ " " __DATE__ " " __TIME__);
ARM_DEMCR |= ARM_DEMCR_TRCENA;
ARM_DWT_CTRL |= ARM_DWT_CTRL_CYCCNTENA;
// start communication with IMU
status = Imu.begin();
if (status < 0) {
Serial.println("IMU initialization unsuccessful");
Serial.println("Check IMU wiring or try cycling power");
Serial.print("Status: ");
Serial.println(status);
while (1) {}
}
Imu.setDlpfBandwidth(MPU9250::DLPF_BANDWIDTH_20HZ);
//Imu.setDlpfBandwidth(MPU9250::DLPF_BANDWIDTH_41HZ);
Imu.setSrd(vvIMU_SRD);
pinMode(PPSinterruptPin, INPUT);
attachInterrupt(PPSinterruptPin, PPSInterruptCall, RISING);
Imu.enableDataReadyInterrupt();
pinMode(IMU_INT_PIN, INPUT);
attachInterrupt(IMU_INT_PIN, runFilter, RISING);
Imu.setSrd(vvIMU_SRD);
Serial.print("\n-----______ IMU_SRD >>\t");
Serial.print(vvIMU_SRD);
Serial.println("\t-----______\t");
emSec = 0;
}
volatile bool IMU_enable = false;
void loop(void)
{
static uint32_t ccTimeLast_IMU;
static uint32_t ccTimeLast_PPS = 0;
if ( true == PPS_set ) {
PPS_set = false;
IMU_enable = true;
Serial.print("\n\n >>>>>>>>> ----- PPS !!!! >>>>>>\t");
Serial.println( CntPPS - ccTimeLast_PPS );
if ( 0 == ccTimeLast_PPS ) {
CntIMU = 0;
}
ccTimeLast_PPS = CntPPS;
}
if (newIMUData == 1) {
uint32_t Tmp_ccTimeNow_IMU = ccTimeNow_IMU;
if ( !( CntIMU % IMU_HZ ) ) {
Serial.print("\n\n-----\t");
Serial.print(CntIMU);
Serial.print("\t");
Serial.print(emSec);
Serial.print(" <-----\t");
emSec = 0;
}
Serial.print(( Tmp_ccTimeNow_IMU - ccTimeLast_IMU) / (CurrPPSsec / 1000000));
ccTimeLast_IMU = Tmp_ccTimeNow_IMU;
Serial.print("\t");
if ( !( CntIMU % 10 ) ) Serial.println();
newIMUData = 0;
CntIMU++;
float ax; float ay; float az; float gx; float gy; float gz; float hx; float hy; float hz; bool MagD;
Imu.readSensorPMD( &ax, &ay, &az, &gx, &gy, &gz, &hx, &hy, &hz, &MagD);
}
if ( (CntIMU > (4 * IMU_HZ)) && (vvIMU_SRD > 10) ) {
vvIMU_SRD -= 8;
emSec = 0;
Imu.setSrd(vvIMU_SRD);
CntIMU = 0;
Serial.print("\n------------------------------______ IMU_SRD >>\t");
Serial.print(vvIMU_SRD);
Serial.println("\t-----______\t");
IMU_HZ = (1000 / (1 + vvIMU_SRD));
ccTimeLast_PPS = 0;
IMU_enable = false;
}
if ( CntIMU > 3000 ) {
while ( 1 ) {
if ( true == PPS_set ) {
PPS_set = false;
IMU_enable = true;
Serial.print("\n >>>>>>>>> ----- PPS !!!! >>>>>>\t");
CurrPPSsec = CntPPS - ccTimeLast_PPS;
Serial.println( CurrPPSsec );
ccTimeLast_PPS = CntPPS;
}
}
}
}
void runFilter() {
ccTimeNow_IMU = ARM_DWT_CYCCNT;
newIMUData = IMU_enable;
Cnt_IMU++;
}
void PPSInterruptCall() {
CntPPS = ARM_DWT_CYCCNT;
PPS_set = true;
pps += 1;
}