-
Notifications
You must be signed in to change notification settings - Fork 3
/
openni2.launch
115 lines (99 loc) · 6.1 KB
/
openni2.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
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
<!-- Entry point for using OpenNI2 devices -->
<launch>
<!-- "camera" should uniquely identify the device. All topics are pushed down
into the "camera" namespace, and it is prepended to tf frame ids. -->
<arg name="camera" default="camera" />
<arg name="rgb_frame_id" default="$(arg camera)_rgb_optical_frame" />
<arg name="depth_frame_id" default="$(arg camera)_depth_optical_frame" />
<!-- device_id can have the following formats:
"#1" : the first device found
"2@X" : the Xth device on USB bus 2 -->
<arg name="device_id" default="#1" />
<!-- By default, calibrations are stored to file://${ROS_HOME}/camera_info/${NAME}.yaml,
where ${NAME} is of the form "[rgb|depth]_[serial#]", e.g. "depth_B00367707227042B".
See camera_info_manager docs for calibration URL details. -->
<arg name="rgb_camera_info_url" default="" />
<arg name="depth_camera_info_url" default="" />
<!-- Hardware depth registration -->
<arg name="depth_registration" default="false" />
<!-- Driver parameters -->
<arg name="color_depth_synchronization" default="false" />
<arg name="auto_exposure" default="true" />
<arg name="auto_white_balance" default="true" />
<!-- Arguments for remapping all device namespaces -->
<arg name="rgb" default="rgb" />
<arg name="ir" default="ir" />
<arg name="depth" default="depth" />
<!-- Optionally suppress loading the driver nodelet and/or publishing the default tf
tree. Useful if you are playing back recorded raw data from a bag, or are
supplying a more accurate tf tree from calibration. -->
<arg name="load_driver" default="true" />
<arg name="publish_tf" default="true" />
<!-- Processing Modules -->
<arg name="rgb_processing" default="true" />
<arg name="debayer_processing" default="false" />
<arg name="ir_processing" default="false" />
<arg name="depth_processing" default="true" />
<arg name="depth_registered_processing" default="true" />
<arg name="disparity_processing" default="false" />
<arg name="disparity_registered_processing" default="false" />
<arg name="hw_registered_processing" default="true" if="$(arg depth_registration)" />
<arg name="sw_registered_processing" default="false" if="$(arg depth_registration)" />
<arg name="hw_registered_processing" default="false" unless="$(arg depth_registration)" />
<arg name="sw_registered_processing" default="true" unless="$(arg depth_registration)" />
<!-- Disable bond topics by default -->
<arg name="respawn" default="false" />
<!-- Worker threads for the nodelet manager -->
<arg name="num_worker_threads" default="4" />
<!-- Push down all topics/nodelets into "camera" namespace -->
<group ns="$(arg camera)">
<!-- Start nodelet manager -->
<arg name="manager" value="$(arg camera)_nodelet_manager" />
<arg name="debug" default="false" /> <!-- Run manager in GDB? -->
<include file="$(find rgbd_launch)/launch/includes/manager.launch.xml">
<arg name="name" value="$(arg manager)" />
<arg name="debug" value="$(arg debug)" />
<arg name="num_worker_threads" value="$(arg num_worker_threads)" />
</include>
<!-- Load driver -->
<include if="$(arg load_driver)"
file="$(find openni2_launch)/launch/includes/device.launch.xml">
<arg name="manager" value="$(arg manager)" />
<arg name="device_id" value="$(arg device_id)" />
<arg name="rgb_frame_id" value="$(arg rgb_frame_id)" />
<arg name="depth_frame_id" value="$(arg depth_frame_id)" />
<arg name="rgb_camera_info_url" value="$(arg rgb_camera_info_url)" />
<arg name="depth_camera_info_url" value="$(arg depth_camera_info_url)" />
<arg name="rgb" value="$(arg rgb)" />
<arg name="ir" value="$(arg ir)" />
<arg name="depth" value="$(arg depth)" />
<arg name="respawn" value="$(arg respawn)" />
<arg name="depth_registration" value="$(arg depth_registration)" />
<arg name="color_depth_synchronization" value="$(arg color_depth_synchronization)" />
<arg name="auto_exposure" value="$(arg auto_exposure)" />
<arg name="auto_white_balance" value="$(arg auto_white_balance)" />
</include>
<!-- Load standard constellation of processing nodelets -->
<include file="$(find rgbd_launch)/launch/includes/processing.launch.xml">
<arg name="manager" value="$(arg manager)" />
<arg name="rgb" value="$(arg rgb)" />
<arg name="ir" value="$(arg ir)" />
<arg name="depth" value="$(arg depth)" />
<arg name="respawn" value="$(arg respawn)" />
<arg name="rgb_processing" value="$(arg rgb_processing)" />
<arg name="debayer_processing" value="$(arg debayer_processing)" />
<arg name="ir_processing" value="$(arg ir_processing)" />
<arg name="depth_processing" value="$(arg depth_processing)" />
<arg name="depth_registered_processing" value="$(arg depth_registered_processing)" />
<arg name="disparity_processing" value="$(arg disparity_processing)" />
<arg name="disparity_registered_processing" value="$(arg disparity_registered_processing)" />
<arg name="hw_registered_processing" value="$(arg hw_registered_processing)" />
<arg name="sw_registered_processing" value="$(arg sw_registered_processing)" />
</include>
</group> <!-- camera -->
<!-- Load reasonable defaults for the relative pose between cameras -->
<include if="$(arg publish_tf)"
file="$(find rgbd_launch)/launch/kinect_frames.launch">
<arg name="camera" value="$(arg camera)" />
</include>
</launch>