Skip to content
Snippets Groups Projects
Commit e69e889e authored by Sergi Hernandez's avatar Sergi Hernandez
Browse files

Added the output topic remapping to the input arguments.

parent 86f0e8ee
No related branches found
No related tags found
No related merge requests found
......@@ -41,10 +41,10 @@ gen = ParameterGenerator()
#gen.add("velocity_scale_factor", double_t, 0, "Maximum velocity scale factor", 0.5, 0.0, 1.0)
gen.add("hole_min_p", int_t, 0, "No of Points to be hole (less points is a hole)",30,5,200)
gen.add("num_cells", int_t, 0, "No of cells in the detections zone",3, 1, 10)
gen.add("box_y", double_t, 0, "Y distance hole detection zone", 0.6, 0, 1.5)
gen.add("box_y", double_t, 0, "Y distance hole detection zone", 0.6, 0, 3)
gen.add("box_z_ini", double_t, 0, "Initial Z hole detection zone", 0, -0.5, 0.5)
gen.add("box_z_end", double_t, 0, "Z distance hole detection zone", 0.1, -0.5, 0.5)
gen.add("box_x_ini", double_t, 0, "Initial X hole detection zone", 0.8, 0, 2)
gen.add("box_x_end", double_t, 0, "X distance hole detection zone", 0.9, 0.5, 2)
gen.add("box_x_ini", double_t, 0, "Initial X hole detection zone", 0.8, -4.0, 4.0)
gen.add("box_x_end", double_t, 0, "X distance hole detection zone", 0.9, -4.0, 4.0)
exit(gen.generate(PACKAGE, "PointCloudHoleDetectionAlgorithm", "PointCloudHoleDetection"))
......@@ -7,6 +7,8 @@
<arg name="output" default="screen"/>
<arg name="launch_prefix" default=""/>
<arg name="cloud_in" default="~pointcloud_in"/>
<arg name="hole_zone_cloud_out" default="~hole_zone_cloud_out"/>
<arg name="hole_obs_cloud_out" default="~hole_obs_cloud_out"/>
<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="~hole_zone" to="$(arg hole_zone_cloud_out)"/>
<remap from="~hole_obstacle" to="$(arg hole_obs_cloud_out)"/>
<rosparam file="$(arg config_file)" command="load"/>
</node>
......
......@@ -8,6 +8,8 @@
<arg name="output" default="screen"/>
<arg name="launch_prefix" default=""/>
<arg name="cloud_in" default="~pointcloud_in"/>
<arg name="hole_zone_cloud_out" default="~hole_zone_cloud_out"/>
<arg name="hole_obs_cloud_out" default="~hole_obs_cloud_out"/>
<group ns="$(arg ns)">
......@@ -17,6 +19,8 @@
args="load iri_point_cloud_hole_detection/PointCloudHoleDetectionAlgNodelet $(arg camera_nodelet_manager)"
output="$(arg output)">
<remap from="~input" to="$(arg cloud_in)"/>
<remap from="~hole_zone" to="$(arg hole_zone_cloud_out)"/>
<remap from="~hole_obstacle" to="$(arg hole_obs_cloud_out)"/>
<rosparam file="$(arg config_file)" command="load"/>
</node>
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment