Questions about the structure of a launch file.

classic Classic list List threaded Threaded
4 messages Options
Reply | Threaded
Open this post in threaded view
|

Questions about the structure of a launch file.

Mikor
Hi Mathiew,

I hope you're doing well. Today I have some questions about the structure of a launch file because I am looking forward to create my own because I feel that it will help me develop my understanding. Also, I create this topic about the creation of the launch file to come back to when I have related questions. So, Let me breakdown the conceptual parts that I think to include in my launch file and please correct me if I am wrong.

So, for starters I am intending to create a launch file that uses scan topic. The conceptual parts are the following:
a) Declare the topics that are going to be used.
b) Create an odometry node.
c) Create the rtabmap node.
d) Create the visualization node.

But I am wondering how the mapping occurs. I get that the rtabmap node is the one that publishes the pointcloud but is not clear to me what parameters to try and experiment with that would affect only the mapping procedure and not the odometry.

Thank you in advance,
Anthony.
Reply | Threaded
Open this post in threaded view
|

Re: Questions about the structure of a launch file.

matlabbe
Administrator
Hi  Anthony,

If you put parameters inside the tags of a node, only that node will use the parameters, so that odometry and rtabmap ndoes use different parameters.

You can see some examples on this page: http://wiki.ros.org/rtabmap_ros/Tutorials/SetupOnYourRobot

If you want to share RTAB-Map's parameters (those shown with "rtabmap --params") between odometry and rtabmap nodes, I generally use the args parameter:

<arg name="common_params" value="--Icp/VoxelSize 0.05 --Icp/PointToPlane true"/>

<node pkg="rtabmap_ros" type="icp_odometry" name="icp_odometry" output="screen" args="$(arg common_params)">
   ...
</node>

<node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="--delete_db_on_start $(arg common_params)">
   ...
   <param name="Grid/CellSize" value="0.1"/> <!-- just for this node -->
</node>

cheers,
Mathieu
Reply | Threaded
Open this post in threaded view
|

Re: Questions about the structure of a launch file.

Mikor
Hmmm so, let's say that I need to replicate a command looking like this in the terminal:

roslaunch rtabmap_ros rtabmap.launch  \
    use_sim_time:=true \
    depth:=false \
    subscribe_scan_cloud:=true \
    frame_id:=velodyne \
    scan_cloud_topic:=/pointcloud2  \
    scan_cloud_max_points:=131072  \
    icp_odometry:=true  \
    approx_sync:=false \
    args:="-d  \
      --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" 

I created a corresponding launch file looking like this

<launch>
    <arg name="rtabmapviz"    default="true"/>	
    <arg name="frame_id" default="velodyne"/>
    <arg name="use_sim_time"  default="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"/>
		</node>
		
		<node pkg="rtabmap_ros" type="rtabmap" name="rtabmap" output="screen" args="-d">
		    <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="true"/>
			<remap from="scan_cloud" to="/pointcloud2"/>
		</node>
		
		<node pkg="rtabmap_ros" type="rtabmapviz" name="rtabmapviz" output="screen" args="$(arg common_params)">
		    <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>

Thinking that it should work the same way but it is not, what am I missing ?

Thanks in advance,
Anthony.
Reply | Threaded
Open this post in threaded view
|

Re: Questions about the structure of a launch file.

matlabbe
Administrator
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>