forked from ouster-lidar/ouster-ros
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathsensor_mtp.launch
70 lines (65 loc) · 3.23 KB
/
sensor_mtp.launch
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
<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" doc="hostname or multicast group IP where the sensor will send UDP data packets"/>
<arg name="mtp_dest" default=" " doc="hostname IP address for receiving data packets via multicast,
by default it is INADDR_ANY, so packets will be received on first available interface"/>
<arg name="mtp_main" default="false" doc="if true, then configure and reinit the sensor, otherwise
start client with active configuration of sensor"/>
<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_DUAL,
RNG19_RFL8_SIG16_NIR16,
RNG15_RFL8_NIR8
}"/>
<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="metadata" default=" " doc="path to write metadata file when receiving sensor data"/>
<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"/>
<group ns="$(arg ouster_ns)">
<node pkg="nodelet" type="nodelet" name="os_nodelet_mgr"
output="screen" required="true"
launch-prefix="bash -c 'sleep 2; $0 $@' "
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 3; $0 $@' "
args="load nodelets_os/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="~/mtp_dest" type="str" value="$(arg mtp_dest)"/>
<param name="~/mtp_main" type="bool" value="$(arg mtp_main)"/>
<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="~/metadata" type="str" value="$(arg metadata)"/>
</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="timestamp_mode" value="$(arg timestamp_mode)"/>
</include>
</launch>