This repository was archived by the owner on Jul 26, 2024. It is now read-only.
-
Notifications
You must be signed in to change notification settings - Fork 237
Expand file tree
/
Copy pathslam_rtabmap.launch
More file actions
65 lines (53 loc) · 2.56 KB
/
slam_rtabmap.launch
File metadata and controls
65 lines (53 loc) · 2.56 KB
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
<!--
Copyright (c) Microsoft Corporation. All rights reserved.
Licensed under the MIT License.
-->
<launch>
<param name="robot_description"
command="xacro $(find azure_kinect_ros_driver)/urdf/azure_kinect_standalone.urdf.xacro" />
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
<node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />
<!-- Start the K4A sensor driver -->
<group ns="k4a" >
<!-- Spawn a nodelet manager -->
<node pkg="nodelet" type="nodelet" name="manager" args="manager" output="screen">
<param name="num_worker_threads" value="16" />
</node>
<!-- Spawn an image_proc/rectify nodelet to rectify the RGB image -->
<node pkg="nodelet" type="nodelet" name="rectify_rgb"
args="load image_proc/rectify manager --no-bond"
respawn="true">
<remap from="image_mono" to="rgb_to_depth/image_raw" />
<remap from="image_rect" to="rgb_to_depth/image_rect" />
</node>
<!-- Spawn an image_proc/rectify nodelet to rectify the depth image -->
<node pkg="nodelet" type="nodelet" name="rectify_depth"
args="load image_proc/rectify manager --no-bond"
respawn="true">
<remap from="image_mono" to="depth/image_raw" />
<remap from="image_rect" to="depth/image_rect" />
</node>
<node pkg="nodelet" type="nodelet" name="k4a_ros_bridge"
args="load Azure_Kinect_ROS_Driver/K4AROSBridgeNodelet manager --no-bond"
respawn="true">
<param name="depth_enabled" value="true" />
<param name="depth_mode" value="NFOV_UNBINNED" />
<param name="color_enabled" value="true" />
<param name="color_resolution" value="1536P" />
<param name="fps" value="30" />
<param name="point_cloud" value="false" />
<param name="rgb_point_cloud" value="false" />
<param name="required" value="true" />
<param name="imu_rate_target" value="100" />
</node>
</group>
<!-- Start rtabmap_ros node -->
<include file="$(find rtabmap_ros)/launch/rtabmap.launch" ns="rtabmap" >
<arg name="rgb_topic" value="/k4a/rgb_to_depth/image_rect" />
<arg name="depth_topic" value="/k4a/depth/image_rect" />
<arg name="camera_info_topic" value="/k4a/depth/camera_info" />
<arg name="approx_sync" value="true" />
<arg name="frame_id" value="camera_base" />
<arg name="args" value="--delete_db_on_start --Odom/ResetCountdown 2" />
</include>
</launch>