|
1 | 1 | <launch> |
2 | 2 | <!-- Start the K4A sensor driver --> |
3 | 3 | <group ns="k4a" > |
4 | | - |
5 | | - <!-- TODO: move into a nodelet and combine with image_proc nodelet --> |
6 | | - <include file="$(find azure_kinect_ros_driver)/launch/driver.launch" > |
7 | | - <arg name="depth_enabled" value="true" /> |
8 | | - <arg name="depth_mode" value="NFOV_UNBINNED" /> |
9 | | - <arg name="color_enabled" value="true" /> |
10 | | - <arg name="color_resolution" value="1536P" /> |
11 | | - <arg name="fps" value="30" /> |
12 | | - <arg name="point_cloud" value="false" /> |
13 | | - <arg name="rgb_point_cloud" value="false" /> |
14 | | - <arg name="required" value="true" /> |
15 | | - </include> |
16 | 4 |
|
17 | 5 | <!-- Spawn a nodelet manager --> |
18 | 6 | <node pkg="nodelet" type="nodelet" name="manager" args="manager" output="screen"> |
|
34 | 22 | <remap from="image_mono" to="depth/image_raw" /> |
35 | 23 | <remap from="image_rect" to="depth/image_rect" /> |
36 | 24 | </node> |
| 25 | + |
| 26 | + <node pkg="nodelet" type="nodelet" name="k4a_ros_bridge" |
| 27 | + args="load Azure_Kinect_ROS_Driver/K4AROSBridgeNodelet manager --no-bond" |
| 28 | + respawn="true"> |
| 29 | + <param name="depth_enabled" value="true" /> |
| 30 | + <param name="depth_mode" value="NFOV_UNBINNED" /> |
| 31 | + <param name="color_enabled" value="true" /> |
| 32 | + <param name="color_resolution" value="720P" /> |
| 33 | + <param name="fps" value="15" /> |
| 34 | + <param name="point_cloud" value="false" /> |
| 35 | + <param name="rgb_point_cloud" value="false" /> |
| 36 | + <param name="required" value="true" /> |
| 37 | + </node> |
37 | 38 | </group> |
38 | 39 |
|
39 | 40 | <!-- Start rtabmap_ros node --> |
|
0 commit comments