-
Notifications
You must be signed in to change notification settings - Fork 89
/
Copy pathd435i_basic.launch
59 lines (47 loc) · 2.71 KB
/
d435i_basic.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
<launch>
<arg name="rs_initial_preset" default="$(find stretch_core)/config/HighAccuracyPreset.json" doc="filepath to json defining a visual preset for the depth image" />
<arg name="rs_initial_reset" default="true" doc="whether to reset camera before streaming, useful if the camera got into a bad state in the last session" />
<!-- REDUCE RATE AND USE NUC TIME -->
<node name="d435i_accel_correction" pkg="stretch_core" type="d435i_accel_correction" output="screen" />
<!-- REALSENSE D435i -->
<include file="$(find realsense2_camera)/launch/rs_camera.launch">
<arg name="enable_confidence" value="false"/>
<arg name="enable_infra1" value="false"/>
<arg name="enable_infra2" value="false"/>
<arg name="enable_infra" value="false"/>
<arg name="enable_color" value="true"/>
<arg name="enable_depth" value="true"/>
<arg name="enable_accel" value="true"/>
<arg name="enable_gyro" value="true"/>
<arg name="color_fps" value="15"/>
<arg name="depth_fps" value="15"/>
<arg name="accel_fps" value="63"/>
<arg name="gyro_fps" value="200"/>
<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)"/>
<!-- publish depth streams aligned to other streams -->
<arg name="align_depth" value="true"/>
<!-- publish an RGBD point cloud -->
<arg name="filters" value="pointcloud"/>
<arg name="enable_pointcloud" value="true"/>
<!-- enable_sync: gathers closest frames of different sensors,
infra red, color and depth, to be sent with the same
timetag. This happens automatically when such filters as
pointcloud are enabled. -->
<arg name="enable_sync" value="true"/>
<!-- Set to true in order to make use of the full field of view of
the depth image instead of being restricted to the field of
view associated with the narrower RGB camera. Note that
points out of the RGB camera's field of view will have their
colors set to 0,0,0. -->
<arg name="allow_no_texture_points" value="true"/>
<!-- initial_reset: On occasions the device was not closed
properly and due to firmware issues needs to reset. If set to
true, the device will reset prior to usage. -->
<arg name="initial_reset" value="$(arg rs_initial_reset)"/>
<!-- configure the depth image to the high accuracy visual preset -->
<arg name="json_file_path" value="$(arg rs_initial_preset)" />
</include>
</launch>