-
Notifications
You must be signed in to change notification settings - Fork 229
Expand file tree
/
Copy pathrecord.launch
More file actions
179 lines (160 loc) · 8.26 KB
/
record.launch
File metadata and controls
179 lines (160 loc) · 8.26 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
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
<launch>
<arg name="ouster_ns" default="ouster" doc="Override the default namespace of all ouster nodes"/>
<arg name="sensor_hostname" doc="hostname or IP in dotted decimal form of the sensor"/>
<arg name="udp_dest" default=" " doc="hostname or IP where the sensor will send data packets"/>
<arg name="lidar_port" default="0" doc="port to which the sensor should send lidar data"/>
<arg name="imu_port" default="0" doc="port to which the sensor should send imu data"/>
<arg name="udp_profile_lidar" default=" " doc="lidar packet profile; possible values: {
LEGACY,
RNG19_RFL8_SIG16_NIR16,
RNG15_RFL8_NIR8
RNG19_RFL8_SIG16_NIR16_DUAL,
FUSA_RNG15_RFL8_NIR8_DUAL
}"/>
<arg name="lidar_mode" default=" " doc="resolution and rate; possible values: {
512x10,
512x20,
1024x10,
1024x20,
2048x10,
4096x5
}"/>
<arg name="timestamp_mode" default=" " doc="method used to timestamp measurements; possible values: {
TIME_FROM_INTERNAL_OSC,
TIME_FROM_SYNC_PULSE_IN,
TIME_FROM_PTP_1588,
TIME_FROM_ROS_TIME
}"/>
<arg name="ptp_utc_tai_offset" default="-37.0"
doc="UTC/TAI offset in seconds to apply when using TIME_FROM_PTP_1588"/>
<arg name="metadata" default="" doc="path to write metadata file when receiving sensor data"/>
<arg name="bag_file" default="" doc="file name to use for the recorded bag file"/>
<arg name="viz" default="true" doc="whether to run a rviz"/>
<arg name="rviz_config" default="$(find ouster_ros)/config/viz.rviz" doc="optional rviz config file"/>
<arg name="tf_prefix" default=" " doc="namespace for tf transforms"/>
<arg name="sensor_frame" default="os_sensor"
doc="sets name of choice for the sensor_frame tf frame, value can not be empty"/>
<arg name="lidar_frame" default="os_lidar"
doc="sets name of choice for the os_lidar tf frame, value can not be empty"/>
<arg name="imu_frame" default="os_imu"
doc="sets name of choice for the os_imu tf frame, value can not be empty"/>
<arg name="point_cloud_frame" default=" "
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="pub_static_tf" default="true" 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="dynamic_transforms_broadcast" default="false"
doc="static or dynamic transforms broadcast"/>
<arg name="dynamic_transforms_broadcast_rate" default="1.0"
doc="set the rate (Hz) of broadcast when using dynamic broadcast; minimum value is 1 Hz"/>
<arg name="proc_mask" default="IMG|PCL|IMU|SCAN|TLM" doc="
The IMG flag here is not supported and does not affect anything,
to disable image topics you would need to omit the os_image node
from the launch file"/>
<arg name="scan_ring" default="0" doc="
use this parameter in conjunction with the SCAN flag
and choose a value the range [0, sensor_beams_count)"/>
<arg name="point_type" default="original" doc="point type for the generated point cloud;
available options: {
original,
native,
xyz,
xyzi,
xyzir
}"/>
<arg name="organized" default="true"
doc="generate an organzied point cloud"/>
<arg name="destagger" default="true"
doc="enable or disable point cloud destaggering"/>
<arg name="min_range" default="0.0"
doc="minimum lidar range to consider (meters)"/>
<arg name="max_range" default="10000.0"
doc="maximum lidar range to consider (meters)"/>
<arg name="azimuth_window_start" default="0" doc="azimuth window start,
values range [0, 360000] millidegrees"/>
<arg name="azimuth_window_end" default="360000" doc="azimuth window end,
values range [0, 360000] millidegrees"/>
<arg name="persist_config" default="false"
doc="request the sensor to persist settings"/>
<arg name="attempt_reconnect" default="false"
doc="attempting to reconnect to the sensor after connection loss or
sensor powered down"/>
<arg name="dormant_period_between_reconnects" default="1.0"
doc="wait time in seconds between reconnection attempts"/>
<arg name="max_failed_reconnect_attempts" default="2147483647"
doc="maximum number of attempts trying to communicate with the sensor.
Counter resets upon successful connection"/>
<arg name="min_scan_valid_columns_ratio" default="0.0"
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_nodelet_mgr"
output="screen" required="true" args="manager"/>
</group>
<group ns="$(arg ouster_ns)">
<node pkg="nodelet" type="nodelet" name="os_node"
output="screen" required="true"
launch-prefix="bash -c 'sleep 1; $0 $@' "
args="load ouster_ros/OusterSensor os_nodelet_mgr">
<param name="~/sensor_hostname" type="str" value="$(arg sensor_hostname)"/>
<param name="~/udp_dest" type="str" value="$(arg udp_dest)"/>
<param name="~/lidar_port" type="int" value="$(arg lidar_port)"/>
<param name="~/imu_port" type="int" value="$(arg imu_port)"/>
<param name="~/udp_profile_lidar" type="str" value="$(arg udp_profile_lidar)"/>
<param name="~/lidar_mode" type="str" value="$(arg lidar_mode)"/>
<param name="~/timestamp_mode" type="str" value="$(arg timestamp_mode)"/>
<param name="~/ptp_utc_tai_offset" type="double"
value="$(arg ptp_utc_tai_offset)"/>
<param name="~/metadata" type="str" value="$(arg metadata)"/>
<param name="~/proc_mask" type="str" value="$(arg proc_mask)"/>
<param name="~/azimuth_window_start" value="$(arg azimuth_window_start)"/>
<param name="~/azimuth_window_end" value="$(arg azimuth_window_end)"/>
<param name="~/persist_config" value="$(arg persist_config)"/>
<param name="~/attempt_reconnect" value="$(arg attempt_reconnect)"/>
<param name="~/dormant_period_between_reconnects"
value="$(arg dormant_period_between_reconnects)"/>
<param name="~/max_failed_reconnect_attempts"
value="$(arg max_failed_reconnect_attempts)"/>
</node>
</group>
<include file="$(find ouster_ros)/launch/common.launch">
<arg name="ouster_ns" value="$(arg ouster_ns)"/>
<arg name="viz" value="$(arg viz)"/>
<arg name="rviz_config" value="$(arg rviz_config)"/>
<arg name="tf_prefix" value="$(arg tf_prefix)"/>
<arg name="sensor_frame" value="$(arg sensor_frame)"/>
<arg name="lidar_frame" value="$(arg lidar_frame)"/>
<arg name="imu_frame" value="$(arg imu_frame)"/>
<arg name="point_cloud_frame" value="$(arg point_cloud_frame)"/>
<arg name="pub_static_tf" value="$(arg pub_static_tf)"/>
<arg name="timestamp_mode" value="$(arg timestamp_mode)"/>
<arg name="ptp_utc_tai_offset" value="$(arg ptp_utc_tai_offset)"/>
<arg name="dynamic_transforms_broadcast"
value="$(arg dynamic_transforms_broadcast)"/>
<arg name="dynamic_transforms_broadcast_rate"
value="$(arg dynamic_transforms_broadcast_rate)"/>
<arg name="proc_mask" value="$(arg proc_mask)"/>
<arg name="scan_ring" value="$(arg scan_ring)"/>
<arg name="point_type" value="$(arg point_type)"/>
<arg name="organized" value="$(arg organized)"/>
<arg name="destagger" value="$(arg destagger)"/>
<arg name="min_range" value="$(arg min_range)"/>
<arg name="max_range" value="$(arg max_range)"/>
<arg name="~/min_scan_valid_columns_ratio"
value="$(arg min_scan_valid_columns_ratio)"/>
</include>
<arg name="_use_bag_file_name" value="$(eval not (bag_file == ''))"/>
<arg name="_topics_to_record" value="
/$(arg ouster_ns)/imu_packets
/$(arg ouster_ns)/lidar_packets
/$(arg ouster_ns)/metadata
"/>
<node if="$(arg _use_bag_file_name)" pkg="rosbag" type="record"
name="rosbag_record_sensor" output="screen" required="true"
args="record -O $(arg bag_file) $(arg _topics_to_record)"/>
<node unless="$(arg _use_bag_file_name)" pkg="rosbag" type="record"
name="rosbag_record_sensor" output="screen" required="true"
args="record $(arg _topics_to_record)"/>
</launch>