RTAB-Map (ROS 2 Humble) multi-camera PnP with 3× D435 — code pointers and guidance? Email body (EN):

classic Classic list List threaded Threaded
2 messages Options
Reply | Threaded
Open this post in threaded view
|

RTAB-Map (ROS 2 Humble) multi-camera PnP with 3× D435 — code pointers and guidance? Email body (EN):

GGYU
Hi Mathieu,

I’m running multi-camera SLAM on ROS 2 Humble with three Intel RealSense D435 cameras (non-overlapping FOVs). I’m using the realsense2_camera wrapper (separate namespaces per camera) and RTAB-Map via rtabmap_sync → rtabmap_odom/rgbd_odometry → rtabmap_slam/rtabmap.

I want to understand (and verify I’m reading the right code for) the multi-camera PnP pipeline used by RTAB-Map. Could you please confirm whether these are the right places to look and if I’m missing anything?

Where multi-camera PnP is implemented (OpenGV):

rtabmap/corelib/src/util3d_motion_estimation.cpp — function estimateMotion3DTo2D(...) uses OpenGV’s NoncentralAbsolute(Multi)Adapter and (Multi)RANSAC for multi-camera 3D-to-2D PnP. It splits keypoints by sub-image width and enforces same image size across camera models. Guarded by RTABMAP_OPENGV.
ROS

Where it’s called from (visual registration path):

rtabmap/corelib/src/RegistrationVis.cpp — RegistrationVis config (e.g., Vis/PnPReprojError, Vis/PnPFlags, Vis/PnPRefineIterations, Vis/PnPVarianceMedianRatio) and the call into util3d_motion_estimation.
ROS

ROS 2 message and sync path (multi cameras):

rtabmap_sync/rgbd_sync can bundle multiple rtabmap_msgs/RGBDImage into a single rtabmap_msgs/RGBDImages for the SLAM/odometry nodes (set subscribe_rgbd:=true, rgbd_cameras:=3).
ROS
+2
wiki.ros.org
+2

Node/package split on ROS 2: rtabmap_odom (odometry), rtabmap_slam (SLAM), rtabmap_sync (sync).
mirror.umd.edu

Build/assumptions:

Multi-camera PnP requires OpenGV enabled (otherwise the function is disabled).
ROS

Cameras should share the same image size; TF extrinsics define each camera’s CameraModel.localTransform().
ROS
+1

Questions:

Is the above the correct path for multi-camera pose estimation in both odometry and loop-closure registration?

Any recommended defaults for multi-camera (e.g., Vis/PnPVarianceMedianRatio, RANSAC iterations, PnPFlags) when fields of view barely overlap?
ROS

For 3× D435 specifically, do you recommend aggregating with a single rtabmap_sync (producing one RGBDImages) vs. feeding three rgbd_sync outputs separately? Any pitfalls you see often (QoS, timestamps, approximate sync)?
wiki.ros.org

Finally, if there are other files/classes you’d point me to for multi-camera PnP (or an example config), I’d really appreciate it.

Thanks for your time, and for RTAB-Map!

Best,
GGYU
Reply | Threaded
Open this post in threaded view
|

Re: RTAB-Map (ROS 2 Humble) multi-camera PnP with 3× D435 — code pointers and guidance? Email body (EN):

matlabbe
Administrator
Is the above the correct path for multi-camera pose estimation in both odometry and loop-closure registration?
yes, rtabmap will use OpenGV under the hood for odometry and loop closure registration. rtabmap library should indeed be built with OpenGV to support multi-camera.

Any recommended defaults for multi-camera (e.g., Vis/PnPVarianceMedianRatio, RANSAC iterations, PnPFlags) when fields of view barely overlap?
not in particular, I use default values most of the time. I would play more with Vis/PnPReprojError or Vis/CorGuessWinSize to improve feature matching in some cases. For example, if rgbd_odometry or stereo_odometry uses guess_frame_id (e.g., from wheel odometry / IMU fusion) and that frame is quite accurate on short term (below vo rate), then decreasing Vis/CorGuessWinSize could make vo more robust to dynamic obstacles.

For 3× D435 specifically, do you recommend aggregating with a single rtabmap_sync (producing one RGBDImages) vs. feeding three rgbd_sync outputs separately? Any pitfalls you see often (QoS, timestamps, approximate sync)?
I would produce a RGBDImages that can be easily synchronized with the visual odometry topic afterwards (should have exact same stamp) with rtabmap or rtabmap_viz nodes. Otherwise, all other nodes subscribing to the three cameras would have to sync them independently (an issue with this example). By using a RGBDImages we also make sure that rtabmap node is receiving exactly the same images that were used by visual odometry. Another option is to make visual odometry synchronize them (rgbd_cameras:=3) but connect the output `odom_rgbd_image` or `sensor_data` topics to rtabmap/rtabmap_viz nodes instead.

If you can hardware synchronize all 3 cameras together, that would be the best. Then hopefully you can use approx_sync:=false or if the stamps cannot be exactly the same but very close (<1ms), you can set approx_sync_max_interval to 0.005 (5 ms) for example.

It seems with latest ROS2 versions, I have less trouble setting QOS, though setting it to reliable may reproduce better what we got on ros1. Most synchronization issues I had with ROS2 were caused by the DDS. It seems I had more success with Cyclone DDS to handle images.

Finally, if there are other files/classes you’d point me to for multi-camera PnP (or an example config), I’d really appreciate it.
Beside examples like this, I don't have other doc about that. Note that if the cameras are synchronized together and TF extrinsics between the cameras are accurate, multi-camera PnP should work well.