Cartographer算法2D激光雷达与IMU融合建图

本文介绍如何使用cartographer算法融合2D雷达与IMU进行slam建图。先说明了硬件设备,包括思岚s1激光雷达和Tobotics ROS IMU HFI - A9,接着阐述获取雷达和IMU的话题名称及frame_id的方法,然后详细讲解修改相关文件的步骤,最后完成建图并验证融合成功。

摘要生成于 C知道 ,由 DeepSeek-R1 满血版支持, 前往体验 >

 上一篇文章讲了cartographer算法手持雷达建图的参数调试,这篇进一步讲如何融合2D雷达与IMU采用cartographer算法进行slam建图。

cartographer算法手持二维激光雷达建图(不使用里程计及IMU)

https://blog.youkuaiyun.com/wangchuchua/article/details/127268037?spm=1001.2014.3001.5502

首先先说一下我的硬件设备:

思岚s1激光雷达、Tobotics ROS IMU HFI-A9。

  和上一篇讲的一样在进行文件修改之前一定一定要先弄明白自己的雷达和IMU的话题名称topic_id以及frame_id,否则名称对不上肯定是会报错的。

首先启动雷达,如果有用思岚激光雷达的小伙伴可以参考这个网址。(只要可以实现点云信息的发布就好。)ROS与激光雷达入门教程-ROS中使用激光雷达(思岚S1) - 创客智造

雷达的frame_id就是图中画红圈的,我的是laser。

  接下来就是查看雷达的话题名称,打开终端输入:

rostopic list

可以看到雷达topic名称一般都是scan。同时还有另一种方法查询雷达的frame_id,就是在终端输入:

rostopic echo /topic | grep frame_id

其中topic名称输入你雷达的话题名称就可,我的话题名称是scan所以输入:

rostopic echo /scan | grep frame_id

 这样就能查到话题scan的fram_id啦。通过以上操作我得知了我的雷达话题是scan、frame_id是laser。

 好接下来启动IMU模块,一般rosIMU是会有启动包的,启动IMU后通过rostopic查询一下IMU的话题名称,我的话题名称是/imu。知道话题名称后输入命令:rostopic echo /imu | grep frame_id查询frame-id。通过以上操作我得知了我IMU的话题名称是/imu,frame-id是base_link。知道这些后就开始正式的修改相关的文件。

首先找到~/google_ws/src/cartographer_ros/cartographer_ros/configuration_files目录下的建立一个revo_lds.lua文件,为了和手持建图的lua文件区分开,我有复制了这个文件,重命名为revo_imu.lua。修改后文件内容如下:

-- Copyright 2016 The Cartographer Authors
--
-- Licensed under the Apache License, Version 2.0 (the "License");
-- you may not use this file except in compliance with the License.
-- You may obtain a copy of the License at
--
--      http://www.apache.org/licenses/LICENSE-2.0
--
-- Unless required by applicable law or agreed to in writing, software
-- distributed under the License is distributed on an "AS IS" BASIS,
-- WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-- See the License for the specific language governing permissions and
-- limitations under the License.

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 = "laser",
  odom_frame = "odom",
  provide_odom_frame = true,
  publish_frame_projected_to_2d = false,
  use_pose_extrapolator = 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.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 = true
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 = "base_link",#这里要与imu的frame_id名称一致
published_frame = "laser",#这里要与雷达的frame_id名称一致
TRAJECTORY_BUILDER_2D.use_imu_data = true

然后在~/google_ws/src/cartographer_ros/cartographer_ros//urdf/文件下创建一个urdf文件文件内容如下所示(我的urdf文件名称是:backpack_2d1.urdf,原本包里自带了两个urdf文件因为我要自己调整imu和雷达的位置关系就另写了一个urdf文件):这里一定要注意urdf里的link name一定要与雷达或者imu的fram_id相对应。

<!--
  Copyright 2016 The Cartographer Authors

  Licensed under the Apache License, Version 2.0 (the "License");
  you may not use this file except in compliance with the License.
  You may obtain a copy of the License at

       http://www.apache.org/licenses/LICENSE-2.0

  Unless required by applicable law or agreed to in writing, software
  distributed under the License is distributed on an "AS IS" BASIS,
  WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
  See the License for the specific language governing permissions and
  limitations under the License.
-->
<robot name="mini">
  <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="base_link">#与imu的fram_id对应
    <visual>
      <origin xyz="0 0 0" />
      <geometry>
        <box size="0.06 0.04 0.02" />
      </geometry>
      <material name="orange" />
    </visual>
  </link>
  <link name="laser">#与雷达的fram_id对应
    <visual>
      <origin xyz="0 0 0" />
      <geometry>
        <cylinder length="0.05" radius="0.03" />
      </geometry>
      <material name="gray" />
    </visual>
  </link>


  <joint name="imu2laser" type="fixed">
    <parent link="laser" />
    <child link="base_link" />
    <origin xyz="0 0 -0.035" />
  </joint>

</robot>

 在riviz中显示是这样的,小老板们可以根据需要调整雷达和imu之间的相对位置关系。

在~/google_ws/src/cartographer_ros/cartographer_ros/launch目录下建立launch文件,我的文件名称是demo_revo_sc_imu.launch。文件内容如下:

<!--
  Copyright 2016 The Cartographer Authors

  Licensed under the Apache License, Version 2.0 (the "License");
  you may not use this file except in compliance with the License.
  You may obtain a copy of the License at

       http://www.apache.org/licenses/LICENSE-2.0

  Unless required by applicable law or agreed to in writing, software
  distributed under the License is distributed on an "AS IS" BASIS,
  WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
  See the License for the specific language governing permissions and
  limitations under the License.
-->

<launch>
  <param name="/use_sim_time" value="false" />

  <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="256000"/>
  <param name="frame_id"            type="string" value="laser"/>
  <param name="inverted"            type="bool"   value="false"/>
  <param name="angle_compensate"    type="bool"   value="true"/>
  </node>

  <node name="cartographer_node" pkg="cartographer_ros"
      type="cartographer_node" args="
          -configuration_directory $(find cartographer_ros)/configuration_files
          -configuration_basename revo_imu.lua"
      output="screen">
    <remap from="scan" to="scan" />
    <remap from="imu/data" to="imu" />#这里是你的imu的话题名称
  </node>

  <node name="cartographer_occupancy_grid_node" pkg="cartographer_ros"
      type="cartographer_occupancy_grid_node" args="-resolution 0.05" />
  <param name="robot_description" textfile="$(find cartographer_ros)/urdf/backpack_2d1.urdf" />
  <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />


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

这个文件中包含了启动雷达节点,和cartographer建图节点,相对于上节的launch文件内容增加了 

 <remap from="imu/data" to="imu" />注意要用你自己imu的话题名称。

以及 urdf文件,注意要对应你的urdf文件路径。

 <param name="robot_description" textfile="$(find cartographer_ros)/urdf/backpack_2d1.urdf" />
  <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />

到这里文件调整部分就完成了,可以开始启动建图了,因为上面的launch文件没有包含imu启动节点所以我这里先单独启动imu。 

roslaunch handsfree_ros_imu imu1.launch

imu启动之后就可以运行 demo_revo_sc_imu.launch文件了,别忘记启动之前要catkin_make_isolated --install --use-ninja。

source install_isolated/setup.bash
catkin_make_isolated --install --use-ninja
roslaunch cartographer_ros demo_revo_sc_imu.launch

 运行成功后的效果是这样的。

 打开终端输入rqt_graph查看节点关系,我们可以看到imu和雷达信息已经输入到cartographer的节点中去说明融合成功了。

rqt_graph

打开终端输入rosrun rqt_tf_tree rqt_tf_tree得到tf关系图: 

到这里就完成了cartographer算法的雷达与IMU融合建图。希望这篇文章能够帮助到大家,祝大家生活愉快,学业顺利 (*^▽^*)。

【资源说明】 1、该资源包括项目的全部源码,下载可以直接使用! 2、本项目适合作为计算机、数学、电子信息等专业的课程设计、期末大作业和毕设项目,作为参考资料学习借鉴。 3、本资源作为“参考资料”如果需要实现其他功能,需要能看懂代码,并且热爱钻研,自行调试。 基于ROS的激光雷达+小车+IMU的SLAM、定位、路径规划c++实现源码+项目说明.zip # 单线激光雷达SLAM路径规划 使用的硬件:autolabor pro1小车、小觅双目相机(S1030标准版本)、IntelNUC迷你主机、显示器、2D激光雷达 Delta-1A 使用的软件:ubuntu 16.04 LTS、ROS-kinetic、小觅驱动、autolabor pro1小车驱动、Delta-1A驱动、VINS-Fusion算法、ROS-navigation导航包、gmapping算法cartographer_ros算法 ## tf介绍 tf变换:map(地坐标系)-->odom(里程计坐标系)——>base_link(小车基座坐标系)——>传感器坐标系(lidar、camera) ---- map-->odom 由算法提供 ---- odom --> base_link 由小车驱动提供 ---- base_link --> 传感器坐标系 根据传感器在小车上安装的位置确定,使用static_transform_publisher静态坐标转换来设置 所需传感器数据类型: sensor_msgs/LaserScan 使用Delta-1A驱动发布的雷达扫描话题,话题名:/scan 所需里程计信息数据类型:nav_msgs/Odometry 使用autolabor pro1发布的里程计,话题名:/wheel_odom ## 采用gmapping cartographer_ros算法分别进行 ### gmapping:(雷达+小车) 打开终端,执行如下指令: $ cd ~/catkin_ws_lidar_slam/ $ source devel/setup.bash $ roslaunch autolabor_box_launch create_map_gmapping.launch ####打开小车urdf模型、驱动、键盘控制节点、打开雷达驱动、打开gmapping节点、打开rviz可视化节点 ####此时使用键盘的上下左右键控制小车移动,开始 ####完成后,开启新的终端执行如下指令,保存地: $ rosrun map_server map_saver -f map_name ####保存地 map_name为保存地的名称,运行结果,会生成2个文件,后缀名分别为 .pgm .yaml ### cartographer_ros:(雷达+小车) ##打开终端,执行如下指令: $ cd ~/catkin_ws_lidar_slam/ $ source devel/setup.bash $ roslaunch autolabor_box_launch create_map_cartographer.launch ####此时使用键盘的上下左右键控制小车移动,开始 ####完成后,开启新的终端执行如下指令,保存地: $ rosrun map_server map_saver -f map_name ......
### 使用2D激光雷达Cartographer进行SLAM配置 #### 启动环境准备 为了确保能够顺利运行基于2D激光雷达Cartographer SLAM程序,在Ubuntu 20.04以及ROS Noetic环境中安装必要的依赖项。这包括但不限于设置好ROS工作空间,安装Cartographer及其对应的ROS包。 ```bash sudo apt-get update && sudo apt-get install ros-noetic-cartographer-ros \ ros-noetic-cartographer-ros-msgs ``` #### 配置文件调整 针对RPLidar X3或其他类型的2D激光雷达设备,需创或修改相应的launch文件来适配具体的硬件接口参数。通常情况下,这些配置会被放置于`/path_to_ws/src/cartographer_ros/configuration_files/rplidar.lua`这样的路径下[^1]。 对于仅利用激光雷达而不借助IMU或里程计的情况,重点在于简化输入源并优化算法处理流程: ```lua 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 = "odom", odom_frame = "", -- 不使用里程计,则留空此项 provide_odom_frame = false, -- 关闭提供里程计帧选项 use_pose_extrapolator = false, num_laser_scans = 1, num_multi_echo_laser_scans = 0, num_subdivisions_per_laser_scan = 1, num_point_clouds = 0, } MAP_BUILDER.use_trajectory_builder_2d = true TRAJECTORY_BUILDER_2D.min_range = 0.12 TRAJECTORY_BUILDER_2D.max_range = 10. TRAJECTORY_BUILDER_2D.missing_data_ray_length = 5. TRAJECTORY_BUILDER_2D.use_imu_data = false -- 明确关闭IMU数据读取 TRAJECTORY_BUILDER_2D.num_accumulated_range_data = 1 POSE_GRAPH.optimization_problem.huber_scale = 5e2 POSE_GRAPH.optimize_every_n_nodes = 90 POSE_GRAPH.constraint_builder.min_score = 0.65 POSE_GRAPH.global_sampling_ratio = 0.003 POSE_GRAPH.max_num_final_iterations = 200 ``` 上述Lua脚本定义了一系列关键参数,特别是去除了对IMU的支持,并且强调了只接收来自单一2D激光扫描仪的数据流作为主要感知手段。 #### Launch 文件编写 接下来就是设计一个适合此场景使用的Launch文件,它负责启动所有必需的服务节点并将它们连接起来形成完整的系统架构。下面是一个简单的例子,假设已经正确设置了之前提到过的配置文件路径: ```xml <launch> <!-- 启动 RPLIDAR 节点 --> <node name="rplidarNode" pkg="rplidar_ros" type="rplidarNode" output="screen"> <param name="frame_id" value="laser"/> <param name="angle_compensate" value="true"/> <param name="scan_mode" value="Sensitivity"/> </node> <!-- 启动 cartographer_node 并加载自定义配置 --> <node name="cartographer_node" pkg="cartographer_ros" type="cartographer_node" args=" -configuration_directory $(find my_robot_carto)/config/ -configuration_basename rplidar.lua"/> <!-- 发布 TF 变换关系 (从 base_link 到 laser) --> <node pkg="tf" type="static_transform_publisher" name="base_to_laser_broadcaster" args="0 0 0 0 0 0 /base_link /laser 100"/> </launch> ``` 这段XML代码片段展示了如何组合不同组件以实现预期功能——即通过指定的配置文件初始化Cartographer实例,并同时激活RPLidar驱动程序以便获取实时测距信息;另外还包含了静态变换发布器用于立固定的空间关联。 ---
评论 27
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值