ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
It is possible to map from a rosbag containing only image topics. If we break down to only minimal info from this launch file, we could have something like this with the topics you specified:
<launch>
<param name="use_sim_time" type="bool" value="True"/>
<arg name="pi/2" value="1.5707963267948966" />
<arg name="optical_rotate" value="0 0 0 -$(arg pi/2) 0 -$(arg pi/2)" />
<node pkg="tf" type="static_transform_publisher" name="camera_base_link"
args="$(arg optical_rotate) base_link camera_link 100" />
<group ns="rtabmap">
<!-- Odometry -->
<node pkg="rtabmap_ros" type="rgbd_odometry" name="rgbd_odometry" output="screen">
<remap from="rgb/image" to="/camera/rgb/image_color"/>
<remap from="depth/image" to="/camera/depth/image"/>
<remap from="rgb/camera_info" to="/camera/rgb/camera_info"/>
<param name="frame_id" type="string" value="base_link"/>
</node>
<!-- SLAM -->
<node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="--delete_db_on_start">
<param name="subscribe_depth" type="bool" value="true"/>
<param name="frame_id" type="string" value="base_link"/>
<remap from="rgb/image" to="/camera/rgb/image_color"/>
<remap from="depth/image" to="/camera/depth/image"/>
<remap from="rgb/camera_info" to="/camera/rgb/camera_info"/>
<remap from="odom" to="odom"/>
</node>
</group>
</launch>
Replace camera_link
by the frame contained in the /camera/rgb/image_color
topic. Then play the bag:
$ roslaunch example_above.launch
$ rosbag play --clock recorded.bag