/
zed_rtabmap.launch
72 lines (63 loc) · 3.91 KB
/
zed_rtabmap.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
<?xml version="1.0"?>
<!--
Copyright (c) 2018, STEREOLABS.
All rights reserved.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
"AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
-->
<launch>
<arg name="zed_namespace" default="zed" />
<arg name="svo_file" default="" /> <!-- <arg name="svo_file" default="path/to/svo/file.svo"> -->
<arg name="camera_model" default="1" /> <!-- 0=ZED, 1=ZEDM-->
<arg name="serial_number" default="0" />
<arg name="verbose" default="true" />
<arg name="resolution" default="2" /> <!--0=RESOLUTION_HD2K, 1=RESOLUTION_HD1080, 2=RESOLUTION_HD720, 3=RESOLUTION_VGA -->
<arg name="frame_rate" default="30" />
<!-- RESOLUTION_HD2K -> 2208*1242, available framerates: 15 fps.
RESOLUTION_HD1080 -> 1920*1080, available framerates: 15, 30 fps.
RESOLUTION_HD720 -> 1280*720, available framerates: 15, 30, 60 fps.
RESOLUTION_VGA -> 672*376, available framerates: 15, 30, 60, 100 fps. -->
<arg name="rgb_topic" default="rgb/image_rect_color" />
<arg name="depth_topic" default="depth/depth_registered" />
<arg name="camera_info_topic" default="rgb/camera_info" />
<arg name="depth_camera_info_topic" default="depth/camera_info" />
<arg name="camera_frame" default="zed_camera_center" />
<group ns="$(arg zed_namespace)">
<!-- ZED Wrapper Node-->
<include file="$(find zed_wrapper)/launch/zed_camera.launch">
<arg name="svo_file" value="$(arg svo_file)" />
<arg name="camera_model" value="$(arg camera_model)" />
<arg name="serial_number" value="$(arg serial_number)" />
<arg name="resolution" value="$(arg resolution)" />
<arg name="frame_rate" value="$(arg frame_rate)" />
<arg name="verbose" value="$(arg verbose)" />
<arg name="rgb_topic" value="$(arg rgb_topic)" />
<arg name="depth_topic" value="$(arg depth_topic)" />
<arg name="rgb_info_topic" value="$(arg camera_info_topic)" />
<arg name="depth_cam_info_topic" value="$(arg depth_camera_info_topic)" />
<arg name="base_frame" value="$(arg camera_frame)" />
<arg name="publish_map_tf" value="false" />
</include>
</group>
<!-- RTAB-map Node-->
<include file="$(find rtabmap_ros)/launch/rtabmap.launch">
<arg name="rtabmap_args" value="--delete_db_on_start" />
<arg name="rgb_topic" value="/$(arg zed_namespace)/$(arg rgb_topic)" />
<arg name="depth_topic" value="/$(arg zed_namespace)/$(arg depth_topic)" />
<arg name="camera_info_topic" value="/$(arg zed_namespace)/$(arg camera_info_topic)" />
<arg name="depth_camera_info_topic" value="/$(arg zed_namespace)/$(arg depth_camera_info_topic)" />
<arg name="frame_id" value="$(arg camera_frame)" />
<arg name="approx_sync" value="false" />
<arg name="visual_odometry" value="false" />
<arg name="odom_topic" value="/$(arg zed_namespace)/odom" />
</include>
</launch>