/
rs_d400_and_t265.launch
50 lines (48 loc) · 2.82 KB
/
rs_d400_and_t265.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
<launch>
<arg name="device_type_camera1" default="t265"/>
<arg name="device_type_camera2" default="d4.5"/> <!-- Note: using regular expression. match D435, D435i, D415... -->
<arg name="serial_no_camera1" default=""/>
<arg name="serial_no_camera2" default=""/>
<arg name="camera1" default="t265"/>
<arg name="camera2" default="d400"/>
<arg name="tf_prefix_camera1" default="$(arg camera1)"/>
<arg name="tf_prefix_camera2" default="$(arg camera2)"/>
<arg name="initial_reset" default="false"/>
<arg name="enable_fisheye" default="false"/>
<arg name="color_width" default="640"/>
<arg name="color_height" default="480"/>
<arg name="depth_width" default="640"/>
<arg name="depth_height" default="480"/>
<arg name="clip_distance" default="-2"/>
<arg name="topic_odom_in" default="odom_in"/>
<arg name="calib_odom_file" default=""/>
<group ns="$(arg camera1)">
<include file="$(find realsense2_camera)/launch/includes/nodelet.launch.xml">
<arg name="device_type" value="$(arg device_type_camera1)"/>
<arg name="serial_no" value="$(arg serial_no_camera1)"/>
<arg name="tf_prefix" value="$(arg tf_prefix_camera1)"/>
<arg name="initial_reset" value="$(arg initial_reset)"/>
<arg name="enable_fisheye1" value="$(arg enable_fisheye)"/>
<arg name="enable_fisheye2" value="$(arg enable_fisheye)"/>
<arg name="topic_odom_in" value="$(arg topic_odom_in)"/>
<arg name="calib_odom_file" value="$(arg calib_odom_file)"/>
<arg name="enable_pose" value="true"/>
</include>
</group>
<group ns="$(arg camera2)">
<include file="$(find realsense2_camera)/launch/includes/nodelet.launch.xml">
<arg name="device_type" value="$(arg device_type_camera2)"/>
<arg name="serial_no" value="$(arg serial_no_camera2)"/>
<arg name="tf_prefix" value="$(arg tf_prefix_camera2)"/>
<arg name="initial_reset" value="$(arg initial_reset)"/>
<arg name="align_depth" value="true"/>
<arg name="filters" value="pointcloud"/>
<arg name="color_width" value="$(arg color_width)"/>
<arg name="color_height" value="$(arg color_height)"/>
<arg name="depth_width" value="$(arg depth_width)"/>
<arg name="depth_height" value="$(arg depth_height)"/>
<arg name="clip_distance" value="$(arg clip_distance)"/>
</include>
</group>
<node pkg="tf" type="static_transform_publisher" name="t265_to_d400" args="0 0 0 0 0 0 /$(arg tf_prefix_camera1)_link /$(arg tf_prefix_camera2)_link 100"/>
</launch>