wpb_home/wpb_home_tutorials/launch/capture_image.launch
2019-08-05 11:08:32 +08:00

112 lines
6.0 KiB
XML

<launch>
<!-- wpb_home core-->
<node pkg="wpb_home_bringup" type="wpb_home_core" name="wpb_home_core" output="screen">
<param name="serial_port" type="string" value="/dev/ftdi"/>
<rosparam file="$(find wpb_home_bringup)/config/wpb_home.yaml" command="load" />
</node>
<!-- js node -->
<node respawn="true" pkg="joy" type="joy_node" name="wpb_home_joy" >
<param name="dev" type="string" value="/dev/input/js0" />
<param name="deadzone" value="0.12" />
</node>
<!-- axes velcmd -->
<param name="axis_linear" value="1" type="int"/>
<param name="axis_angular" value="0" type="int"/>
<param name="scale_linear" value="1" type="double"/>
<param name="scale_angular" value="1" type="double"/>
<node pkg="wpb_home_bringup" type="wpb_home_js_vel" name="teleop"/>
<!-- capture image -->
<node pkg="wpb_home_tutorials" type="wpb_home_capture_image" name="wpb_home_capture_image" output="screen"/>
<!--************************ kinect ************************-->
<arg name="base_name" default="kinect2"/>
<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="cpu"/>
<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="worker_threads" default="4"/>
<arg name="machine" default="localhost"/>
<arg name="nodelet_manager" default="$(arg base_name)"/>
<arg name="start_manager" default="true"/>
<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)"/>
<node pkg="nodelet" type="nodelet" name="$(arg nodelet_manager)" args="manager"
if="$(arg start_manager)" machine="$(arg machine)" />
<!-- 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 nodelet_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="worker_threads" type="int" value="$(arg 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="worker_threads" type="int" value="$(arg worker_threads)"/>
</node>
<!--************************ end ************************-->
</launch>