Using RTABMAP with Gmapping?
Hi there!
I am building a map with a Kinect 360, a RPLidar-laserscanner and a turtlebot using RTABMAP on Ubuntu 14.04 and ROS Indigo. Hi,
While using RTABMAP I get poor results for the registered 3D Point Cloud and the 2D grid_map (which I am using for navigation). There a many registration errors in both map. So I decided to use gmapping for building the 2D map and run rtabmap in parallel. I set "publish_tf" to false and got really good results for the 2D Map, but still poor results in the 3D point cloud. Is it possible in RTABMAP to prior the laserscanner data for RTABMAPs scan-matching and pose estimation? Or to use gmappings pose estimation for RTABMAPs point cloud registration?
Or does anyone now another package to register the point clouds from kinect?
I am using this launch file from now:
<launch>
<arg name="database_path" default="rtabmap.db"/>
<arg name="localization" default="false"/>
<arg name="rgbd_odometry" default="false"/>
<arg name="args" default="--delete_db_on_start"/>
<arg name="rtabmapviz" default="false"/>
<arg name="wait_for_transform" default="0.2"/>
<!--
robot_state_publisher's publishing frequency in "turtlebot_bringup/launch/includes/robot.launch.xml"
can be increase from 5 to 10 Hz to avoid some TF warnings.
-->
<!-- Navigation stuff (move_base) -->
<include file="$(find turtlebot_bringup)/launch/3dsensor.launch">
<arg name="scan_processing" value="false" /> <!-- Disable conversion from Kinect to /scan -->
</include>
<!-- gmapping -->
<include file="$(find turtlebot_igm)/launch/gmapping.launch"/>
<include file="$(find turtlebot_navigation)/launch/includes/move_base.launch.xml"/>
<!-- Mapping -->
<group ns="rtabmap">
<node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="$(arg args)">
<param name="database_path" type="string" value="$(arg database_path)"/>
<param name="frame_id" type="string" value="base_footprint"/>
<param name="odom_frame_id" type="string" value="odom"/>
<param name="wait_for_transform_duration" type="double" value="$(arg wait_for_transform)"/>
<param name="subscribe_depth" type="bool" value="true"/>
<param name="subscribe_scan" type="bool" value="true"/>
<!--<param name="Grid/FromDepth" type="string" value="true" />-->
<param name="publish_tf" type="bool" value="false"/>
<param name="RGBD/PoseScanMatching" type="bool" value="true"/>
<!-- inputs -->
<remap from="scan" to="/scan"/>
<remap from="rgb/image" to="/camera/rgb/image_rect_color"/>
<remap from="depth/image" to="/camera/depth_registered/image_raw"/>
<remap from="rgb/camera_info" to="/camera/rgb/camera_info"/>
<!-- output -->
<!--<remap from="grid_map" to="/map"/>-->
<!-- RTAB-Map's parameters: do "rosrun rtabmap rtabmap (double-dash)params" to see the list of available parameters. -->
<param name="RGBD/ProximityBySpace" type="string" value="true"/> <!-- Local loop closure detection (using estimated position) with locations in WM -->
<param name="RGBD/OptimizeFromGraphEnd" type="string" value="false"/> <!-- Set to false to generate map correction between /map and /odom -->
<param name="Kp/MaxDepth" type="string" value="4.0"/>
<param name="Reg/Strategy" type="string" value="1"/> <!-- Loop closure transformation refining with ICP: 0=Visual, 1=ICP, 2=Visual+ICP -->
<param name="Icp/CoprrespondenceRatio" type="string" value="0.3"/>
<param name="Vis/MinInliers" type="string" value="5"/> <!-- 3D visual words minimum inliers to accept loop closure -->
<param name="Vis/InlierDistance" type="string" value="0.1"/> <!-- 3D visual words correspondence distance -->
<param name="RGBD/AngularUpdate" type="string" value="0.1"/> <!-- Update map only if the robot is moving ...