-
Notifications
You must be signed in to change notification settings - Fork 10
/
Copy pathsick_lidar_localization.launch
46 lines (42 loc) · 6.08 KB
/
sick_lidar_localization.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
<?xml version="1.0"?>
<launch>
<!-- Launch sick_lidar_localization -->
<arg name="hostname" default="192.168.0.1"/> <!-- IP address of the localization controller -->
<arg name="serverpath" default="api"/> <!-- Relative path to the rest api, i.e. url of rest requests is "http://<hostname>/<serverpath>/" -->
<arg name="verbose" default="0"/> <!-- If verbose>0: print informational messages, otherwise silent except for error messages -->
<arg name="udp_ip_lls_output" default=""/> <!-- IP address for output UDP messages, or "" for broadcast (INADDR_ANY), default: "", use IP address of your local machine -->
<arg name="udp_ip_lls_input" default="192.168.0.1"/> <!-- IP address for input UDP messages, or "" for broadcast, default: "192.168.0.1", (IP adress of the localization controller) -->
<arg name="udp_port_lls_input" default="5009"/> <!-- UDP port of input messages -->
<arg name="udp_lls_input_source_id" default="21"/> <!-- Source_id of UDP input messages (e.g. source ID of odom sender), has to match the ID in the localization controller configuration file lidarloc_config.yml (e.g. vehicle/odometer/external/interface/sourceId) -->
<arg name="udp_port_lls_output" default="5010"/> <!-- UDP port of output messages -->
<arg name="udp_lls_output_logfile" default=""/> <!-- Optional logfile for human readable UDP output messages, default: "" (no outputlogfile) -->
<arg name="software_pll_fifo_length" default="7"/> <!-- Length of fifo in SoftwarePLL -->
<arg name="odom_topic" default="/odom"/> <!-- Topic of ros odom messages -->
<arg name="ros_odom_to_udp_msg" default="3"/> <!-- Convert ros odom message to udp: -->
<!-- 1 = map velocity to OdometryPayload0104 and send udp message type 1, version 4 -->
<!-- 2 = map position to OdometryPayload0105 and send udp message type 1, version 5 -->
<!-- 3 = map velocity to OdometryPayload0104 and position to OdometryPayload0105 and send both udp message type 1, version 4 and 5 -->
<!-- Launch sick_lidar_localization -->
<node name="sick_lidar_localization" pkg="sick_lidar_localization" type="sick_lidar_localization" output="screen">
<param name="hostname" type="string" value="$(arg hostname)"/> <!-- IP address of the localization controller, f.e. "192.168.0.1" (default) -->
<param name="serverpath" type="string" value="$(arg serverpath)"/> <!-- Relative path to the rest api, i.e. url of rest requests is "http://<hostname>/<serverpath>/" -->
<param name="verbose" type="int" value="$(arg verbose)"/> <!-- If verbose>0: print informational messages, otherwise silent except for error messages -->
<param name="udp_ip_lls_output" type="string" value="$(arg udp_ip_lls_output)"/> <!-- IP address for output UDP messages, or "" for broadcast (INADDR_ANY), default: "", use IP address of your local machine -->
<param name="udp_ip_lls_input" type="string" value="$(arg udp_ip_lls_input)"/> <!-- IP address for input UDP messages, or "" for broadcast, default: "192.168.0.1", (IP adress of the localization controller) -->
<param name="udp_port_lls_input" type="int" value="$(arg udp_port_lls_input)"/> <!-- UDP port of input messages -->
<!-- We recommend to set the source_id in the input message itself instead of using the global setting. Output messages are defined in lidarloc_config.yml in LiDAR-LOC UI -->
<param name="udp_lls_input_source_id" type="int" value="$(arg udp_lls_input_source_id)"/> <!-- Default source_id of all UDP input messages if source_id not otherwise specified -->
<param name="udp_lls_input_source_id_1_4" type="int" value="$(arg udp_lls_input_source_id)"/> <!-- Default source_id of UDP input messages type 1 version 4 if not set in the message itself (i.e. source_id = 0) -->
<param name="udp_lls_input_source_id_1_5" type="int" value="$(arg udp_lls_input_source_id)"/> <!-- Default source_id of UDP input messages type 1 version 5 if not set in the message itself (i.e. source_id = 0) -->
<param name="udp_lls_input_source_id_3_3" type="int" value="$(arg udp_lls_input_source_id)"/> <!-- Default source_id of UDP input messages type 3 version 3 if not set in the message itself (i.e. source_id = 0) -->
<param name="udp_lls_input_source_id_4_3" type="int" value="$(arg udp_lls_input_source_id)"/> <!-- Default source_id of UDP input messages type 4 version 3 if not set in the message itself (i.e. source_id = 0) -->
<param name="udp_lls_input_source_id_4_4" type="int" value="$(arg udp_lls_input_source_id)"/> <!-- Default source_id of UDP input messages type 4 version 4 if not set in the message itself (i.e. source_id = 0) -->
<param name="udp_lls_input_source_id_7_1" type="int" value="$(arg udp_lls_input_source_id)"/> <!-- Default source_id of UDP input messages type 7 version 1 if not set in the message itself (i.e. source_id = 0) -->
<!-- end source_id global setting -->
<param name="udp_port_lls_output" type="int" value="$(arg udp_port_lls_output)"/> <!-- UDP port of output messages -->
<param name="udp_lls_output_logfile" type="string" value="$(arg udp_lls_output_logfile)"/> <!-- Optional logfile for human readable UDP output messages, default: "" (no outputlogfile) -->
<param name="software_pll_fifo_length" type="int" value="$(arg software_pll_fifo_length)"/> <!-- Length of fifo in SoftwarePLL -->
<param name="odom_topic" type="string" value="$(arg odom_topic)"/> <!-- Topic of ros odom messages -->
<param name="ros_odom_to_udp_msg" type="int" value="$(arg ros_odom_to_udp_msg)"/> <!-- Convert ros odom message to udp message type 1, version 4 or 5 -->
</node>
</launch>