Rtab-Map ICP + visual loop closing
Hey,
i used rtabmap in Reg/Strategy 0 so far with my kinect camera. I wanted to try to fake a laserscan to use rtabmap with ICP and visual loop closing. For some reason when i start the application it's says there is no laserscan data. But the laserscan data is published under the topic /cloud as a 3D laserscan. I checked that topic using rviz and rostopic.
<launch>
<arg name="model" default="$(env TURTLEBOT3_MODEL)" doc="model type [burger, waffle, waffle_pi]"/>
<arg name="open_rviz" default="true"/>
<arg name="rtabmapviz" default="true"/>
<arg name="move_forward_only" default="false"/>
<arg name="with_camera" default="true"/>
<arg name="localization" default="false"/>
<arg name="database_path" default="~/.ros/rtabmap.db"/>
<arg if="$(arg localization)" name="rtabmap_args" default="--uinfo"/>
<arg unless="$(arg localization)" name="rtabmap_args" default="-d"/>
<include file="$(find turtlebot3_bringup)/launch/turtlebot3_remote.launch">
<arg name="model" value="$(arg model)" />
</include>
<node pkg="nodelet" type="nodelet" name="rgbd_relay" args="standalone rtabmap_ros/rgbd_relay" output="screen">
<remap from="/rtabmap/rgbd_image" to="/rgbd_image"/>
<remap from="/rtabmap/rgbd_image_relay" to="/rgbd_image_relay"/>
</node>
<group ns="rtabmap">
<node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="$(arg rtabmap_args)">
<param name="database_path" type="string" value="$(arg database_path)"/>
<param name="frame_id" type="string" value="base_footprint"/>
<param name="subscribe_depth" type="bool" value="false"/>
<param name="subscribe_rgb" type="bool" value="false"/>
<param name="subscribe_rgbd" type="bool" value="true"/>
<param name="subscribe_scan_cloud" type="bool" value="true"/>
<param name="map_frame_id" type="string" value="map"/>
<param name="Grid/FromDepth" type="string" value="true"/>
<param name="approx_sync" type="bool" value="true"/>
<param name="publish_tf" type="bool" value="true"/>
<param name="tf_delay" type="double" value="0.05"/>
<param name="rgbd_cameras" type="int" value="1"/>
<param name="wait_for_transform_duration" type="double" value="0.1"/>
<!-- use actionlib to send goals to move_base -->
<param name="use_action_for_goal" type="bool" value="true"/>
<remap from="move_base" to="/move_base"/>
<remap from="odom" to="/odom"/>
<remap from="rgbd_image" to="/rgbd_image_relay"/>
<remap from="rgb/camera_info" to="/camera/rgb/camera_info"/>
<remap from="scan_cloud" to="/cloud"/>
<remap from="grid_map" to="/map"/>
<!-- RTAB-Map's Paramter -->
<param name="Reg/Strategy" type="string" value="2"/>
<param name="Reg/Force3DoF" type="string" value="true"/>
<param name="GridGlobal/MinSize" type="string" value="20"/>
<param name="Grid/MaxObstacleHeight" type="string" value="0.5"/>
<param name="Grid/MaxGroundHeight" type="string" value="0.1"/>
<param name="Grid/MinGroundHeight" type="string" value="-0.05"/>
<param name="Icp/VoxelSize" type="string" value="0.02"/>
<!-- localization mode -->
<param if="$(arg localization)" name="Mem/IncrementalMemory" type="string" value="false"/>
<param unless="$(arg localization)" name="Mem/IncrementalMemory" type="string" value="true"/>
</node>
<node pkg="nodelet" type="nodelet" name="points_xyzrgb" args="standalone rtabmap_ros/point_cloud_xyzrgb" output="screen">
<remap from="/rtabmap/rgbd_image" to="/rgbd_image_relay"/>
<remap from="cloud" to="/cloud" />
<param name="voxel_size" type ...
Please put the launchfile in code tags in the question, for future searchability and completeness. Thanks.