rtabmap-ros mapping without loop closure detection
Hi,
I'm using rtabmap_ros with kinect and a simulation environment (Gazebo) and ubuntu 14.04 and ros indigo
I'm trying to 3D map a very big structure model (Aircraft model) placed in a Gazebo environment..the 3D mapping is done using a kinect placed on a UAV that autonomously navigates around the structure ... the map starts to be created successfully and incrementally but after a several hours the first mapped parts disappears. covering the structure takes alot of time. The path that the UAV follows is too long and does not include loop closure so I increased the RGBD/localimmunizationRatio from 0.025 to 0.5 to handle longer paths and I set up the RGBD/LocalLoopDetectionSpace to false but still I have the same problem so what could be the problem in my case ??
Here is the launch file part with the parameters I used:
<group ns="$(arg ns)">
<node if="$(arg rgbd_odometry)" pkg="rtabmap_ros" type="rgbd_odometry" name="rgbd_odometry" output="screen">
<param name="frame_id" type="string" value="iris/xtion_sensor/camera_depth_optical_frame"/>
<param name="wait_for_transform" type="bool" value="true"/>
<param name="Odom/Force2D" type="string" value="true"/>
<remap from="rgb/image" to="/iris/xtion_sensor/iris/xtion_sensor_camera/rgb/image_raw"/>
<remap from="depth/image" to="/iris/xtion_sensor/iris/xtion_sensor_camera/depth/image_raw"/>
<remap from="rgb/camera_info" to="/iris/xtion_sensor/iris/xtion_sensor_camera/rgb/camera_info"/>
</node>
<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="/iris/xtion_sensor/ground_truth/iris/xtion_sensor/ground_truth/odometry_sensor_link"/>
<param name="odom_frame_id" type="string" value="world"/>
<param name="subscribe_depth" type="bool" value="true"/>
<remap from="odom" to="/iris/ground_truth/odometry"/>
<remap from="rgb/image" to="/iris/xtion_sensor/iris/xtion_sensor_camera/rgb/image_raw"/>
<remap from="depth/image" to="/iris/xtion_sensor/iris/xtion_sensor_camera/depth/image_raw"/>
<remap from="rgb/camera_info" to="/iris/xtion_sensor/iris/xtion_sensor_camera/rgb/camera_info"/>
<remap from="rtabmap/get_map" to="/iris/get_map"/>
<param name="RGBD/LocalLoopDetectionSpace" type="string" value="false"/>
<param name="RGBD/OptimizeFromGraphEnd" type="string" value="false"/>
<param name="Kp/MaxDepth" type="string" value="8.5"/>
<param name="LccIcp/Type" type="string" value="1"/>
<param name="LccIcp2/CorrespondenceRatio" type="string" value="0.05"/>
<param name="LccBow/MinInliers" type="string" value="10"/>
<param name="LccBow/InlierDistance" type="string" value="0.1"/>
<param name="RGBD/AngularUpdate" type="string" value="0.1"/>
<param name="RGBD/LinearUpdate" type="string" value="0.1"/>
<param name="RGBD/LocalImmunizationRatio" type="string" value="0.50"/>
<param name="Rtabmap/TimeThr" type="string" value="700"/>
<param name="Mem/RehearsalSimilarity" type="string" value="0.30"/>
<!-- localization mode -->
<param if="$(arg localization)" name="Mem/IncrementalMemory" type="string" value="false"/>
<param unless="$(arg localization)" name="Mem/IncrementalMemory" type="string" value="true"/>
<param name="Mem/InitWMWithAllNodes" type="string" value="$(arg localization)"/>
</node>
<node if="$(arg rtabmapviz)" pkg="rtabmap_ros" type="rtabmapviz" name="rtabmapviz" args="-d $(find rtabmap_ros)/launch/config/rgbd_gui.ini" output="screen">
<param name="subscribe_depth" type="bool" value="true"/>
<param name="frame_id" type="string" value="/iris/xtion_sensor/ground_truth/iris/xtion_sensor/ground_truth/odometry_sensor_link"/>
<param name="wait_for_transform" type="bool" value="true ...