microsoft / Azure_Kinect_ROS_Driver

A ROS sensor driver for the Azure Kinect Developer Kit.
MIT License
304 stars 226 forks source link

Negative latency measured in IMU samples #164

Open zchenpds opened 3 years ago

zchenpds commented 3 years ago

Describe the bug IMU timestamp leads ros::Time::now() by around 20~40 ms, which violates causality. It is measured by https://github.com/microsoft/Azure_Kinect_ROS_Driver/blob/6d575cefd4d9ce872a2f954da94b7f018ab512fb/src/k4a_ros_device.cpp#L689 For example,

[DEBUG] [1607311968.268557095]: IMU timestamp lags ros::Time::now() by -19.9212 ms. The lag ranges from -21.4135ms to 0.914652ms.

To Reproduce Steps to reproduce the behavior:

  1. roslaunch azure_kinect_ros_driver driver.launch
  2. Change the log verbosity level to DEBUG.

Expected behavior IMU latency (ros::Time::now() minus the ROS timestamp of the IMU sample) should positive. The clock offset from device to host PC should be set according to the system time from when a data packet arrives from the least latent data source, IMU, rather than the depth/color camera. We should not shy away from using the IMU system timestamp just because it is not measured exactly when the USB firmware finishes receiving it.

This issue regarding precise time sync between device and PC is still open.

Logs The first subfigure below shows the IMU sample latency. I started subscribing to /body_tracking_data at around t = 12 s, which started causing spikes in latency and the forced update of the clock offset exactly four times

[ WARN] [1607309887.239125438]: Initializing or re-initializing the device to realtime offset: 1607309873656763324 ns [ WARN] [1607309887.277057048]: Initializing or re-initializing the device to realtime offset: 1607309873642803868 ns [ WARN] [1607309888.236627856]: Initializing or re-initializing the device to realtime offset: 1607309873654011978 ns [ WARN] [1607309888.269853462]: Initializing or re-initializing the device to realtime offset: 1607309873642823711 ns

which corresponds to the two spikes in the third subfigure. original

Desktop (please complete the following information):

Proposed changes

Option 1

As shown in https://github.com/zchenpds/Azure_Kinect_ROS_Driver/commit/cfb8978789927f9ba9e2846133e185274fb9b36f, we can estimate offset pts_to_system_offset_ using the measured differences pts_to_system between system timestamp and device timestamp from both IMU samples and image captures. The result as follows shows that this method could force the lower envelope of the IMU latency signal to converge to zero, which should improve the synchronization accuracy between the device and host PC. In the unlikely case where IMU is not the least latent data source, the system timestamp from color or IR image will be favored. This method is simple, but the drawback is the IMU latency will still be negative once in a while even after convergence, and there is some undesired offset fluctuation after convergence. improved

Option 2

One of the great ideas discussed in https://github.com/microsoft/Azure_Kinect_ROS_Driver/issues/57 was https://github.com/ethz-asl/cuckoo_time_translator. If we do not mind adding some dependencies, this convex hull + Kalman filter solution would be ideal in the absence of some hardware tools that are needed to find the unknown bias.