RTAB-Map with D435i on a UR10

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

RTAB-Map with D435i on a UR10

robertzickler
This post was updated on .
Hello everyone,
I'm trying to create a map with the Intel Realsense D435i mounted on the end effector of an UR10 6 DOF manipulator. The idea is to use the movement of the manipulator to get the position and orientation of the depth camera in the environment. I use RVIZ with MoveIt! Therefore, I want to use the map in RVIZ, too. As well as having it aligned correctly.
I tried a lot of things but can't get it working. Here are my questions:
1) The base_link of the manipulator is always fixed to the world. How do I have to link map and Odom? Do I have to create them in the UR10-Xacro/URDF and then link them to the rtabmap or is this done within rtabmap?
2) How do I correctly link the end effector with the camera? With a “static_transform_publisher” like
<node pkg="tf" type="static_transform_publisher" name="eef_to_camera_tf" args="x y z r p y  /ee_link /camera_link 10" />
3) I neither want to use the IMU nor the visual odometry but the TF frame of the end effector as Odom. Is this possible?
4) Somehow it should be possible to give a ground truth with “ground_truth_frame_id”. In my case this would be the “world” but is this necessary if I have the full “perfect” tf from the world to the camera?
Here is the tf-tree of the UR10 without the camera:

Thank you!
Robert
Reply | Threaded
Open this post in threaded view
|

Re: RTAB-Map with D435i on a UR10

matlabbe
Administrator
Hi Robert,

It is possible to use the manipulator arm's TF for odometry. Also, as we can assume that there is no drift, we can disable loop closure detection to save resources and cpu time.

What does /world -> /base_link represent in your setup? For the link between the end effector and the camera, a static_transform_publisher can be used, or the urdf of the arm can be modified to include the joint and link directly.

The config of rtabmap node could look like this:
<node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" args="--delete_db_on_start">
    <remap from="rgb/image"       to="/camera/color/image_raw"/>
    <remap from="depth/image"     to="/camera/aligned_depth_to_color/image_raw"/>
    <remap from="rgb/camera_info" to="/camera/color/camera_info"/>
    
    <param name="frame_id"              value="base_link"/>
    <param name="odom_frame_id"         value="base_link"/> <!-- fake fixed odometry -->
    <param name="approx_sync"           value="false"/>     <!-- D435i has exact synchronized frames -->
    <param name="Rtabmap/DetectionRate" value="2"/>         <!-- increase to make the map faster -->
    <param name="Kp/MaxFeatures"        value="-1"/>        <!-- disable loop closure detection -->
    <param name="RGBD/ProximityDetectionBySpace" value="false"/> <!-- disable proximity detection -->
    <param name="RGBD/LinearUpdate"     value="0.0"/> <!-- always add new frames even if we don't move... arm is fixed -->
    <param name="RGBD/AngularUpdate"    value="0.0"/> 
</node>

You can also play with the Grid/ parameters if you need an OctoMap with finer cells for example (default 5 cm).
$ rtabmap --params | grep Grid/

To reuse a previous map, remove "--delete_db_on_start" and set "Mem/IncrementalMemory" to false.

cheers,
Mathieu
Reply | Threaded
Open this post in threaded view
|

Re: RTAB-Map with D435i on a UR10

robertzickler
Thank you Mathieu, that worked perfectly!
I used "world“ as a global coordinate system that was at a specific position in the room. The robot is not standing in the same position as "world". I now have map -> base_link -> arm... -> camera_link
Robert