使用 Google Cartographer 和 RPLidar 与 Raspberry Pi 进行机器人SLAM建图

在这个实验中,我将在具有 360 度 LDS RPLidar A1m8 的 Raspberry Pi b3+ 上启动开源 SLAM 软件——Google Cartographer
所有的 SLAM 过程都是在 Raspberry PI 上启动的。Cartographer 配置为仅使用激光雷达数据进行地图构建和位置估计。不使用 IMU。
我假设您已经在 Raspberry Pi 上安装了 Ubuntu 18.04 和 ROS。
微信截图_20230213195924.png


什么是 Google Cartographer

Cartographer 是一个提供实时 SLAM(同时定位和映射)的系统。换句话说,使用来自激光雷达和其他传感器的信息,Cartographer 可以构建环境地图并显示机器人与地图相关的位置。Cartographer 可以构建二维地图和 3D。但对于 3D 地图,需要点云作为源。我们将使用 RPLIDAR a1m8 作为主要传感器。该传感器提供 360 度距离测量作为细线 — Laserscan。Cartorgapher 支持多种激光雷达、IMU 和其他
方法提高 SLAM 质量。但最小的传感器组是单个 360 度 LDS 传感器(在我们的例子中是 RPLIDAR),我将测试它是如何工作的。Cartographer 有一个 ROS 集成包
— cartographer_ros您可以从源代码构建它或从 ROS 存储库获取。对于第一次尝试,我会推荐第二个选项。

3D打印零件

为了让实验更方便,我打印了几个部件来将 RPLIDAR、Raspberry Pi 和 powerbank 放在一起。您可以从 Thingiverse下载 STL 文件

微信截图_20230213200012.png

整个设备由作为传感器的RPLIDAR、作为计算机的Raspberry Pi和作为电源的powerbank组成。组装设备相当简单和坚固:

微信截图_20230213200047.png

解释软件部分

您可以在下面看到整个设置的高级描述。RPLIDAR 连接到 Raspberry Pi,Cartographer 在 Raspberry Pi 上安装并运行,笔记本电脑用于可视化。

微信截图_20230213200119.png

由于我在 Raspberry Pi(没有 GUI)上使用无头系统,因此将在笔记本电脑上执行可视化。笔记本电脑也安装了 ROS。
要配置 ROS 通过网络工作,您必须在两台计算机上指定两个环境变量:ROS_IP 和 ROS_MASTER_URL。您可以在 ROS Wiki 中找到详细信息

树莓派

注意——我假设您已经在 Raspberry Pi 上安装了 Ubuntu并安装了ROS Melodic
首先你必须安装 Cartographer 和 rplidar ROS 包:

sudo apt install ros-melodic-cartographer-ros ros-旋律-rplidar-ros

安装包后,创建 catkin 工作区并将 gbot_core 包从 Github 克隆到src目录:

git   clone   https://github.com/Andrew-rw/gbot_core.git

该软件包不包含任何编译代码,但包含对 SLAM 系统很重要的配置文件和启动脚本。让我们详细看看它们。
configuration_files目录中,您可以找到 Cartographer 的配置:

 
include "map_builder.lua"
include "trajectory_builder.lua"
options = {
  map_builder = MAP_BUILDER,
  trajectory_builder = TRAJECTORY_BUILDER,
  map_frame = "map",
  tracking_frame = "base_link",
  published_frame = "base_link",
  odom_frame = "odom",
  provide_odom_frame = true,
  publish_frame_projected_to_2d = true,
  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.min_range = 0.5
TRAJECTORY_BUILDER_2D.max_range = 8.
TRAJECTORY_BUILDER_2D.missing_data_ray_length = 8.5
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
TRAJECTORY_BUILDER_2D.motion_filter.max_angle_radians = math.rad(0.2)
-- for current lidar only 1 is good value
TRAJECTORY_BUILDER_2D.num_accumulated_range_data = 1
POSE_GRAPH.constraint_builder.min_score = 0.65
POSE_GRAPH.constraint_builder.global_localization_min_score = 0.65
POSE_GRAPH.optimization_problem.huber_scale = 1e2
POSE_GRAPH.optimize_every_n_nodes = 35
return options

大多数参数是根据 RPLIDAR 的规范通过实验或计算得出的,但我想强调其中的一些参数。由于我们要使用的唯一传感器是 RPLIDAR,因此将根据扫描数据和根据先前扫描构建的计算地图之间的空间差异来计算定位。因此 Cartographer 将成为里程计的来源。
参数provide_odom_frame = true表示 Cartographer 将发布published_framemap_frame 之间的转换。在我们的例子中,它将是“base_link”和“map”之间的 TF 转换。
参数publish_frame_projected_to_2d = true表示发布的变换将仅在 X 和 Y 坐标中,不存在高程。
范围use_odometry = false表示没有其他里程计来源。制图师只会将“odom”框架粘贴到“地图”上。同样,对于我们的简单案例来说,这很好。
TRAJECTORY_BUILDER_2D.use_imu_data = false表示我们不会使用 IMU 并且只计算 Laserscan 点匹配算法。您可以在 Cartographer 文档中
找到有关特定参数的更多信息rviz目录有一个 RViz 视图文件,其中包含已设置的主题侦听器列表,以使地图可视化更方便使用。urdf

目录中有一个所谓的机器人描述——包含机器人对 ROS 的物理描述的文件。有传感器的空间位置和关系、关节类型、长度、质量、惯性等信息。更多信息在ROS Wiki 页面上对于我们的测试平台,创建 URDF 是一项开销——基础和激光雷达之间只有一个链接,它可以作为静态转换添加到启动文件中——但如果你决定添加 IMU 传感器,这个文件是一个很好的起点,测距仪或其他东西。URDF 描述语言建立在 XML 之上:

 
<robot name="head_2d">
  <material name="orange">
    <color rgba="1.0 0.5 0.2 1" />
  </material>
  <material name="gray">
    <color rgba="0.2 0.2 0.2 1" />
  </material>
  <link name="laser">
    <visual>
      <origin xyz="0 0 0" />
      <geometry>
        <cylinder length="0.03" radius="0.03" />
      </geometry>
      <material name="gray" />
    </visual>
  </link>
  <link name="base_link">
    <visual>
      <origin xyz="0.01 0 0.015" />
      <geometry>
        <box size="0.11 0.065 0.052" />
      </geometry>
      <material name="orange" />
    </visual>
  </link>
  <joint name="laser_joint" type="fixed">
    <parent link="base_link" />
    <child link="laser" />
    <origin rpy="0 0 3.1415926" xyz="0 0 0.05" />
  </joint>
</robot>

最后,在launch目录中有两个脚本,用于启动 SLAM 过程 ( gbot.launch ) 和启动可视化 ( visualization.launch )。gbot.launch的结构很简单——首先是启动机器人描述节点,然后是 Lidar,最后是 Cartographer。最后一个节点 cartographer_occupancy_grid_node 用于将 Cartographer 地图数据转换为更流行的 ROS 导航堆栈占用网格。Occupancy Grid 将环境表示为单元格的网格,其中每个单元格都包含一个概率值,表示该单元格在 [0,100] 范围内被占用。这个启动文件应该在 Raspberry Pi 上执行。


<launch>
  <!-- Load robot description and start state publisher-->
    <param name="robot_description" textfile="$(find gbot_core)/urdf/head_2d.urdf" />
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />

  <!-- Start RPLIDAR sensor node which provides LaserScan data  -->
    <node name="rplidarNode" pkg="rplidar_ros" type="rplidarNode" output="screen">
        <param name="serial_port" type="string" value="/dev/ttyUSB0"/>
        <param name="serial_baudrate" type="int" value="115200"/>
        <param name="frame_id" type="string" value="laser"/>
        <param name="inverted" type="bool" value="false"/>
        <param name="angle_compensate" type="bool" value="true"/>
    </node>

  <!-- Start Google Cartographer node with custom configuration file-->
    <node name="cartographer_node" pkg="cartographer_ros" type="cartographer_node" args="
          -configuration_directory
              $(find gbot_core)/configuration_files
          -configuration_basename gbot_lidar_2d.lua" output="screen">
    </node>
<!-- Additional node which converts Cartographer map into ROS occupancy grid map. Not used and can be skipped in this case -->
    <node name="cartographer_occupancy_grid_node" pkg="cartographer_ros" type="cartographer_occupancy_grid_node" args="-resolution 0.05" />

</launch>

visualization.launch的结构更简单。它的目的是用准备好的视图配置启动rviz

 
<launch>
  <!-- Start RViz with custom view -->
  <node pkg="rviz" type="rviz" name="show_rviz" args="-d $(find gbot_core)/rviz/demo.rviz"/>    
</launch>

笔记本电脑

要正确可视化 Carographer 数据,应在笔记本电脑上安装 cartographer-rviz 包:

sudo apt install  ros-melodic-cartographer-rviz

为了能够启动可视化脚本,我建议在笔记本电脑上也克隆 gbot_core。
需要注意的是 - Cartographer 和可视化可以从一台计算机启动,无需任何配置更改。

Cartographer测试

好吧,假设计算机之间的网络连接已建立,我们准备启动制图师和可视化节点。
在树莓派上启动映射过程:

roslaunch gbot_core gbot.launch

 微信截图_20230213200621.png

在围绕房间移动激光雷达的过程中,地图将变得更加详细,并且对比度越来越高。这意味着 Cartographer 对环境的不确定性降低了。您还会看到一条蓝线轨迹,它是从计算的里程计中提取的:


https://miro.medium.com/v2/resize:fit:720/1*8ImKqBVghzGgsvGWvz6foA.gif

结论

Cartographer 可以提供质量不错的 2D 里程计,只使用低成本的 360 度 LDS 和相当低的数据速率(5-7 赫兹)。
IMU 和额外的里程计源(例如轮式平台里程计或视觉里程计)可以提高大环境区域的地图质量。但对于大约 50-60 平方米的室内地图,它们并不那么重要——Cartographer 的内部闭环算法能够保持这种小地图的一致性。

Links

3D files: https://www.thingiverse.com/thing:3970110
Project on GitHub: https://github.com/Andrew-rw/gbot_core
Cartographer Wiki: https://google-cartographer.readthedocs.io/en/latest/

sitemap