Adding launch file arg for launch-prefix to offline nodes (#1066)
Useful for debugging with gdb or profiling, e.g. with perf.master
parent
e2f72ff514
commit
6b9d8ff2d5
|
@ -21,6 +21,7 @@
|
||||||
<arg name="configuration_directory" default="$(find cartographer_ros)/configuration_files"/>
|
<arg name="configuration_directory" default="$(find cartographer_ros)/configuration_files"/>
|
||||||
<arg name="configuration_basenames" default="backpack_2d.lua"/>
|
<arg name="configuration_basenames" default="backpack_2d.lua"/>
|
||||||
<arg name="urdf_filenames" default="$(find cartographer_ros)/urdf/backpack_2d.urdf"/>
|
<arg name="urdf_filenames" default="$(find cartographer_ros)/urdf/backpack_2d.urdf"/>
|
||||||
|
<arg name="launch_prefix" default=""/>
|
||||||
|
|
||||||
<remap from="echoes" to="horizontal_laser_2d"/>
|
<remap from="echoes" to="horizontal_laser_2d"/>
|
||||||
<include file="$(find cartographer_ros)/launch/offline_node.launch">
|
<include file="$(find cartographer_ros)/launch/offline_node.launch">
|
||||||
|
@ -30,5 +31,6 @@
|
||||||
<arg name="configuration_directory" value="$(arg configuration_directory)"/>
|
<arg name="configuration_directory" value="$(arg configuration_directory)"/>
|
||||||
<arg name="configuration_basenames" value="$(arg configuration_basenames)"/>
|
<arg name="configuration_basenames" value="$(arg configuration_basenames)"/>
|
||||||
<arg name="urdf_filenames" value="$(arg urdf_filenames)"/>
|
<arg name="urdf_filenames" value="$(arg urdf_filenames)"/>
|
||||||
|
<arg name="launch_prefix" value="$(arg launch_prefix)"/>
|
||||||
</include>
|
</include>
|
||||||
</launch>
|
</launch>
|
||||||
|
|
|
@ -21,6 +21,7 @@
|
||||||
<arg name="configuration_directory" default="$(find cartographer_ros)/configuration_files"/>
|
<arg name="configuration_directory" default="$(find cartographer_ros)/configuration_files"/>
|
||||||
<arg name="configuration_basenames" default="backpack_3d.lua"/>
|
<arg name="configuration_basenames" default="backpack_3d.lua"/>
|
||||||
<arg name="urdf_filenames" default="$(find cartographer_ros)/urdf/backpack_3d.urdf"/>
|
<arg name="urdf_filenames" default="$(find cartographer_ros)/urdf/backpack_3d.urdf"/>
|
||||||
|
<arg name="launch_prefix" default=""/>
|
||||||
|
|
||||||
<remap from="points2_1" to="horizontal_laser_3d" />
|
<remap from="points2_1" to="horizontal_laser_3d" />
|
||||||
<remap from="points2_2" to="vertical_laser_3d" />
|
<remap from="points2_2" to="vertical_laser_3d" />
|
||||||
|
@ -31,5 +32,6 @@
|
||||||
<arg name="configuration_directory" value="$(arg configuration_directory)"/>
|
<arg name="configuration_directory" value="$(arg configuration_directory)"/>
|
||||||
<arg name="configuration_basenames" value="$(arg configuration_basenames)"/>
|
<arg name="configuration_basenames" value="$(arg configuration_basenames)"/>
|
||||||
<arg name="urdf_filenames" value="$(arg urdf_filenames)"/>
|
<arg name="urdf_filenames" value="$(arg urdf_filenames)"/>
|
||||||
|
<arg name="launch_prefix" value="$(arg launch_prefix)"/>
|
||||||
</include>
|
</include>
|
||||||
</launch>
|
</launch>
|
||||||
|
|
|
@ -21,6 +21,7 @@
|
||||||
<arg name="configuration_directory"/>
|
<arg name="configuration_directory"/>
|
||||||
<arg name="configuration_basenames"/>
|
<arg name="configuration_basenames"/>
|
||||||
<arg name="urdf_filenames"/>
|
<arg name="urdf_filenames"/>
|
||||||
|
<arg name="launch_prefix"/>
|
||||||
|
|
||||||
<param name="/use_sim_time" value="true" />
|
<param name="/use_sim_time" value="true" />
|
||||||
|
|
||||||
|
@ -44,5 +45,6 @@
|
||||||
-configuration_basenames $(arg configuration_basenames)
|
-configuration_basenames $(arg configuration_basenames)
|
||||||
-urdf_filenames $(arg urdf_filenames)
|
-urdf_filenames $(arg urdf_filenames)
|
||||||
-bag_filenames $(arg bag_filenames)"
|
-bag_filenames $(arg bag_filenames)"
|
||||||
|
launch-prefix="$(arg launch_prefix)"
|
||||||
output="screen"/>
|
output="screen"/>
|
||||||
</launch>
|
</launch>
|
||||||
|
|
Loading…
Reference in New Issue