-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
修改kinect2.launch至此功能包下,并修改了调用此文件的kinect2.launch.xml。添加说明文档和mark图片pdf。
- Loading branch information
WLwind
committed
May 15, 2019
1 parent
d326446
commit 0a07ed0
Showing
7 changed files
with
128 additions
and
40 deletions.
There are no files selected for viewing
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
127 changes: 127 additions & 0 deletions
127
turtlebot2i_bringup/launch/includes/3dsensor/kinect2.launch
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,127 @@ | ||
<launch> | ||
|
||
<arg name="base_name" default="camera"/> | ||
<arg name="sensor" default=""/> | ||
<arg name="publish_tf" default="false"/> | ||
<arg name="base_name_tf" default="$(arg base_name)"/> | ||
<arg name="fps_limit" default="-1.0"/> | ||
<arg name="calib_path" default="$(find kinect2_bridge)/data/"/> | ||
<arg name="use_png" default="false"/> | ||
<arg name="jpeg_quality" default="90"/> | ||
<arg name="png_level" default="1"/> | ||
<arg name="depth_method" default="opengl"/> | ||
<arg name="depth_device" default="-1"/> | ||
<arg name="reg_method" default="cpu"/> | ||
<arg name="reg_device" default="-1"/> | ||
<arg name="max_depth" default="12.0"/> | ||
<arg name="min_depth" default="0.1"/> | ||
<arg name="queue_size" default="5"/> | ||
<arg name="bilateral_filter" default="true"/> | ||
<arg name="edge_aware_filter" default="true"/> | ||
<arg name="num_worker_threads" default="4"/> | ||
<arg name="machine" default="localhost"/> | ||
<arg name="nodelet_manager" default="$(arg base_name)/$(arg base_name)_nodelet_manager"/> | ||
<arg name="start_manager" default="false"/> | ||
<arg name="use_machine" default="true"/> | ||
<arg name="respawn" default="true"/> | ||
<arg name="use_nodelet" default="true"/> | ||
<arg name="output" default="screen"/> | ||
|
||
<machine name="localhost" address="localhost" if="$(arg use_machine)"/> | ||
|
||
|
||
<group ns="$(arg base_name)"> | ||
<!-- Start nodelet manager --> | ||
<arg name="manager" value="$(arg base_name)_nodelet_manager" /> | ||
<arg name="debug" default="false" /> <!-- Run manager in GDB? --> | ||
<include file="$(find rgbd_launch)/launch/includes/manager.launch.xml"> | ||
<arg name="name" value="$(arg manager)" /> | ||
<arg name="debug" value="$(arg debug)" /> | ||
<arg name="num_worker_threads" value="$(arg num_worker_threads)" /> | ||
</include> | ||
|
||
<!--node pkg="nodelet" type="nodelet" name="$(arg nodelet_manager)" args="manager" | ||
if="$(arg start_manager)" machine="$(arg machine)" output="screen"/--> | ||
|
||
|
||
<!-- Nodelet version of kinect2_bridge --> | ||
<node pkg="nodelet" type="nodelet" name="$(arg base_name)_bridge" machine="$(arg machine)" | ||
args="load kinect2_bridge/kinect2_bridge_nodelet $(arg manager)" | ||
respawn="$(arg respawn)" output="$(arg output)" if="$(arg use_nodelet)"> | ||
<param name="base_name" type="str" value="$(arg base_name)"/> | ||
<param name="sensor" type="str" value="$(arg sensor)"/> | ||
<param name="publish_tf" type="bool" value="$(arg publish_tf)"/> | ||
<param name="base_name_tf" type="str" value="$(arg base_name_tf)"/> | ||
<param name="fps_limit" type="double" value="$(arg fps_limit)"/> | ||
<param name="calib_path" type="str" value="$(arg calib_path)"/> | ||
<param name="use_png" type="bool" value="$(arg use_png)"/> | ||
<param name="jpeg_quality" type="int" value="$(arg jpeg_quality)"/> | ||
<param name="png_level" type="int" value="$(arg png_level)"/> | ||
<param name="depth_method" type="str" value="$(arg depth_method)"/> | ||
<param name="depth_device" type="int" value="$(arg depth_device)"/> | ||
<param name="reg_method" type="str" value="$(arg reg_method)"/> | ||
<param name="reg_device" type="int" value="$(arg reg_device)"/> | ||
<param name="max_depth" type="double" value="$(arg max_depth)"/> | ||
<param name="min_depth" type="double" value="$(arg min_depth)"/> | ||
<param name="queue_size" type="int" value="$(arg queue_size)"/> | ||
<param name="bilateral_filter" type="bool" value="$(arg bilateral_filter)"/> | ||
<param name="edge_aware_filter" type="bool" value="$(arg edge_aware_filter)"/> | ||
<param name="num_worker_threads" type="int" value="$(arg num_worker_threads)"/> | ||
</node> | ||
|
||
|
||
<!-- Node version of kinect2_bridge --> | ||
<node pkg="kinect2_bridge" type="kinect2_bridge" name="$(arg base_name)_bridge" machine="$(arg machine)" | ||
respawn="$(arg respawn)" output="$(arg output)" unless="$(arg use_nodelet)"> | ||
<param name="base_name" type="str" value="$(arg base_name)"/> | ||
<param name="sensor" type="str" value="$(arg sensor)"/> | ||
<param name="publish_tf" type="bool" value="$(arg publish_tf)"/> | ||
<param name="base_name_tf" type="str" value="$(arg base_name_tf)"/> | ||
<param name="fps_limit" type="double" value="$(arg fps_limit)"/> | ||
<param name="calib_path" type="str" value="$(arg calib_path)"/> | ||
<param name="use_png" type="bool" value="$(arg use_png)"/> | ||
<param name="jpeg_quality" type="int" value="$(arg jpeg_quality)"/> | ||
<param name="png_level" type="int" value="$(arg png_level)"/> | ||
<param name="depth_method" type="str" value="$(arg depth_method)"/> | ||
<param name="depth_device" type="int" value="$(arg depth_device)"/> | ||
<param name="reg_method" type="str" value="$(arg reg_method)"/> | ||
<param name="reg_device" type="int" value="$(arg reg_device)"/> | ||
<param name="max_depth" type="double" value="$(arg max_depth)"/> | ||
<param name="min_depth" type="double" value="$(arg min_depth)"/> | ||
<param name="queue_size" type="int" value="$(arg queue_size)"/> | ||
<param name="bilateral_filter" type="bool" value="$(arg bilateral_filter)"/> | ||
<param name="edge_aware_filter" type="bool" value="$(arg edge_aware_filter)"/> | ||
<param name="num_worker_threads" type="int" value="$(arg num_worker_threads)"/> | ||
</node> | ||
|
||
<!-- sd point cloud (512 x 424) --> | ||
<node pkg="nodelet" type="nodelet" name="$(arg base_name)_points_xyzrgb_sd" machine="$(arg machine)" | ||
args="load depth_image_proc/point_cloud_xyzrgb $(arg manager)" respawn="$(arg respawn)"> | ||
<remap from="rgb/camera_info" to="$(arg base_name)/sd/camera_info"/> | ||
<remap from="rgb/image_rect_color" to="$(arg base_name)/sd/image_color_rect"/> | ||
<remap from="depth_registered/image_rect" to="$(arg base_name)/sd/image_depth_rect"/> | ||
<remap from="depth_registered/points" to="$(arg base_name)/sd/points"/> | ||
<param name="queue_size" type="int" value="$(arg queue_size)"/> | ||
</node> | ||
|
||
<!-- qhd point cloud (960 x 540) --> | ||
<node pkg="nodelet" type="nodelet" name="$(arg base_name)_points_xyzrgb_qhd" machine="$(arg machine)" | ||
args="load depth_image_proc/point_cloud_xyzrgb $(arg manager)" respawn="$(arg respawn)"> | ||
<remap from="rgb/camera_info" to="$(arg base_name)/qhd/camera_info"/> | ||
<remap from="rgb/image_rect_color" to="$(arg base_name)/qhd/image_color_rect"/> | ||
<remap from="depth_registered/image_rect" to="$(arg base_name)/qhd/image_depth_rect"/> | ||
<remap from="depth_registered/points" to="$(arg base_name)/qhd/points"/> | ||
<param name="queue_size" type="int" value="$(arg queue_size)"/> | ||
</node> | ||
|
||
<!-- hd point cloud (1920 x 1080) --> | ||
<node pkg="nodelet" type="nodelet" name="$(arg base_name)_points_xyzrgb_hd" machine="$(arg machine)" | ||
args="load depth_image_proc/point_cloud_xyzrgb $(arg manager)" respawn="$(arg respawn)"> | ||
<remap from="rgb/camera_info" to="$(arg base_name)/hd/camera_info"/> | ||
<remap from="rgb/image_rect_color" to="$(arg base_name)/hd/image_color_rect"/> | ||
<remap from="depth_registered/image_rect" to="$(arg base_name)/hd/image_depth_rect"/> | ||
<remap from="depth_registered/points" to="$(arg base_name)/hd/points"/> | ||
<param name="queue_size" type="int" value="$(arg queue_size)"/> | ||
</node> | ||
</group> | ||
</launch> |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters