Why sensor reading is not 1kHz?

Hi all,

I’m reading IMU data through masterboard in 1kHz. The IMU data shows repeated values every two measurement, which implies effective sampling frequency of 500Hz. Is it supposed to be 1kHz as described in the paper? Do I miss something?

I’m using masterboard firmware SDK: Partial support of the new Power-Board hardware by thomasfla · Pull Request #98 · open-dynamic-robot-initiative/master-board · GitHub

Thanks in advance!

An

Hi An,

The IMU provides certain quantities only at 500 Hz (especially the ones from the internel external kalman filter like orientation). Therefore, when reading at 1 kHz, you see the signal repeated.

Best,
Julian

1 Like

Hi Julian,

thanks for quick response.

are all data filtered by the onboard extended kalman filter? I’m mostly interested the below 9 values. I found them to be all 500Hz.

  mData[1] = robot_if.imu_data_accelerometer(0);
  mData[2] = robot_if.imu_data_accelerometer(1);
  mData[3] = robot_if.imu_data_accelerometer(2);
  mData[4] = robot_if.imu_data_gyroscope(0);
  mData[5] = robot_if.imu_data_gyroscope(1);
  mData[6] = robot_if.imu_data_gyroscope(2);
  mData[7] = robot_if.imu_data_linear_acceleration(0);
  mData[8] = robot_if.imu_data_linear_acceleration(1);
  mData[9] = robot_if.imu_data_linear_acceleration(2);

As far as I understand from the IMU datasheet, the raw reading can be up to 1kHz. Is there any setting I should modify to read in 1kHz?

Best,
An

Hi An,

Not all data is filtered, only some.

Here is where we configure the IMU in the code:

You can see:

    75 65 0C 0A 0A 08 01 02 04 00 01 05 00 01 10 73   // IMU data: acc+gyr at 1000Hz
    75 65 0C 0A 0A 0A 01 02 05 00 01 0D 00 01 1B A3   // EF data: RPY + LinACC at 500Hz (max)
    75 65 0C 07 07 0A 01 01 05 00 01 06 23            // EF data: RPY at 500Hz (max)

From that, I would assume that imu_data_accelerometer and imu_data_gyroscope should be at 1000 Hz. The imu_data_linear_acceleration is at 500 Hz.

Are you sure the imu_data_accelerometer are not coming in at 1000 Hz?

Best,
Julian

Hi Julian,

I found this code and understood as you said: imu_data_accelerometer and imu_data_gyroscope should be at 1000 Hz. The imu_data_linear_acceleration is at 500 Hz.

I double checked today the reading. They are all coming in at 500Hz. Do you see 1kHz data in your robot?

In my program, the control loop (1kHz) looks like this:

measureData IMU::measure()
{
  // init
  initMeasurement();

  // read imu
  robot_if.ParseSensorData(); // This will read the last incomming packet and update all sensor fields.
  robot_if.SendCommand(); //This will send the command packet
  mData[1] = robot_if.imu_data_accelerometer(0);
  mData[2] = robot_if.imu_data_accelerometer(1);
  mData[3] = robot_if.imu_data_accelerometer(2);
  mData[4] = robot_if.imu_data_gyroscope(0);
  mData[5] = robot_if.imu_data_gyroscope(1);
  mData[6] = robot_if.imu_data_gyroscope(2);
  mData[7] = robot_if.imu_data_linear_acceleration(0);
  mData[8] = robot_if.imu_data_linear_acceleration(1);
  mData[9] = robot_if.imu_data_linear_acceleration(2);

  return mData;
}

Best,
An

Hi,

I don’t have a dataset on hand to check, but here is some important information:

The IMU is streaming at 1khz to the masterboard (500Hz for the EKF data), but this data is then stored in the master board and sent to the PC at 1khz, and the two timers are not in sync.
Furthermore, you are sampling the latest measurement received on the PC by calling robot_if.ParseSensorData(); in your own loop witch is also not in sync with the master board timer neither the IMU timer.

If you call robot_if.ParseSensorData(); slightly too fast, you will see twice the same data occasionally.

You are using my fork, which contains a rewrite of the IMU driver. It is also possible that I introduced a bug here. Could you check to change the masterboard firmware / sdk for the origin master branch?

I hope this helps.

Best,
Thomas.

Hi Thomas,

thanks for the explanation. The occasional twice the same data make sense. I’m quite surprise to see it happens constantly.

I will check out the origin master branch later when I have time. Thanks again!

Best,
An

Hi An,

Felix was so kind to do some more testing and it looks the master-board <-> imu communication is happening at 1 kHz when we expect it. See the results here:

Use mailbox for SPI communication by jviereck · Pull Request #109 · open-dynamic-robot-initiative/master-board · GitHub

Best,
Julian

Hi Julian,

thank you all for helping with additional testing. The results look reasonably good and are exactly what I need.

Best,
An