-
Notifications
You must be signed in to change notification settings - Fork 6
/
Copy pathrealsense.launch
94 lines (94 loc) · 4.99 KB
/
realsense.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
<?xml version="1.0"?>
<launch>
<arg name="record" default="False"/>
<!--This guide tells us settings to start with:-->
<!--https://www.intel.com/content/dam/support/us/en/documents/emerging-technologies/intel-realsense-technology/BKMs_Tuning_RealSense_D4xx_Cam.pdf-->
<!--Valid resolutions on page 55:-->
<!--https://www.intel.com/content/dam/support/us/en/documents/emerging-technologies/intel-realsense-technology/Intel-RealSense-D400-Series-Datasheet.pdf-->
<!--S/N 1: 904412060717-->
<!--S/N 2: 912322061173-->
<arg name="serial_no_lower" value="904412060717"/>
<arg name="serial_no_upper" value="912322061173"/>
<arg name="depth_width" value="1280"/>
<arg name="depth_height" value="720"/>
<arg name="depth_fps" value="30"/>
<arg name="enable_color" value="True"/>
<arg name="enable_depth" value="True" if="$(eval record==True)"/>
<arg name="color_width" value="1920" if="$(eval record==True)"/>
<arg name="color_height" value="1080" if="$(eval record==True)"/>
<arg name="align_depth" value="True" if="$(eval record==True)"/>
<arg name="enable_depth" value="False" if="$(eval record==False)"/>
<arg name="color_width" value="848" if="$(eval record==False)"/>
<arg name="color_height" value="480" if="$(eval record==False)"/>
<arg name="align_depth" value="False" if="$(eval record==False)"/>
<!--Should be 30:-->
<arg name="color_fps" value="30"/>
<arg name="enable_pointcloud" value="false"/>
<arg name="enable_infra" value="false"/>
<!--<arg name="enable_sync" default="false"/>-->
<!--This seems like a good idea, but when this is done, nothing can connect for a while:-->
<arg name="initial_reset" value="false"/>
<include file="$(find realsense2_camera)/launch/rs_camera.launch">
<arg name="serial_no" value="$(arg serial_no_lower)"/>
<arg name="camera" value="lower_realsense"/>
<arg name="depth_width" value="$(arg depth_width)"/>
<arg name="depth_height" value="$(arg depth_height)"/>
<arg name="enable_depth" value="$(arg enable_depth)"/>
<arg name="depth_fps" value="$(arg depth_fps)"/>
<arg name="infra_width" value="$(arg depth_width)"/>
<arg name="infra_height" value="$(arg depth_height)"/>
<arg name="infra_fps" value="$(arg depth_fps)"/>
<arg name="color_width" value="$(arg color_width)"/>
<arg name="color_height" value="$(arg color_height)"/>
<arg name="enable_color" value="$(arg enable_color)"/>
<arg name="color_fps" value="$(arg color_fps)"/>
<arg name="align_depth" value="$(arg align_depth)"/>
<arg name="enable_pointcloud" value="$(arg enable_pointcloud)"/>
<arg name="enable_gyro" value="false"/>
<arg name="enable_accel" value="false"/>
<!--<arg name="enable_pose" value="false"/>-->
<arg name="enable_infra1" value="$(arg enable_infra)"/>
<arg name="enable_infra2" value="$(arg enable_infra)"/>
<arg name="initial_reset" value="$(arg initial_reset)"/>
</include>
<group ns="lower_realsense/color">
<node pkg="topic_tools" name="image_throttled" type="throttle" args="messages image_raw 15 image_throttled"/>
<node pkg="nodelet" type="nodelet" name="image_web" args="standalone image_proc/resize">
<param name="use_scale" type="bool" value="False"/>
<param name="width" type="int" value="480"/>
<param name="height" type="int" value="270"/>
<remap from="image" to="image_throttled"/>
<remap from="~image" to="image_web"/>
</node>
</group>
<include file="$(find realsense2_camera)/launch/rs_camera.launch">
<arg name="serial_no" value="$(arg serial_no_upper)"/>
<arg name="camera" value="upper_realsense"/>
<arg name="depth_width" value="$(arg depth_width)"/>
<arg name="depth_height" value="$(arg depth_height)"/>
<arg name="enable_depth" value="$(arg enable_depth)"/>
<arg name="depth_fps" value="$(arg depth_fps)"/>
<arg name="color_width" value="$(arg color_width)"/>
<arg name="color_height" value="$(arg color_height)"/>
<arg name="enable_color" value="$(arg enable_color)"/>
<arg name="color_fps" value="$(arg color_fps)"/>
<arg name="align_depth" value="$(arg align_depth)"/>
<arg name="enable_pointcloud" value="$(arg enable_pointcloud)"/>
<arg name="enable_gyro" value="false"/>
<arg name="enable_accel" value="false"/>
<!--<arg name="enable_pose" value="false"/>-->
<arg name="enable_infra1" value="$(arg enable_infra)"/>
<arg name="enable_infra2" value="$(arg enable_infra)"/>
<arg name="initial_reset" value="$(arg initial_reset)"/>
</include>
<group ns="upper_realsense/color">
<node pkg="topic_tools" name="image_throttled" type="throttle" args="messages image_raw 15 image_throttled"/>
<node pkg="nodelet" type="nodelet" name="image_web" args="standalone image_proc/resize">
<param name="use_scale" type="bool" value="False"/>
<param name="width" type="int" value="480"/>
<param name="height" type="int" value="270"/>
<remap from="image" to="image_throttled"/>
<remap from="~image" to="image_web"/>
</node>
</group>
</launch>