diff --git a/launch/node.launch b/launch/node.launch index 0242e69f4f5cf930f4dc67701fdacfd8b71b3488..f8194caa1cf9eb5d917e23c1a0e20ca8fb46a83a 100644 --- a/launch/node.launch +++ b/launch/node.launch @@ -7,6 +7,8 @@ <arg name="output" default="screen"/> <arg name="launch_prefix" default=""/> <arg name="cloud_in" default="~pointcloud_in"/> + <arg name="obstacles_cloud_out" default="~obstacles_cloud_in"/> + <arg name="free_space_cloud_out" default="~free_space_cloud_in"/> <group ns="$(arg ns)"> @@ -16,6 +18,8 @@ output="$(arg output)" launch-prefix="$(arg launch_prefix)"> <remap from="~input" to="$(arg cloud_in)"/> + <remap from="~obstacles" to="$(arg obstacles_cloud_out)"/> + <remap from="~free_space" to="$(arg free_space_cloud_out)"/> <rosparam file="$(arg config_file)" command="load"/> </node> diff --git a/launch/nodelet.launch b/launch/nodelet.launch index b8c7815af99ee5ce0dc683536d4f4a84cb95940d..f4635f3b9178eba4da3eabd2f7be2751e673ae71 100644 --- a/launch/nodelet.launch +++ b/launch/nodelet.launch @@ -8,6 +8,8 @@ <arg name="output" default="screen"/> <arg name="launch_prefix" default=""/> <arg name="cloud_in" default="~pointcloud_in"/> + <arg name="obstacles_cloud_out" default="~obstacles_cloud_in"/> + <arg name="free_space_cloud_out" default="~free_space_cloud_in"/> <group ns="$(arg ns)"> @@ -17,6 +19,8 @@ args="load iri_obstacle_detection_normals/ObstacleDetectionNormalsAlgNodelet $(arg camera_nodelet_manager)" output="$(arg output)"> <remap from="~input" to="$(arg cloud_in)"/> + <remap from="~obstacles" to="$(arg obstacles_cloud_out)"/> + <remap from="~free_space" to="$(arg free_space_cloud_out)"/> <rosparam file="$(arg config_file)" command="load"/> </node>