< >
Home » ROS机器人Diego制作 » ROS机器人Diego制作22-基于EAI F4激光雷达数据进行定位amcl

ROS机器人Diego制作22-基于EAI F4激光雷达数据进行定位amcl

ROS机器人Diego制作22-基于EAI F4激光雷达数据进行定位amcl

说明:

  • 介绍利用F4激光雷达通过AMCL导航
  • 在上两篇博文中我们讲到了利用gmapping和hector生成室内地图
  • 本文将阐述如何利用激光雷达数据,在已产生的地图上进行定位。

生成地图

  • 创建maps文件夹,并赋予其777的权限,既可以让map_server在此文件夹中生成地图文件

  • 图示:
    请输入图片描述

  • 打开终端cd进入maps目录,并执行地图生成命令:

cd ~/catkin_ws/src/diego_nav/maps/
rosrun map_server map_saver -f f4_gmapping
  • 执行完后,在maps目录下将生成两个地图文件

  • 图示:
    请输入图片描述

  • 地图效果如下:
    请输入图片描述

配置定位的launch文件

  • 创建diego_run_gmapping_amcl_flashgo.launch文件
  • 代码如下:
<launch>
  <master auto="start"/>

  <include file="$(find flashgo)/launch/lidar.launch" />

  <node name="arduino" pkg="ros_arduino_python" type="arduino_node.py" output="screen">
      <rosparam file="$(find ros_arduino_python)/config/my_arduino_params.yaml" command="load" />
  </node>  

  <node pkg="tf" type="static_transform_publisher" name="base_frame_2_laser_link" args="0.0 0.0 0.2 3.14 3.14 0 /base_link /laser 40"/>   

  <!-- Map server -->
  <node name="map_server" pkg="map_server" type="map_server" args="$(find diego_nav)/maps/f4_gmapping_whole1.yaml" /> 

  <!-- amcl node -->
  <node pkg="amcl" type="amcl" name="amcl" output="screen">
  <remap from="scan" to="scan"/>
  <!-- Publish scans from best pose at a max of 10 Hz -->
  <param name="initial_pose_x" value="0.0"/>
  <param name="initial_pose_y" value="0.0"/>
  <param name="initial_pose_a" value="0.0"/>
  <param name="use_map_topic" value="true"/>
  <param name="odom_model_type" value="diff"/>
  <param name="odom_alpha5" value="0.1"/>
  <param name="transform_tolerance" value="0.5" />
  <param name="gui_publish_rate" value="10.0"/>
  <param name="laser_max_beams" value="300"/>
  <param name="min_particles" value="500"/>
  <param name="max_particles" value="5000"/>
  <param name="kld_err" value="0.1"/>
  <param name="kld_z" value="0.99"/>
  <param name="odom_alpha1" value="0.1"/>
  <param name="odom_alpha2" value="0.1"/>
  <!-- translation std dev, m -->
  <param name="odom_alpha3" value="0.1"/>
  <param name="odom_alpha4" value="0.1"/>
  <param name="laser_z_hit" value="0.9"/>
  <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_lambda_short" value="0.1"/>
  <param name="laser_model_type" value="likelihood_field"/>
  <!-- <param name="laser_model_type" value="beam"/> -->
  <param name="laser_min_range" value="1"/>
  <param name="laser_max_range" value="8"/>
  <param name="laser_likelihood_max_dist" value="2.0"/>
  <param name="update_min_d" value="0.2"/>
  <param name="update_min_a" value="0.5"/>
  <param name="resample_interval" value="1"/>
  <param name="transform_tolerance" value="0.1"/>
  <param name="recovery_alpha_slow" value="0.0"/>
  <param name="recovery_alpha_fast" value="0.0"/>


  </node>

</launch>
  • 这里需要强调的一点是必须配置机器人的初始位置点 ,机器人随便放一个位置,amcl并不会定位到,需要指定初始位置,地图的原点是用gmapping/hector构建地图时候的起始点,我们在这里就把机器人放在起始的位置,所以初始位置的值都设定为0.0
<param name="initial_pose_x" value="0.0"/>
 <param name="initial_pose_y" value="0.0"/>

启动launch文件

  • 新终端,执行:
roslaunch diego_nav diego_run_gmapping_amcl_flashgo.launch
  • 打开新的终端,启动键盘控制节点:
rosrun teleop_twist_keyboard teleop_twist_keyboard.py
  • 这时我们可以用键盘控制机器人动起来,并打开rviz查看定位情况
rosrun  rviz rviz
  • 图示:
    请输入图片描述
  • 这张图中我们可以看到一堆红色的箭头暨蒙特卡洛定位算法所产生的粒子分布,其中箭头方向是机器人运动的方向

  • 图示:
    请输入图片描述

  • 这张图中可以看粒子比上张图更加聚合,从实际观察来看聚合度高的情况下定位效果更加。

纠错,疑问,交流: 请进入讨论区点击加入Q群

获取最新文章: 扫一扫右上角的二维码加入“创客智造”公众号


标签: ros机器人diego制作