使用激光雷达RPLIDAR A1/A2与Cartographer算法实现SLAM

一 、在Gazebo仿真环境中实现SLAM

在终端上输入以下命令,来完成cartographer SLAM的Gazebo仿真:

roslaunch mbot_gazebo mbot_laser_nav_gazebo.launch 

roslaunch cartographer_ros cartographer_demo_rplidar2.launch

roslaunch mbot_teleop mbot_teleop.launch

通过键盘控制装有激光雷达的小车在仿真环境中运动,激光雷达不断探测周围环境,并通过cartographer算法完成定位与地图构建:

使用激光雷达RPLIDAR A1/A2与Cartographer算法实现SLAM_第1张图片
建图完成后,通过以下命令保存地图:

(1)不再接受进一步数据:

rosservice call /finish_trajectory 0

(2)序列化保存其当前状态

rosservice call /write_state "{filename: '${HOME}/Downloads/mymap.pbstream'}"

(3)将pbstream转换为pgm和yaml

rosrun cartographer_ros cartographer_pbstream_to_ros_map -map_filestem=${HOME}/Downloads/mymap -pbstream_filename=${HOME}/Downloads/mymap.pbstream -resolution=0.05

生成对应的pgm和yaml,放于${HOME}/Downloads/mymap目录下:

使用激光雷达RPLIDAR A1/A2与Cartographer算法实现SLAM_第2张图片

cartographer_demo_rplidar2.launch文件内容:

  
  
    

    
      
    

这里要注意的是 :

(1)仿真环境下,参数"/use_sim_time"的值为"true"

 

(2)参数配置文件为revo_lds2.lua

revo_lds2.lua文件内容:

include "map_builder.lua"
include "trajectory_builder.lua"

options = {
  map_builder = MAP_BUILDER,
  trajectory_builder = TRAJECTORY_BUILDER,
  map_frame = "map",
  tracking_frame = "laser_link",
  published_frame = "laser_link",
  odom_frame = "odom",
  provide_odom_frame = true,
  publish_frame_projected_to_2d = false,
  use_odometry = false,
  use_nav_sat = false,
  use_landmarks = false,
  num_laser_scans = 1,
  num_multi_echo_laser_scans = 0,
  num_subdivisions_per_laser_scan = 1,
  num_point_clouds = 0,
  lookup_transform_timeout_sec = 0.2,
  submap_publish_period_sec = 0.3,
  pose_publish_period_sec = 5e-3,
  trajectory_publish_period_sec = 30e-3,
  rangefinder_sampling_ratio = 1.,
  odometry_sampling_ratio = 1.,
  fixed_frame_pose_sampling_ratio = 1.,
  imu_sampling_ratio = 1.,
  landmarks_sampling_ratio = 1.,
}

MAP_BUILDER.use_trajectory_builder_2d = true

TRAJECTORY_BUILDER_2D.submaps.num_range_data = 35
TRAJECTORY_BUILDER_2D.min_range = 0.3
TRAJECTORY_BUILDER_2D.max_range = 8.
TRAJECTORY_BUILDER_2D.missing_data_ray_length = 1.
TRAJECTORY_BUILDER_2D.use_imu_data = false
TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = true
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.linear_search_window = 0.1
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.translation_delta_cost_weight = 10.
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.rotation_delta_cost_weight = 1e-1

POSE_GRAPH.optimization_problem.huber_scale = 1e2
POSE_GRAPH.optimize_every_n_nodes = 35
POSE_GRAPH.constraint_builder.min_score = 0.65

return options

这里要注意的地方是 :

tracking_frame = “laser_link”,
published_frame = “laser_link”,

即cartographer参数配置文件中的frame_id,要与xacro机器人模型文件中的frame_id匹配。

二、在真实环境中实现SLAM

在终端上输入以下命令,来完成真实环境中的cartographer SLAM:

roslaunch cartographer_ros cartographer_view_slam.launch

launch文件运行后,在真实的环境中移动激光雷达,激光雷达不断探测周围环境,并通过cartographer算法完成定位与地图构建,地图会以一种渐变的形式由浅至深出现,随着激光雷达的移动,建立完成的地图会逐渐呈现为白色:

使用激光雷达RPLIDAR A1/A2与Cartographer算法实现SLAM_第3张图片
建图完成后,保存地图,方法不再赘述。

cartographer_view_slam.launch文件内容如下:



  

  


cartographer_demo_rplidar3.launch文件内容如下:


 
  
  
    
  

 

 

  

这里要注意的是 :

(1)非仿真环境下,参数"/use_sim_time"的值为"false"

 

(2)参数配置文件为revo_lds3.lua

revo_lds3.lua文件内容:

include "map_builder.lua"
include "trajectory_builder.lua"

options = {
  map_builder = MAP_BUILDER,
  trajectory_builder = TRAJECTORY_BUILDER,
  map_frame = "map",
  tracking_frame = "laser",
  published_frame = "laser",
  odom_frame = "odom",
  provide_odom_frame = true, --算法内部提供里程计
  publish_frame_projected_to_2d = false,
  use_odometry = false, --不使用里程计
  use_nav_sat = false,
  use_landmarks = false,

  num_laser_scans = 1,
  num_multi_echo_laser_scans = 0,
  num_subdivisions_per_laser_scan = 1,
  num_point_clouds = 0,
  lookup_transform_timeout_sec = 0.2,
  submap_publish_period_sec = 0.3,
  pose_publish_period_sec = 5e-3,
  trajectory_publish_period_sec = 30e-3,
  rangefinder_sampling_ratio = 1.,
  odometry_sampling_ratio = 1.,
  fixed_frame_pose_sampling_ratio = 1.,
  imu_sampling_ratio = 1.,
  landmarks_sampling_ratio = 1.,
}

MAP_BUILDER.use_trajectory_builder_2d = true

TRAJECTORY_BUILDER_2D.submaps.num_range_data = 35
TRAJECTORY_BUILDER_2D.min_range = 0.3
TRAJECTORY_BUILDER_2D.max_range = 5.
TRAJECTORY_BUILDER_2D.missing_data_ray_length = 1.
TRAJECTORY_BUILDER_2D.use_imu_data = false
TRAJECTORY_BUILDER_2D.imu_gravity_time_constant = 9.8 
TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = true
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.linear_search_window = 0.1
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.translation_delta_cost_weight = 10.
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.rotation_delta_cost_weight = 1e-1
POSE_GRAPH.optimization_problem.huber_scale = 1e2
POSE_GRAPH.optimize_every_n_nodes = 35
POSE_GRAPH.constraint_builder.min_score = 0.65

return options

这里要注意的地方是 :

tracking_frame = “laser”,
published_frame = “laser”,

即cartographer参数配置文件中的frame_id,要与rplidar.launch文件中的frame_id匹配:

使用激光雷达RPLIDAR A1/A2与Cartographer算法实现SLAM_第4张图片

你可能感兴趣的:(使用激光雷达RPLIDAR A1/A2与Cartographer算法实现SLAM)