标准启动方法
//仿真导航
//需要在.bashrc文件中添加“export TURTLEBOT3_MODEL=burger”
$ roslaunch turtlebot3_gazebo turtlebot3_world.launch //搭建仿真环境
$ roslaunch turtlebot3_navigation turtlebot3_navigation.launch map_file:=$HOME/map.yaml //导航,需要提前存储地图数据(不加参数也可以,文件中设置了默认地图)
参考 “https://www.ncnynl.com/archives/201707/1791.html”
实现效果
如图:(两个命令行与启动的gazebo与rviz),通过使用rviz中的“2D Nav Goal”可以控制仿真环境中的机器人前往目标位置。(但由于move_base建立的成本地图没有设置原始点,需要让机器人移动一段时间进行地图间的对齐,也有可能对不齐)。
如图,节点图:
自己的启动方法
顺便把/map_server节点换成gmapping建图,就基本实现了SLAM功能。
$ roslaunch turtlebot3_gazebo turtlebot3_world.launch //搭建仿真环境
$ roslaunch turtlebot3_bringup turtlebot3_remote.launch //构建tf树
//以下三个launch文件是自己从turtlebot3_navigation.launch中提取的,创建在当前目录下即可。
$ roslaunch move_base.launch // 导航节点
$ roslaunch amcl.launch // 定位节点
$ roslaunch mapping.launch // 建图节点
// amcl.launch
<launch>
<node pkg="amcl" type="amcl" name="amcl">
<param name="min_particles" value="500"/>
<param name="max_particles" value="3000"/>
<param name="kld_err" value="0.02"/>
<param name="update_min_d" value="0.20"/>
<param name="update_min_a" value="0.20"/>
<param name="resample_interval" value="1"/>
<param name="transform_tolerance" value="0.5"/>
<param name="recovery_alpha_slow" value="0.00"/>
<param name="recovery_alpha_fast" value="0.00"/>
<param name="initial_pose_x" value="0"/>
<param name="initial_pose_y" value="0"/>
<param name="initial_pose_a" value="0"/>
<param name="gui_publish_rate" value="50.0"/>
<remap from="scan" to="scan"/>
<param name="laser_max_range" value="3.5"/>
<param name="laser_max_beams" value="180"/>
<param name="laser_z_hit" value="0.5"/>
<param name="laser_z_short" value="0.05"/>
<param name="laser_z_max" value="0.05"/>
<param name="laser_z_rand" value="0.5"/>
<param name="laser_sigma_hit" value="0.2"/>
<param name="laser_lambda_short" value="0.1"/>
<param name="laser_likelihood_max_dist" value="2.0"/>
<param name="laser_model_type" value="likelihood_field"/>
<param name="odom_model_type" value="diff"/>
<param name="odom_alpha1" value="0.1"/>
<param name="odom_alpha2" value="0.1"/>
<param name="odom_alpha3" value="0.1"/>
<param name="odom_alpha4" value="0.1"/>
<param name="odom_frame_id" value="odom"/>
<param name="base_frame_id" value="base_footprint"/>
</node>
</launch>
// mapping.launch
<launch>
<node pkg="gmapping" type="slam_gmapping" name="my_mapping" output="screen">
<param name="base_frame" value="base_footprint"/>
<param name="odom_frame" value="odom"/>
<param name="map_frame" value="map"/>
<param name="map_update_interval" value="2.0" />
<param name="maxUrange" value="3.0" />
<param name="sigma" value="0.05" />
<param name="kernelSize" value="1" />
<param name="lstep" value="0.05" />
<param name="astep" value="0.05" />
<param name="iterations" value="5" />
<param name="lsigma" value="0.075" />
<param name="ogain" value="3.0" />
<param name="lskip" value="0" />
<param name="minimumScore" value="50" />
<param name="srr" value="0.1" />
<param name="srt" value="0.2" />
<param name="str" value="0.1" />
<param name="stt" value="0.2" />
<param name="linearUpdate" value="1.0" />
<param name="angularUpdate" value="0.2" />
<param name="temporalUpdate" value="0.5" />
<param name="resampleThreshold" value="0.5" />
<param name="particles" value="100" />
<param name="xmin" value="-10.0" />
<param name="ymin" value="-10.0" />
<param name="xmax" value="10.0" />
<param name="ymax" value="10.0" />
<param name="delta" value="0.05" />
<param name="llsamplerange" value="0.01" />
<param name="llsamplestep" value="0.01" />
<param name="lasamplerange" value="0.005" />
<param name="lasamplestep" value="0.005" />
</node>
</launch>
// move_base.launch
<launch>
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<param name="base_local_planner" value="dwa_local_planner/DWAPlannerROS" />
<rosparam file="$(find turtlebot3_navigation)/param/costmap_common_params_burger.yaml" command="load" ns="global_costmap" />
<rosparam file="$(find turtlebot3_navigation)/param/costmap_common_params_burger.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find turtlebot3_navigation)/param/local_costmap_params.yaml" command="load" />
<rosparam file="$(find turtlebot3_navigation)/param/global_costmap_params.yaml" command="load" />
<rosparam file="$(find turtlebot3_navigation)/param/move_base_params.yaml" command="load" />
<rosparam file="$(find turtlebot3_navigation)/param/dwa_local_planner_params_burger.yaml" command="load" />
<remap from="cmd_vel" to="/cmd_vel"/>
<remap from="odom" to="odom"/>
</node>
</launch>
…
执行效果
打开rviz,把各种界面调出来:/map,tf,Path等,可以使用“2D Nav Goal”控制小车移动,并同时进行建图。