浏览该文件的文档.
2 <
arg name=
"velodyne64_calibration_online" default=
"true" />
4 <
arg name=
"velodyne64_calibration_file" default=
"$(find velodyne_pointcloud)/params/64E_S3_calibration_example.yaml"/>
5 <
arg name=
"extrinsics_velodyne64" default=
"$(find velodyne_pointcloud)/params/velodyne64_novatel_extrinsics_example.yaml"/>
6 <
arg name=
"velodyne64_frame_id" default=
"velodyne64"/>
7 <
arg name=
"organized" default=
"false"/>
8 <
arg name=
"min_range" default=
"0.9" />
9 <
arg name=
"max_range_64" default=
"70.0" />
10 <
arg name=
"rpm" default=
"600"/>
12 <
arg name=
"model" default=
"64E_S3D_STRONGEST" />
14 <
arg name=
"tf_query_timeout" default=
"0.1"/>
15 <
arg name=
"nodelet_manager_name" value=
"velodyne_nodelet_manager"/>
17 <
include file=
"$(find velodyne_pointcloud)/launch/nodelet_manager.launch">
18 <
arg name=
"nodelet_manager_name" value=
"$(arg nodelet_manager_name)"/>
22 <
include file=
"$(find velodyne_driver)/launch/driver_nodelet.launch">
23 <
arg name=
"node_name" value=
"sensor_velodyne64_driver"/>
24 <
arg name=
"nodelet_manager_name" value=
"$(arg nodelet_manager_name)"/>
25 <
arg name=
"model" value=
"$(arg model)"/>
26 <
arg name=
"rpm" value=
"$(arg rpm)"/>
27 <
arg name=
"frame_id" value=
"$(arg velodyne64_frame_id)"/>
28 <
arg name=
"topic" value=
"/apollo/sensor/velodyne64/VelodyneScanUnified"/>
32 <
include file=
"$(find velodyne_pointcloud)/launch/convert_nodelet.launch">
33 <
arg name=
"node_name" value=
"sensor_velodyne64_convert"/>
34 <
arg name=
"nodelet_manager_name" value=
"$(arg nodelet_manager_name)"/>
35 <
arg name=
"model" value=
"$(arg model)"/>
36 <
arg name=
"calibration_online" value=
"$(arg velodyne64_calibration_online)" />
37 <
arg name=
"calibration" default=
"$(arg velodyne64_calibration_file)" />
38 <
arg name=
"organized" default=
"$(arg organized)"/>
39 <
arg name=
"min_range" default=
"$(arg min_range)" />
40 <
arg name=
"max_range" default=
"$(arg max_range_64)" />
41 <
arg name=
"topic_pointcloud" default=
"/apollo/sensor/velodyne64/PointCloud2"/>
42 <
arg name=
"topic_packets" default=
"/apollo/sensor/velodyne64/VelodyneScanUnified"/>
46 <
include file=
"$(find velodyne_pointcloud)/launch/compensator_nodelet.launch">
47 <
arg name=
"node_name" value=
"sensor_velodyne64_compensator"/>
48 <
arg name=
"nodelet_manager_name" value=
"$(arg nodelet_manager_name)"/>
49 <
arg name=
"child_frame_id" value=
"$(arg velodyne64_frame_id)"/>
50 <
arg name=
"tf_query_timeout" value=
"$(arg tf_query_timeout)"/>
51 <
arg name=
"topic_pointcloud" value=
"/apollo/sensor/velodyne64/PointCloud2"/>
52 <
arg name=
"topic_compensated_pointcloud" value=
"/apollo/sensor/velodyne64/compensator/PointCloud2"/>