-
Notifications
You must be signed in to change notification settings - Fork 545
/
data_recorder.launch
76 lines (65 loc) · 4.47 KB
/
data_recorder.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
<launch>
<!-- arguments -->
<arg name="subscribe_odometry" default="false"/>
<arg name="subscribe_depth" default="true"/>
<arg name="subscribe_stereo" default="false"/>
<arg name="subscribe_scan" default="false"/>
<arg name="stereo_approx_sync" default="false"/>
<arg name="frame_id" default="camera_link"/>
<arg name="odom_frame_id" default=""/> <!-- use topic when not set, otherwise use TF if set -->
<arg name="output_path" default="output.db"/>
<arg name="record_in_RAM" default="false"/>
<arg name="queue_size" default="10"/>
<arg name="max_rate" default="0"/> <!-- Record as fast as possible -->
<arg name="rgb_topic" default="camera/rgb/image_rect_color"/>
<arg name="rgb_info_topic" default="camera/rgb/camera_info"/>
<arg name="depth_topic" default="camera/depth_registered/image_raw"/>
<arg name="left_topic" default="camera/left/image_rect_color"/>
<arg name="left_info_topic" default="camera/left/camera_info"/>
<arg name="right_topic" default="camera/right/image_rect"/>
<arg name="right_info_topic" default="camera/right/camera_info"/>
<arg name="odom_topic" default="odom"/>
<arg name="scan_topic" default="scan"/>
<arg name="rgb_image_transport" default="raw"/>
<arg name="depth_image_transport" default="raw"/>
<node name="data_recorder" pkg="rtabmap_ros" type="rtabmap" output="screen" args="--delete_db_on_start">
<!-- Disable any processing -->
<param name="Mem/RehearsalSimilarity" type="string" value="1.0"/> <!-- deactivate rehearsal -->
<param name="Kp/MaxFeatures" type="string" value="-1"/> <!-- deactivate keypoints extraction -->
<param name="Rtabmap/MaxRetrieved" type="string" value="0"/> <!-- deactivate global retrieval -->
<param name="RGBD/MaxLocalRetrieved" type="string" value="0"/> <!-- deactivate local retrieval -->
<param name="Mem/MapLabelsAdded" type="string" value="false"/> <!-- don't create map labels -->
<param name="Rtabmap/MemoryThr" type="string" value="2"/> <!-- keep the WM empty -->
<param name="Mem/STMSize" type="string" value="1"/> <!-- STM=1 -->
<param name="publish_tf" type="bool" value="false"/> <!-- don't publish TF -->
<param name="RGBD/ProximityBySpace" type="string" value="false"/>
<param name="RGBD/LinearUpdate" type="string" value="0"/>
<param name="RGBD/AngularUpdate" type="string" value="0"/>
<param unless="$(arg subscribe_odometry)" name="RGBD/Enabled" type="string" value="false"/>
<param name="Rtabmap/DetectionRate" type="string" value="$(arg max_rate)"/>
<param name="DbSqlite3/InMemory" type="string" value="$(arg record_in_RAM)"/>
<param name="database_path" type="string" value="$(arg output_path)"/>
<param name="frame_id" type="string" value="$(arg frame_id)"/>
<param name="subscribe_depth" type="bool" value="$(arg subscribe_depth)"/>
<param name="subscribe_scan" type="bool" value="$(arg subscribe_scan)"/>
<param name="subscribe_stereo" type="bool" value="$(arg subscribe_stereo)"/>
<param name="queue_size" type="int" value="$(arg queue_size)"/>
<param name="stereo_approx_sync" type="bool" value="$(arg stereo_approx_sync)"/>
<!-- Hack to use a fake odom_frame_id=frame_id if subscribe_odometry = false -->
<param if="$(arg subscribe_odometry)" name="odom_frame_id" type="string" value="$(arg odom_frame_id)"/>
<param unless="$(arg subscribe_odometry)" name="odom_frame_id" type="string" value="$(arg frame_id)"/>
<param name="rgb/image_transport" type="string" value="$(arg rgb_image_transport)"/>
<param name="depth/image_transport" type="string" value="$(arg depth_image_transport)"/>
<param name="left/image_transport" type="string" value="$(arg rgb_image_transport)"/>
<param name="right/image_transport" type="string" value="$(arg rgb_image_transport)"/>
<remap from="rgb/image" to="$(arg rgb_topic)"/>
<remap from="rgb/camera_info" to="$(arg rgb_info_topic)"/>
<remap from="depth/image" to="$(arg depth_topic)"/>
<remap from="left/image_rect" to="$(arg left_topic)"/>
<remap from="left/camera_info" to="$(arg left_info_topic)"/>
<remap from="right/image_rect" to="$(arg right_topic)"/>
<remap from="right/camera_info" to="$(arg right_info_topic)"/>
<remap from="scan" to="$(arg scan_topic)"/>
<remap from="odom" to="$(arg odom_topic)"/>
</node>
</launch>