Skip to content

Commit

Permalink
add launch args to support multiple devices (#108)
Browse files Browse the repository at this point in the history
  • Loading branch information
jack-oquin committed Oct 8, 2016
1 parent 611df63 commit 4d0d71f
Show file tree
Hide file tree
Showing 7 changed files with 30 additions and 55 deletions.
17 changes: 8 additions & 9 deletions velodyne_driver/launch/nodelet_manager.launch
Original file line number Diff line number Diff line change
@@ -1,16 +1,11 @@
<!-- -*- mode: XML -*- -->
<!-- start velodyne_driver/DriverNodelet in a nodelet manager
$Id$
-->
<!-- start velodyne_driver/DriverNodelet in a nodelet manager -->

<launch>

<!-- start nodelet manager and load driver nodelet -->
<node pkg="nodelet" type="nodelet" name="velodyne_nodelet_manager"
args="manager" />
<arg name="device_ip" default="" />
<arg name="frame_id" default="velodyne" />
<arg name="manager" default="$(arg frame_id)_nodelet_manager" />
<arg name="model" default="64E" />
<arg name="pcap" default="" />
<arg name="port" default="2368" />
Expand All @@ -19,8 +14,12 @@
<arg name="repeat_delay" default="0.0" />
<arg name="rpm" default="600.0" />

<node pkg="nodelet" type="nodelet" name="driver_nodelet"
args="load velodyne_driver/DriverNodelet velodyne_nodelet_manager" >
<!-- start nodelet manager -->
<node pkg="nodelet" type="nodelet" name="$(arg manager)" args="manager" />

<!-- load driver nodelet into it -->
<node pkg="nodelet" type="nodelet" name="$(arg manager)_driver"
args="load velodyne_driver/DriverNodelet $(arg manager)" >
<param name="device_ip" value="$(arg device_ip)" />
<param name="frame_id" value="$(arg frame_id)"/>
<param name="model" value="$(arg model)"/>
Expand Down
11 changes: 4 additions & 7 deletions velodyne_pointcloud/launch/32e_points.launch
Original file line number Diff line number Diff line change
@@ -1,18 +1,13 @@
<!-- -*- mode: XML -*- -->
<!-- run velodyne_pointcloud/CloudNodelet in a nodelet manager for an HDL-32E
arg: calibration = path to calibration file (default: standard 32db.yaml)
pcap = path to packet capture file (default: use real device)
$Id$
-->
<!-- run velodyne_pointcloud/CloudNodelet in a nodelet manager for an HDL-32E -->

<launch>

<!-- declare arguments with default values -->
<arg name="calibration" default="$(find velodyne_pointcloud)/params/32db.yaml"/>
<arg name="device_ip" default="" />
<arg name="frame_id" default="velodyne" />
<arg name="manager" default="$(arg frame_id)_nodelet_manager" />
<arg name="max_range" default="130.0" />
<arg name="min_range" default="0.4" />
<arg name="pcap" default="" />
Expand All @@ -26,6 +21,7 @@
<include file="$(find velodyne_driver)/launch/nodelet_manager.launch">
<arg name="device_ip" value="$(arg device_ip)"/>
<arg name="frame_id" value="$(arg frame_id)"/>
<arg name="manager" value="$(arg manager)" />
<arg name="model" value="32E"/>
<arg name="pcap" value="$(arg pcap)"/>
<arg name="port" value="$(arg port)"/>
Expand All @@ -38,6 +34,7 @@
<!-- start cloud nodelet -->
<include file="$(find velodyne_pointcloud)/launch/cloud_nodelet.launch">
<arg name="calibration" value="$(arg calibration)"/>
<arg name="manager" value="$(arg manager)" />
<arg name="max_range" value="$(arg max_range)"/>
<arg name="min_range" value="$(arg min_range)"/>
</include>
Expand Down
9 changes: 4 additions & 5 deletions velodyne_pointcloud/launch/VLP16_points.launch
Original file line number Diff line number Diff line change
@@ -1,16 +1,13 @@
<!-- -*- mode: XML -*- -->
<!-- run velodyne_pointcloud/CloudNodelet in a nodelet manager for an VLP-16
arg: calibration = path to calibration file (default: standard VLP16db.yaml)
pcap = path to packet capture file (default: use real device)
-->
<!-- run velodyne_pointcloud/CloudNodelet in a nodelet manager for a VLP-16 -->

<launch>

<!-- declare arguments with default values -->
<arg name="calibration" default="$(find velodyne_pointcloud)/params/VLP16db.yaml"/>
<arg name="device_ip" default="" />
<arg name="frame_id" default="velodyne" />
<arg name="manager" default="$(arg frame_id)_nodelet_manager" />
<arg name="max_range" default="130.0" />
<arg name="min_range" default="0.4" />
<arg name="pcap" default="" />
Expand All @@ -24,6 +21,7 @@
<include file="$(find velodyne_driver)/launch/nodelet_manager.launch">
<arg name="device_ip" value="$(arg device_ip)"/>
<arg name="frame_id" value="$(arg frame_id)"/>
<arg name="manager" value="$(arg manager)" />
<arg name="model" value="VLP16"/>
<arg name="pcap" value="$(arg pcap)"/>
<arg name="port" value="$(arg port)"/>
Expand All @@ -36,6 +34,7 @@
<!-- start cloud nodelet -->
<include file="$(find velodyne_pointcloud)/launch/cloud_nodelet.launch">
<arg name="calibration" value="$(arg calibration)"/>
<arg name="manager" value="$(arg manager)" />
<arg name="max_range" value="$(arg max_range)"/>
<arg name="min_range" value="$(arg min_range)"/>
</include>
Expand Down
12 changes: 4 additions & 8 deletions velodyne_pointcloud/launch/cloud_nodelet.launch
Original file line number Diff line number Diff line change
@@ -1,18 +1,14 @@
<!-- -*- mode: XML -*- -->
<!-- run velodyne_pointcloud/CloudNodelet in a nodelet manager
arg: calibration = path to calibration file
$Id$
-->
<!-- run velodyne_pointcloud/CloudNodelet in a nodelet manager -->

<launch>
<arg name="calibration" default="" />
<arg name="manager" default="velodyne_nodelet_manager" />
<arg name="max_range" default="130.0" />
<arg name="min_range" default="0.9" />

<node pkg="nodelet" type="nodelet" name="cloud_nodelet"
args="load velodyne_pointcloud/CloudNodelet velodyne_nodelet_manager">
<node pkg="nodelet" type="nodelet" name="$(arg manager)_cloud"
args="load velodyne_pointcloud/CloudNodelet $(arg manager)">
<param name="calibration" value="$(arg calibration)"/>
<param name="max_range" value="$(arg max_range)"/>
<param name="min_range" value="$(arg min_range)"/>
Expand Down
12 changes: 4 additions & 8 deletions velodyne_pointcloud/launch/transform_nodelet.launch
Original file line number Diff line number Diff line change
@@ -1,18 +1,14 @@
<!-- -*- mode: XML -*- -->
<!-- run velodyne_pointcloud/TransformNodelet in a nodelet manager
arg: calibration = path to calibration file
$Id$
-->
<!-- run velodyne_pointcloud/TransformNodelet in a nodelet manager -->

<launch>
<arg name="calibration" default="" />
<arg name="frame_id" default="odom" />
<arg name="manager" default="velodyne_nodelet_manager" />
<arg name="max_range" default="130.0" />
<arg name="min_range" default="0.9" />
<node pkg="nodelet" type="nodelet" name="transform_nodelet"
args="load velodyne_pointcloud/TransformNodelet velodyne_nodelet_manager" >
<node pkg="nodelet" type="nodelet" name="$(arg manager)_transform"
args="load velodyne_pointcloud/TransformNodelet $(arg manager)" >
<param name="calibration" value="$(arg calibration)"/>
<param name="frame_id" value="$(arg frame_id)"/>
<param name="max_range" value="$(arg max_range)"/>
Expand Down
12 changes: 3 additions & 9 deletions velodyne_pointcloud/tests/cloud_nodelet_32e_hz.test
Original file line number Diff line number Diff line change
Expand Up @@ -3,18 +3,12 @@

<launch>

<!-- start nodelet manager and driver nodelets -->
<include file="$(find velodyne_driver)/launch/nodelet_manager.launch">
<arg name="model" value="32E"/>
<!-- start nodelet manager, driver and cloud nodelets -->
<include file="$(find velodyne_pointcloud)/launch/32e_points.launch">
<arg name="frame_id" value="test_frame"/>
<arg name="pcap" value="$(find velodyne_pointcloud)/tests/32e.pcap"/>
</include>

<!-- start cloud nodelet using test calibration file -->
<include file="$(find velodyne_pointcloud)/launch/cloud_nodelet.launch">
<arg name="calibration"
value="$(find velodyne_pointcloud)/params/32db.yaml"/>
</include>

<!-- verify PointCloud2 publication rate -->
<test test-name="cloud_nodelet_32e_hz_test" pkg="rostest"
type="hztest" name="hztest_cloud_nodelet_32e" >
Expand Down
12 changes: 3 additions & 9 deletions velodyne_pointcloud/tests/cloud_nodelet_vlp16_hz.test
Original file line number Diff line number Diff line change
Expand Up @@ -3,18 +3,12 @@

<launch>

<!-- start nodelet manager and driver nodelets -->
<include file="$(find velodyne_driver)/launch/nodelet_manager.launch">
<arg name="model" value="VLP16"/>
<!-- start nodelet manager, driver and cloud nodelets -->
<include file="$(find velodyne_pointcloud)/launch/VLP16_points.launch">
<arg name="frame_id" value="test_frame"/>
<arg name="pcap" value="$(find velodyne_pointcloud)/tests/vlp16.pcap"/>
</include>

<!-- start cloud nodelet using test calibration file -->
<include file="$(find velodyne_pointcloud)/launch/cloud_nodelet.launch">
<arg name="calibration"
value="$(find velodyne_pointcloud)/params/VLP16db.yaml"/>
</include>

<!-- verify PointCloud2 publication rate -->
<test test-name="cloud_nodelet_vlp16_hz_test" pkg="rostest"
type="hztest" name="hztest_cloud_nodelet_vlp16" >
Expand Down

0 comments on commit 4d0d71f

Please sign in to comment.