ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
If TF of the arm is available and the camera is linked to that Tf tree, you can then use TF directly to scan the area. To do so with rtabmap:
<launch>
<arg name="rgb_topic" default="/camera/color/image_raw"/>
<arg name="depth_topic" default="/camera/aligned_depth_to_color/image_raw"/>
<arg name="camera_info_topic" default="/camera/color/camera_info"/>
<arg name="approx_sync" default="false"/>
<group ns="rtabmap">
<node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="--delete_db_on_start">
<param name="frame_id" type="string" value="base_link"/> <!-- base frame of the arm -->
<param name="odom_frame_id" type="string" value="base_link"/> <!-- same as frame_id, as the base of the arm doesn't move -->
<param name="approx_sync" type="bool" value="$(arg approx_sync)"/>
<remap from="rgb/image" to="$(arg rgb_topic)"/>
<remap from="depth/image" to="$(arg depth_topic)"/>
<remap from="rgb/camera_info" to="$(arg camera_info_topic)"/>
<!-- RTAB-Map's parameters -->
<param name="Rtabmap/DetectionRate" type="string" value="2"/> <!-- Hz -->
<param name="Kp/MaxFeatures" type="string" value="-1"/> <!-- Disable loop closure detection -->
<param name="RGBD/ProximityBySpace" type="string" value="false"/> <!-- Disable proximity detection -->
<param name="RGBD/AngularUpdate" type="string" value="0.0"/> <!-- Always add frames -->
<param name="RGBD/LinearUpdate" type="string" value="0.0"/> <!-- Always add frames -->
<param name="Grid/VoxelSize" type="string" value="0.05"/>
</node>
</group>
</launch>