rtabmap icon indicating copy to clipboard operation
rtabmap copied to clipboard

ERROR: "Overwriting previous data! Make sure IMU is published faster than data rate."

Open HHendy69 opened this issue 3 years ago • 8 comments

I integrated an external IMU in preference to the internal one to enhance the mapping performance, namely gx5 (https://www.microstrain.com/inertial-sensors/3dm-gx5-25) The IMU publishes with 500 Hz which is surely higher than frame rate!

However I get from time to another the error [ERROR] [1643724123.738174802]: Overwriting previous data! Make sure IMU is published faster than data rate. (last image stamp buffered=1643724122.277859 and new one is 1643724122.344204, last imu stamp received=1643724122.022523) beside the warning.

The assumption is when I connect to a master the all time stamps synchronization become the same.

image

I really can't decide, where the problem could be.

By the way, I installed the IMU on the camera so that I can have the same coordinates. Furthermore, I am using static transformation from /camera_link to /camera_imu_optical_frame and the imu frame is /camera_imu_optical_frame. It doesn't make sense to me but otherwise the gets built flipped on its side.

<node pkg="tf" type="static_transform_publisher" name="camera_aligned" args="0 0 0 -1.571 0 -1.571 /camera_link /camera_imu_optical_frame 400"/> <remap from="/gx5/imu/data" to="/rtabmap/imu"/>

HHendy69 avatar Feb 01 '22 14:02 HHendy69

For the static transform, it depends how the axes are oriented on the IMU.

For the error, what kind of camera are you using? Are images of the camera stamped on system time or camera time? Are imu messages stamped on IMU time or system time? If they are not stamped with same clock, or the clocks are not synchronized, rtabmap may received images with stamp in the future in comparison to latest imu readings (generating this error).

On a side note, if you are doing ICP odometry with a TOF camera, you may also look at this example for some parameters tuning: http://official-rtab-map-forum.206.s1.nabble.com/Kinect-For-Azure-L515-ICP-lighting-invariant-mapping-td7187.html

matlabbe avatar Feb 01 '22 18:02 matlabbe

I mistakenly though that /camera/imu publishes on frame /camera_link but it's l515. So the static transforms makes sense now. I mounted the IMU to out the same result published on the /camera/imu .

I am using realsense l515.

I am gonna try examine the time stamps and recomment.

HHendy69 avatar Feb 02 '22 13:02 HHendy69

I happen to have the D435 camera (has no IMU) and I integrated/mounted the IMU in the same way, and It worked just fine!!! There were no problems. I, of course, used the static tf as aforementioned and gave the IMU topic from the external IMU as if it's D435i. In my humble opinion, it should have also shown the same error if there had been an issue in the time stamps! How would that be explained? Would the assumption of connection with a master dictates the same time stamp on all still stand?

HHendy69 avatar Feb 02 '22 20:02 HHendy69

There could be a difference between how D435 and L515 cameras stamp their frames. Depending on the camera capability, the reslasense sdk may switch between internal camera clock and computer clock to stamp the messages. Related post: https://github.com/IntelRealSense/realsense-ros/issues/796

matlabbe avatar Feb 02 '22 21:02 matlabbe

I can conclude form the issue here https://github.com/IntelRealSense/librealsense/pull/3909#issue-440445164 and explicitly here https://github.com/IntelRealSense/realsense-ros/issues/796#issuecomment-497997643 that the integration with system time is already done for L500 series, would you agree with me?

HHendy69 avatar Feb 03 '22 14:02 HHendy69

I agree, but it seems to be verified or set explicitly depending on the realsense sdk and realsense ros package: https://github.com/introlab/rtabmap_ros/issues/570#issuecomment-1013315742

Like in http://official-rtab-map-forum.206.s1.nabble.com/L515-T265-stops-mapping-after-a-few-frames-tp8659p8711.html, you can show side by side header/stamps of your topics in two side-by-side terminals and check if the stamps give the same time.

matlabbe avatar Feb 03 '22 14:02 matlabbe

By the way,I've just observed that camera (D435) time stamp and IMU time stamps are not identical, even though RTAB-map can handle it without problems! timestamps_cameraIMU IMU left, camera right

HHendy69 avatar Feb 03 '22 15:02 HHendy69

At least imu stamps are after camera stamps, so rtabmap is able to buffer imu messages and using them when receiving the corresponding images. But the inverse will throw the imu not received error.

If your other imu at 500 Hz produces also stamps after image stamps, you may try to increase the buffer size of the imu callbacks, here for rtabmap: https://github.com/introlab/rtabmap_ros/blob/452be2cc6157d20603210f8939a686f287dbada6/src/CoreWrapper.cpp#L2512 https://github.com/introlab/rtabmap_ros/blob/452be2cc6157d20603210f8939a686f287dbada6/src/CoreWrapper.cpp#L833 and here for visual odometry: https://github.com/introlab/rtabmap_ros/blob/452be2cc6157d20603210f8939a686f287dbada6/src/OdometryROS.cpp#L460 https://github.com/introlab/rtabmap_ros/blob/452be2cc6157d20603210f8939a686f287dbada6/src/OdometryROS.cpp#L364

The if(>1000) means for 500 Hz that the buffer is 2 seconds. If the stamps between the camera and imu are farther than 2 seconds, you will get the error.

matlabbe avatar Feb 03 '22 15:02 matlabbe