Re: Questions about the structure of a launch file.
Posted by
matlabbe on
URL: http://official-rtab-map-forum.206.s1.nabble.com/Questions-about-the-structure-of-a-launch-file-tp7719p7867.html
use_sim_time should be a parameter, as an argument like this it does nothing. common_params should be set to rtabmap node, not rtabmapviz.
<launch>
<arg name="rtabmapviz" default="true"/>
<arg name="frame_id" default="velodyne"/>
<arg name="scan_cloud_max_points" default="131072"/>
<param name="use_sim_time" value="true"/>
<arg name="common_params" value="--RGBD/CreateOccupancyGrid false \
--Rtabmap/DetectionRate 2 \
--Odom/ScanKeyFrameThr 0.9 \
--OdomF2M/ScanMaxSize 25000 \
--OdomF2M/ScanSubtractRadius 0.5 \
--Icp/PM true \
--Icp/VoxelSize 0.5 \
--Icp/MaxTranslation 5 \
--Icp/MaxCorrespondenceDistance 1.5 \
--Icp/PMOutlierRatio 0.8 \
--Icp/Iterations 10 \
--Icp/PointToPlane true \
--Icp/PMMatcherKnn 3 \
--Icp/PMMatcherEpsilon 0 \
--Icp/Epsilon 0.0001 \
--Icp/PointToPlaneK 10 \
--Icp/PointToPlaneRadius 0 \
--Icp/CorrespondenceRatio 0.01 \
--Odom/GuessSmoothingDelay 1"/>
<group ns = "rtabmap">
<node pkg="rtabmap_ros" type="icp_odometry" name="icp_odometry" output="screen" args="$(arg common_params)">
<remap from="scan_cloud" to="/pointcloud2"/>
<param name="frame_id" type="string" value="$(arg frame_id)"/>
<param name="odom_frame_id" type="string" value="odom"/>
<param name="scan_cloud_max_points" type="int" value="$(arg scan_cloud_max_points)"/>
</node>
<node pkg="rtabmap_ros" type="rtabmap" name="rtabmap" output="screen" args="-d $(arg common_params)">
<param name="frame_id" type="string" value="$(arg frame_id)"/>
<param name="subscribe_depth" type="bool" value="false"/>
<param name="subscribe_rgb" type="bool" value="false"/>
<param name="subscribe_scan_cloud" type="bool" value="true"/>
<param name="approx_sync" type="bool" value="false"/>
<param name="scan_cloud_max_points" type="int" value="$(arg scan_cloud_max_points)"/>
<remap from="scan_cloud" to="/pointcloud2"/>
</node>
<node if="$(arg rtabmapviz)" pkg="rtabmap_ros" type="rtabmapviz" name="rtabmapviz" output="screen">
<param name="frame_id" type="string" value="$(arg frame_id)"/>
<param name="odom_frame_id" type="string" value="odom"/>
<param name="subscribe_odom_info" type="bool" value="true"/>
<param name="subscribe_scan_cloud" type="bool" value="true"/>
<param name="approx_sync" type="bool" value="false"/>
<remap from="scan_cloud" to="/pointcloud2"/>
</node>
</group>
</launch>