<!-- -*- mode: XML -*- --> <!-- run velodyne_pointcloud/TransformNodelet 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="" /> <arg name="port" default="2368" /> <arg name="read_fast" default="false" /> <arg name="read_once" default="false" /> <arg name="repeat_delay" default="0.0" /> <arg name="rpm" default="600.0" /> <arg name="gps_time" default="false" /> <arg name="pcap_time" default="false" /> <arg name="cut_angle" default="-0.01" /> <arg name="timestamp_first_packet" default="false" /> <arg name="laserscan_ring" default="-1" /> <arg name="laserscan_resolution" default="0.007" /> <arg name="organize_cloud" default="false" /> <!-- start nodelet manager and driver nodelets --> <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)"/> <arg name="read_fast" value="$(arg read_fast)"/> <arg name="read_once" value="$(arg read_once)"/> <arg name="repeat_delay" value="$(arg repeat_delay)"/> <arg name="rpm" value="$(arg rpm)"/> <arg name="gps_time" value="$(arg gps_time)"/> <arg name="pcap_time" value="$(arg pcap_time)"/> <arg name="cut_angle" value="$(arg cut_angle)"/> <arg name="timestamp_first_packet" value="$(arg timestamp_first_packet)"/> </include> <!-- start transform nodelet --> <include file="$(find velodyne_pointcloud)/launch/transform_nodelet.launch"> <arg name="model" value="32E"/> <arg name="calibration" value="$(arg calibration)"/> <arg name="manager" value="$(arg manager)" /> <arg name="fixed_frame" value="" /> <arg name="target_frame" value="" /> <arg name="max_range" value="$(arg max_range)"/> <arg name="min_range" value="$(arg min_range)"/> <arg name="organize_cloud" value="$(arg organize_cloud)"/> </include> <!-- start laserscan nodelet --> <include file="$(find velodyne_pointcloud)/launch/laserscan_nodelet.launch"> <arg name="manager" value="$(arg manager)" /> <arg name="ring" value="$(arg laserscan_ring)"/> <arg name="resolution" value="$(arg laserscan_resolution)"/> </include> </launch>