You can not select more than 25 topics Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.
 
 

57 lines
2.8 KiB

<launch>
<arg name="localization"/>
<arg name="args"/>
<arg name="database_path"/>
<arg name="wait_for_transform"/>
<arg name="pointcloud_topic"/>
<arg name="cmd_vel_topic"/>
<arg name="odom_topic"/>
<arg name="scan"/>
<arg name="rgb_topic"/>
<arg name="rgb_camera_info"/>
<!-- 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_link"/>
<param name="odom_frame_id" type="string" value="odom"/>
<param name="odom_tf_angular_variance" type="double" value="0.005"/>
<param name="odom_tf_linear_variance" type="double" value="0.005"/>
<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"/>
<!-- inputs -->
<remap from="scan" to="$(arg scan)"/>
<remap from="rgb/image" to="$(arg rgb_topic)"/>
<remap from="depth/image" to="$(arg pointcloud_topic)"/>
<remap from="rgb/camera_info" to="$(arg 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"/>
<param name="RGBD/OptimizeFromGraphEnd" type="string" value="false"/>
<param name="Kp/MaxDepth" type="string" value="4.0"/>
<param name="Reg/Strategy" type="string" value="1"/>
<param name="Icp/CoprrespondenceRatio" type="string" value="0.3"/>
<param name="Vis/MinInliers" type="string" value="6"/>
<param name="Vis/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="Rtabmap/TimeThr" type="string" value="700"/>
<param name="Mem/RehearsalSimilarity" type="string" value="0.30"/>
<param name="Reg/Force3DoF" type="string" value="true"/>
<param name="Grid/FromDepth" type="string" value="true"/>
<param name="RGBD/ProximityPathMaxNeighbors" type="string" value="10"/>
</node>
<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)"/>
</group>
</launch>