-
Notifications
You must be signed in to change notification settings - Fork 229
Expand file tree
/
Copy pathcommon.launch
More file actions
100 lines (85 loc) · 4.48 KB
/
common.launch
File metadata and controls
100 lines (85 loc) · 4.48 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
<launch>
<arg name="ouster_ns" doc="Override the default namespace of all ouster nodes"/>
<arg name="viz" doc="whether to run a rviz"/>
<arg name="rviz_config" doc="optional rviz config file"/>
<arg name="tf_prefix" doc="namespace for tf transforms"/>
<arg name="sensor_frame" doc="
sets name of choice for the sensor_frame tf frame, value can not be empty"/>
<arg name="lidar_frame" doc="
sets name of choice for the os_lidar tf frame, value can not be empty"/>
<arg name="imu_frame" doc="
sets name of choice for the os_imu tf frame, value can not be empty"/>
<arg name="point_cloud_frame" doc="
when this flag is set to True, the driver will broadcast the TF transforms
for the imu/sensor/lidar frames. Prevent the driver from broadcasting TF transforms by
setting this parameter to False.."/>
<arg name="pub_static_tf" doc="
which frame to be used when publishing PointCloud2 or LaserScan messages.
Choose between the value of sensor_frame or lidar_frame, leaving this value empty
would set lidar_frame to be the frame used when publishing these messages."/>
<arg name="timestamp_mode" doc="method used to timestamp measurements"/>
<arg name="ptp_utc_tai_offset" doc="UTC/TAI offset in seconds to apply when using TIME_FROM_PTP_1588"/>
<arg name="dynamic_transforms_broadcast" doc="static or dynamic transforms broadcast"/>
<arg name="dynamic_transforms_broadcast_rate"
doc="set the rate (Hz) of broadcast when using dynamic broadcast; minimum value is 1 Hz"/>
<arg name="_no_bond" default="" doc="set the no-bond option when loading nodelets"/>
<arg name="proc_mask" doc="
use any combination of the 4 flags to enable or disable specific processors"/>
<arg name="scan_ring" doc="
use this parameter in conjunction with the SCAN flag
and choose a value the range [0, sensor_beams_count)"/>
<arg name="point_type" doc="point type for the generated point cloud;
available options: {
original,
native,
xyz,
xyzi,
xyzir
}"/>
<arg name="organized" doc="generate an organzied point cloud"/>
<arg name="destagger" doc="enable or disable point cloud destaggering"/>
<arg name="min_range" doc="minimum lidar range to consider (meters)"/>
<arg name="max_range" doc="maximum lidar range to consider (meters)"/>
<arg name="min_scan_valid_columns_ratio"
doc="The minimum ratio of valid columns for processing the LidarScan [0, 1]"/>
<group ns="$(arg ouster_ns)">
<node pkg="nodelet" type="nodelet" name="os_cloud_node"
output="screen" required="true"
args="load ouster_ros/OusterCloud os_nodelet_mgr $(arg _no_bond)">
<param name="~/tf_prefix" type="str" value="$(arg tf_prefix)"/>
<param name="~/sensor_frame" value="$(arg sensor_frame)"/>
<param name="~/lidar_frame" value="$(arg lidar_frame)"/>
<param name="~/imu_frame" value="$(arg imu_frame)"/>
<param name="~/point_cloud_frame" value="$(arg point_cloud_frame)"/>
<param name="~/pub_static_tf" value="$(arg pub_static_tf)"/>
<param name="~/timestamp_mode" type="str" value="$(arg timestamp_mode)"/>
<param name="~/dynamic_transforms_broadcast" type="bool"
value="$(arg dynamic_transforms_broadcast)"/>
<param name="~/dynamic_transforms_broadcast_rate" type="double"
value="$(arg dynamic_transforms_broadcast_rate)"/>
<param name="~/proc_mask" value="$(arg proc_mask)"/>
<param name="~/scan_ring" value="$(arg scan_ring)"/>
<param name="~/ptp_utc_tai_offset" type="double" value="$(arg ptp_utc_tai_offset)"/>
<param name="~/point_type" value="$(arg point_type)"/>
<param name="~/organized" value="$(arg organized)"/>
<param name="~/destagger" value="$(arg destagger)"/>
<param name="~/min_range" value="$(arg min_range)"/>
<param name="~/max_range" value="$(arg max_range)"/>
<param name="~/min_scan_valid_columns_ratio"
value="$(arg min_scan_valid_columns_ratio)"/>
</node>
</group>
<group ns="$(arg ouster_ns)">
<node pkg="nodelet" type="nodelet" name="img_node"
output="screen" required="true"
args="load ouster_ros/OusterImage os_nodelet_mgr $(arg _no_bond)">
<param name="~/proc_mask" value="$(arg proc_mask)"/>
</node>
</group>
<!-- TODO: how can/should we handle the change of default ouster namespace in RVIZ? -->
<node if="$(arg viz)"
pkg="rviz" name="rviz" type="rviz"
output="screen" required="false"
launch-prefix="bash -c 'sleep 5; $0 $@' "
args="-d $(arg rviz_config)"/>
</launch>