turtlebot3_cleaner/clean_robot/launch/auto_slam.launch

45 lines
2.0 KiB
XML

<?xml version="1.0"?>
<launch>
<!-- <arg name="slam_methods" default="karto" doc="slam type [gmapping, cartographer, hector, karto, frontier_exploration]"/> -->
<arg name="model" value="burger" doc="model type [burger, waffle, waffle_pi]"/>
<arg name="configuration_basename" default="turtlebot3_lds_2d.lua"/>
<arg name="open_rviz" default="true"/>
<include file="$(find turtlebot3_bringup)/launch/turtlebot3_remote.launch">
<arg name="model" value="$(arg model)" />
</include>
<!-- 启动仿真环境 -->
<include file="$(find clean_robot)/launch/gazebo.launch"/>
<!-- SLAM: Gmapping, Cartographer, Hector, Karto, Frontier_exploration, RTAB-Map -->
<include file="$(find turtlebot3_slam)/launch/turtlebot3_karto.launch">
<arg name="model" value="$(arg model)"/>
<arg name="configuration_basename" value="$(arg configuration_basename)"/>
</include>
<!-- 启动 rviz 的标签 -->
<group if="$(arg open_rviz)">
<node pkg="rviz" type="rviz" name="rviz" required="true" args="-d $(find clean_robot)/rviz/turtlebot3_karto.rviz"/>
</group>
<!-- 通过导航来实现自动建图 -->
<include file="$(find clean_robot)/launch/move_base.launch">
<arg name="model" value="$(arg model)" />
</include>
<!-- 自动探索 -->
<node pkg="explore_lite" type="explore" respawn="false" name="explore" output="screen">
<param name="robot_base_frame" value="base_link"/>
<param name="costmap_topic" value="map"/>
<param name="costmap_updates_topic" value="map_updates"/>
<param name="visualize" value="true"/>
<param name="planner_frequency" value="0.33"/>
<param name="progress_timeout" value="50.0"/>
<param name="potential_scale" value="3.0"/>
<param name="orientation_scale" value="0.0"/>
<param name="gain_scale" value="1.0"/>
<param name="transform_tolerance" value="0.3"/>
<param name="min_frontier_size" value="0.6"/>
</node>
<!-- 键盘操作 -->
<!-- <node pkg="turtlebot3_teleop" type="turtlebot3_teleop_key" name="turtlebot3_teleop_key" launch-prefix="xterm -e" output="screen"/> -->
</launch>