Skip to content

Commit

Permalink
Use nodelet in rtabmap_slam.launch (#11)
Browse files Browse the repository at this point in the history
* Use nodelet for slam_rtabmap.launch

* Create pull_request_template.md
  • Loading branch information
Stuart Alldritt committed Jun 21, 2019
1 parent 24b5d5b commit d66fb22
Showing 1 changed file with 13 additions and 12 deletions.
25 changes: 13 additions & 12 deletions launch/slam_rtabmap.launch
Original file line number Diff line number Diff line change
@@ -1,18 +1,6 @@
<launch>
<!-- Start the K4A sensor driver -->
<group ns="k4a" >

<!-- TODO: move into a nodelet and combine with image_proc nodelet -->
<include file="$(find azure_kinect_ros_driver)/launch/driver.launch" >
<arg name="depth_enabled" value="true" />
<arg name="depth_mode" value="NFOV_UNBINNED" />
<arg name="color_enabled" value="true" />
<arg name="color_resolution" value="1536P" />
<arg name="fps" value="30" />
<arg name="point_cloud" value="false" />
<arg name="rgb_point_cloud" value="false" />
<arg name="required" value="true" />
</include>

<!-- Spawn a nodelet manager -->
<node pkg="nodelet" type="nodelet" name="manager" args="manager" output="screen">
Expand All @@ -34,6 +22,19 @@
<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="720P" />
<param name="fps" value="15" />
<param name="point_cloud" value="false" />
<param name="rgb_point_cloud" value="false" />
<param name="required" value="true" />
</node>
</group>

<!-- Start rtabmap_ros node -->
Expand Down

0 comments on commit d66fb22

Please sign in to comment.