RoboSense(速腾)16线激光雷达数据进行cartographer建图的实践历程

在上篇博客对RoboSense(速腾)16线激光雷达的介绍基础上,本文分享如何利用雷达数据进行cartographer建图。

一.cartographer相关文件的修改

进入cartographer所在工作空间

cd ~/catkin_cartographer/src/cartographer_ros/cartographer_ros/launch
cp demo_revo_lds.launch cartographer_demo_rs16.launch
  1. 修改cartographer_demo_rs16.launch文件如下:
<launch>
  <param name="/use_sim_time" value="false" />

  <node name="cartographer_node" pkg="cartographer_ros"
      type="cartographer_node" args="
          -configuration_directory $(find cartographer_ros)/configuration_files
          -configuration_basename rs16_lidar.lua"
      output="screen">
    <remap from="scan" to="/scan" />
  </node>
  
  <node pkg="tf" type="static_transform_publisher" name="base_to_laser" args="0.0 0.0 0.45 0 0.0 0.0 map rslidar 100" />

  <node name="cartographer_occupancy_grid_node" pkg="cartographer_ros"
      type="cartographer_occupancy_grid_node" args="-resolution 0.05" />
  <node name="rviz" pkg="rviz" type="rviz" required="true"
      args="-d $(find cartographer_ros)/configuration_files/demo_2d.rviz" />
</launch>

如下图,框选出来的参数是重点:
在这里插入图片描述

  1. 创建rs16_lidar.lua文件
cd ~/catkin_cartographer/src/cartographer_ros/cartographer_ros/configuration_files
cp revo_lds.lua rs16_lidar.lua
gedit rs16_lidar.lua

修改文件如下:

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

options = {
  map_builder = MAP_BUILDER,
  trajectory_builder = TRAJECTORY_BUILDER,
  map_frame = "map",
  tracking_frame = "rslidar",
  published_frame = "rslidar",
  odom_frame = "odom",
  provide_odom_frame = false,
  publish_frame_projected_to_2d = false,
  use_pose_extrapolator = on,
  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.ceres_scan_matcher.translation_weight = 2
TRAJECTORY_BUILDER_2D.ceres_scan_matcher.rotation_weight = 10
TRAJECTORY_BUILDER_2D.submaps.num_range_data = 90
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

如下图,框选出来的参数是重点:
在这里插入图片描述

二.下载pointcloud_to_laserscan包实现三维转二维

  1. 安装pointcloud_to_laserscan包
    下载源码到工作空间并编译,我选择的是上文介绍的雷达所在的工作空间~/robosense_ws
cd ~/robosense_ws/src
git clone https://github.com/BluewhaleRobot/pointcloud_to_laserscan.git
cd ~/robosense_ws
catkin_make
  1. 创建launch文件
cd ~/robosense_ws/src/pointcloud_to_laserscan/launch
gedit point_to_scan.launch

在打开的文本中输入如下:

<?xml version="1.0"?>

<launch>

    <!-- run pointcloud_to_laserscan node -->
    <node pkg="pointcloud_to_laserscan" type="pointcloud_to_laserscan_node" name="pointcloud_to_laserscan">

        <remap from="cloud_in" to="/rslidar_points"/>
        
        <rosparam>
            # target_frame: rslidar # Leave disabled to output scan in pointcloud frame
            transform_tolerance: 0.01
            min_height: -0.4
            max_height: 1.0

            angle_min: -3.1415926 # -M_PI
            angle_max: 3.1415926 # M_PI
            angle_increment: 0.003 # 0.17degree
            scan_time: 0.1
            range_min: 0.2
            range_max: 100
            use_inf: true
            inf_epsilon: 1.0

            # Concurrency level, affects number of pointclouds queued for processing and number of threads used
            # 0 : Detect number of cores
            # 1 : Single threaded
            # 2->inf : Parallelism level
            concurrency_level: 1
        </rosparam>

    </node>

</launch>

这里需要注意的是这句代码:。因为激光雷达节点发布的信息是/rslidar_points,因此需要将pointcloud_to_laserscan的订阅信息从默认的cloud_in改为/rslidar_points。

三.运行服务

  1. 新开一个终端,启动3d雷达驱动
    在此之前可以屏蔽rs_lidar_16.launch文件中对节点rviz的启动,不屏蔽也没关系,第3步Cartographer也将启动rviz节点覆盖。
cd ~/robosense_ws
source devel/setup.bash
roslaunch rslidar_pointcloud rs_lidar_16.launch
  1. 新开一个终端,启动pointcloud_to_laserscan节点
cd ~/robosense_ws
source devel/setup.bash
roslaunch pointcloud_to_laserscan point_to_scan.launch
  1. 新开一个终端,启动Cartographer
cd ~/catkin_cartographer
catkin_make_isolated --install --use-ninja
source install_isolated/setup.bash
roslaunch cartographer_ros cartographer_demo_rs16.launch

四.见证奇迹

在这里插入图片描述
可以看到Cartographer成功接收了雷达数据并建图(可移动雷达扫描周围环境),并在rviz上展示。

若需要保存所建地图,可查看上篇博客ROS入门——slam之cartographer仿真建图,存图,加载地图所分享的内容。

可以开启新终端,用命令查看当前话题分布情况:

rqt_graph 

在这里插入图片描述

  • 4
    点赞
  • 65
    收藏
    觉得还不错? 一键收藏
  • 3
    评论
评论 3
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值