-
Notifications
You must be signed in to change notification settings - Fork 0
/
zed_camera.launch.xml
91 lines (74 loc) · 4.05 KB
/
zed_camera.launch.xml
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
<?xml version="1.0"?>
<!--
Copyright (c) 2023, 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>
<!-- Camera Model and Name -->
<arg name="camera_name" default="zed" /> <!-- The name you want -->
<arg name="camera_model" default="zed" /> <!-- 'zed' or 'zedm' or 'zed2' -->
<arg name="node_name" default="zed_node" />
<!-- Load SVO file -->
<arg name="svo_file" default="" /><!-- <arg name="svo_file" default="path/to/svo/file.svo"> -->
<!-- Remote stream -->
<arg name="stream" default="" /> <!-- <arg name="stream" default="<ip_address>:<port>"> -->
<!-- Base frame -->
<arg name="base_frame" default="base_link" />
<!-- Publish ZED urdf -->
<arg name="publish_urdf" default="true" />
<arg name="camera_id" default="0" />
<arg name="gpu_id" default="-1" />
<!-- Position respect to base frame (i.e. "base_link) -->
<arg name="cam_pos_x" default="0.0" />
<arg name="cam_pos_y" default="0.0" />
<arg name="cam_pos_z" default="0.0" />
<!-- Orientation respect to base frame (i.e. "base_link) -->
<arg name="cam_roll" default="0.0" />
<arg name="cam_pitch" default="0.0" />
<arg name="cam_yaw" default="0.0" />
<!-- ROS URDF description of the ZED -->
<group if="$(arg publish_urdf)">
<param name="$(arg camera_name)_description"
command="$(find xacro)/xacro '$(find zed_wrapper)/urdf/zed_descr.urdf.xacro'
camera_name:=$(arg camera_name)
camera_model:=$(arg camera_model)
base_frame:=$(arg base_frame)
cam_pos_x:=$(arg cam_pos_x)
cam_pos_y:=$(arg cam_pos_y)
cam_pos_z:=$(arg cam_pos_z)
cam_roll:=$(arg cam_roll)
cam_pitch:=$(arg cam_pitch)
cam_yaw:=$(arg cam_yaw)"
/>
<node name="$(arg camera_name)_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" output="screen" required="true">
<remap from="robot_description" to="$(arg camera_name)_description" />
</node>
</group>
<node name="$(arg node_name)" pkg="zed_wrapper" type="zed_wrapper_node" output="screen" required="true"><!-- launch-prefix="valgrind" -->
<rosparam file="$(find pr2_utils)/config/camera/zed/common.yaml" command="load" />
<rosparam file="$(find pr2_utils)/config/camera/zed/$(arg camera_model).yaml" command="load" />
<!-- Camera name -->
<param name="general/camera_name" value="$(arg camera_name)" />
<!-- Base frame -->
<param name="general/base_frame" value="$(arg base_frame)" />
<!-- SVO file path -->
<param name="svo_file" value="$(arg svo_file)" />
<!-- Remote stream -->
<param name="stream" value="$(arg stream)" />
<!-- Camera ID -->
<param name="general/zed_id" value="$(arg camera_id)" />
<!-- GPU ID -->
<param name="general/gpu_id" value="$(arg gpu_id)" />
</node>
</launch>