wpb_home/wpb_home_tutorials/launch/3d_slam.launch
2021-04-09 08:09:41 +08:00

93 lines
4.5 KiB
XML

<launch>
<arg name="model" default="$(find wpb_home_bringup)/urdf/wpb_home.urdf"/>
<arg name="gui" default="false" />
<arg name="rvizconfig" default="$(find wpb_home_tutorials)/rviz/3d_slam.rviz" />
<param name="robot_description" command="$(find xacro)/xacro $(arg model)" />
<param name="use_gui" value="$(arg gui)"/>
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher">
<rosparam file="$(find wpb_home_bringup)/config/wpb_home.yaml" command="load" />
</node>
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"/>
<node name="rviz" pkg="rviz" type="rviz" args="-d $(arg rvizconfig)" required="true" />
<!--- Run Kinect -->
<include file="$(find kinect2_bridge)/launch/kinect2_bridge.launch"/>
<!--- Run Rplidar -->
<node pkg="rplidar_ros" type="rplidarNode" name="rplidar" output="screen">
<param name="serial_port" type="string" value="/dev/rplidar"/>
<param name="serial_baudrate" type="int" value="115200"/>
<param name="frame_id" type="string" value="laser"/>
<param name="inverted" type="bool" value="false"/>
<param name="angle_compensate" type="bool" value="true"/>
<remap from="scan" to="scan_raw"/>
</node>
<!-- Run lidar filter -->
<node pkg="wpb_home_bringup" type="wpb_home_lidar_filter" name="wpb_home_lidar_filter">
<param name="pub_topic" value="/scan"/>
</node>
<!-- 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>
<node pkg="gmapping" type="slam_gmapping" name="slam_gmapping">
<param name="base_frame" value="base_footprint"/>
</node>
<!-- RTAB-Map -->
<group ns="rtabmap">
<node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="--delete_db_on_start">
<param name="subscribe_depth" type="bool" value="true"/>
<param name="frame_id" type="string" value="base_footprint"/>
<param name="subscribe_scan" type="bool" value="true"/>
<param name="cloud_decimation" value="2"/>
<param name="cloud_max_depth" value="5.0"/>
<param name="cloud_voxel_size" value="0.01"/>
<param name="map_cleanup" type="bool" value="false"/>
<remap from="rgb/image" to="/kinect2/sd/image_color_rect"/>
<remap from="depth/image" to="/kinect2/sd/image_depth_rect"/>
<remap from="rgb/camera_info" to="/kinect2/sd/camera_info"/>
<remap from="scan" to="/scan"/>
<remap from="odom" to="/odom"/>
<param name="approx_sync" type="bool" value="true"/>
<param name="Reg/Strategy" type="string" value="1"/> <!-- 0=Visual, 1=ICP, 2=Visual+ICP -->
<param name="Vis/MaxDepth" type="string" value="8.0"/> <!-- 3D visual words maximum depth 0=infinity -->
<param name="Vis/InlierDistance" type="string" value="0.1"/> <!-- 3D visual words correspondence distance -->
<param name="Optimizer/Slam2D" type="string" value="true"/>
<param name="Reg/Force3DoF" type="string" value="true"/>
<param name="queue_size" value="10"/>
<param name="publish_tf" type="bool" value="false"/>
</node>
</group>
<node pkg="nodelet" type="nodelet" name="points_xyzrgb" args="load rtabmap_ros/point_cloud_xyzrgb standalone_nodelet">
<remap from="rgb/image" to="data_odom_sync/image"/>
<remap from="depth/image" to="data_odom_sync/depth"/>
<remap from="rgb/camera_info" to="data_odom_sync/camera_info"/>
<remap from="cloud" to="voxel_cloud" />
<param name="voxel_size" type="double" value="0.01"/>
</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"/>
</launch>