forked from SICKAG/sick_scan_xd
-
Notifications
You must be signed in to change notification settings - Fork 0
/
sick_tim_5xx_twin.launch
86 lines (76 loc) · 6.98 KB
/
sick_tim_5xx_twin.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
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
<?xml version="1.0"?>
<!--
Example launch of using two scanners in parallel
In this example we use two TIM5xx-scanner with a mounting distance of 2 m.
Do see the result in rviz we recommend the following settings:
1. Global Options->Fixed Frame: map
2. Pointcloud2->Topic: /cloud_1
3. Pointcloud2->Topic: /cloud_2
4. Modify the given ip addresses to your local setup.
Remark: Add two Pointcloud2-Visualizer to the Displays-Windows.
You can also add two Laserscan-Visualizer. Please set the topic for laserscan-Visualizer to /scan_1 and /scan_2 in this case.
-->
<!-- Using node option required="true" will close roslaunch after node exits -->
<launch>
<arg name="hostname1" default="192.168.0.1"/>
<arg name="hostname2" default="192.168.0.2"/>
<arg name="add_transform_xyz_rpy" default="0,0,0,0,0,0"/>
<param name="robot_description" command="$(find xacro)/xacro.py '$(find sick_scan)/urdf/example.urdf.xacro'"/>
<node pkg="tf" type="static_transform_publisher" name="scanner1_to_map" args="0 0 0 0 0 0 map laser_1 100"/>
<node pkg="tf" type="static_transform_publisher" name="scanner2_to_map" args="2 0 0 0 0 0 map laser_2 100"/>
<node name="sick_tim_5xx_1" pkg="sick_scan" type="sick_generic_caller" respawn="false" output="screen" required="true">
<param name="scanner_type" type="string" value="sick_tim_5xx"/>
<param name="frame_id" value="/laser_1"/>
<param name="min_ang" type="double" value="-2.35619449"/><!-- -135 deg -->
<param name="max_ang" type="double" value="2.35619449"/><!-- 135 deg -->
<param name="range_max" type="double" value="100.0"/>
<param name="intensity" type="bool" value="True"/>
<param name="hostname" type="string" value="$(arg hostname1)"/>
<param name="port" type="string" value="2112"/>
<param name="timelimit" type="int" value="5"/>
<param name="min_intensity" type="double" value="0.0"/> <!-- Set range of LaserScan messages to infinity, if intensity < min_intensity (default: 0) -->
<param name="use_generation_timestamp" type="bool" value="true"/> <!-- Use the lidar generation timestamp (true, default) or send timestamp (false) for the software pll converted message timestamp -->
<remap from="scan" to="scan_1"/>
<remap from="cloud" to="cloud_1"/>
<!-- Apply an additional transform to the cartesian pointcloud, default: "0,0,0,0,0,0" (i.e. no transform) -->
<!-- Note: add_transform_xyz_rpy is specified by 6D pose x, y, z, roll, pitch, yaw in [m] resp. [rad] -->
<!-- It transforms a 3D point in cloud coordinates to 3D point in user defined world coordinates: -->
<!-- add_transform_xyz_rpy := T[world,cloud] with parent "world" and child "cloud", i.e. P_world = T[world,cloud] * P_cloud -->
<!-- The additional transform applies to cartesian lidar pointclouds and visualization marker (fields) -->
<!-- It is NOT applied to polar pointclouds, radarscans, ldmrs objects or other messages -->
<param name="add_transform_xyz_rpy" type="string" value="$(arg add_transform_xyz_rpy)" />
<param name="start_services" type="bool" value="True" /> <!-- Start ros service for cola commands, default: true -->
<param name="message_monitoring_enabled" type="bool" value="True" /> <!-- Enable message monitoring with reconnect+reinit in case of timeouts, default: true -->
<param name="read_timeout_millisec_default" type="int" value="5000"/> <!-- 5 sec read timeout in operational mode (measurement mode), default: 5000 milliseconds -->
<param name="read_timeout_millisec_startup" type="int" value="120000"/> <!-- 120 sec read timeout during startup (sensor may be starting up, which can take up to 120 sec.), default: 120000 milliseconds -->
<param name="read_timeout_millisec_kill_node" type="int" value="150000"/> <!-- 150 sec pointcloud timeout, ros node will be killed if no point cloud published within the last 150 sec., default: 150000 milliseconds -->
<param name="client_authorization_pw" type="string" value="F4724744"/> <!-- Default password for client authorization -->
</node>
<node name="sick_tim_5xx_2" pkg="sick_scan" type="sick_generic_caller" respawn="false" output="screen" required="true">
<param name="scanner_type" type="string" value="sick_tim_5xx"/>
<param name="frame_id" value="/laser_2"/>
<param name="min_ang" type="double" value="-2.35619449"/><!-- -135 deg -->
<param name="max_ang" type="double" value="2.35619449"/><!-- 135 deg -->
<param name="range_max" type="double" value="100.0"/>
<param name="intensity" type="bool" value="True"/>
<param name="hostname" type="string" value="$(arg hostname2)"/>
<param name="port" type="string" value="2112"/>
<param name="timelimit" type="int" value="5"/>
<param name="use_generation_timestamp" type="bool" value="true"/> <!-- Use the lidar generation timestamp (true, default) or send timestamp (false) for the software pll converted message timestamp -->
<!-- Apply an additional transform to the cartesian pointcloud, default: "0,0,0,0,0,0" (i.e. no transform) -->
<!-- Note: add_transform_xyz_rpy is specified by 6D pose x, y, z, roll, pitch, yaw in [m] resp. [rad] -->
<!-- It transforms a 3D point in cloud coordinates to 3D point in user defined world coordinates: -->
<!-- add_transform_xyz_rpy := T[world,cloud] with parent "world" and child "cloud", i.e. P_world = T[world,cloud] * P_cloud -->
<!-- The additional transform applies to cartesian lidar pointclouds and visualization marker (fields) -->
<!-- It is NOT applied to polar pointclouds, radarscans, ldmrs objects or other messages -->
<param name="add_transform_xyz_rpy" type="string" value="$(arg add_transform_xyz_rpy)" />
<param name="start_services" type="bool" value="True" /> <!-- Start ros service for cola commands, default: true -->
<param name="message_monitoring_enabled" type="bool" value="True" /> <!-- Enable message monitoring with reconnect+reinit in case of timeouts, default: true -->
<param name="read_timeout_millisec_default" type="int" value="5000"/> <!-- 5 sec read timeout in operational mode (measurement mode), default: 5000 milliseconds -->
<param name="read_timeout_millisec_startup" type="int" value="120000"/> <!-- 120 sec read timeout during startup (sensor may be starting up, which can take up to 120 sec.), default: 120000 milliseconds -->
<param name="read_timeout_millisec_kill_node" type="int" value="150000"/> <!-- 150 sec pointcloud timeout, ros node will be killed if no point cloud published within the last 150 sec., default: 150000 milliseconds -->
<param name="client_authorization_pw" type="string" value="F4724744"/> <!-- Default password for client authorization -->
<remap from="scan" to="scan_2"/>
<remap from="cloud" to="cloud_2"/>
</node>
</launch>