前言
cartographer因为加了回环检测,以及图优化等思路, 在室内建图方面相比hector,gmapping等算法有着较好的建图效果, hector如果雷达频率高的话,也是完全可以胜任建图,但是在低特征的场合下,仍然还是要gmapping去融合里程计的效果会更为优秀一些。我最早接触cartographer是在2017年, 当时谷歌一开源,我便第一时间下载学习,当时需要的算力硬件比较苛刻,现在经过优化之后, 已经完全可以在树莓派的硬件上流畅的运行, 如今如何突发奇想, 写一下学习总结。
部署
需要条件:
- Ubuntu 20.04
- ROS1.0中的Noetic 版本
编译过程:
- 在Noetic ROS版本中通过以下命令安装相应的工具。
sudo apt-get update sudo apt-get install -y python3-wstool python3-rosdep ninja-build stow # 在老一点的ROS版本使用以下命令安装相应的工具。 sudo apt-get update sudo apt-get install -y python-wstool python-rosdep ninja-build stow
- 创建cartographer工作空间并加载代码。
mkdir catkin_ws cd catkin_ws wstool init src wstool merge -t src https://raw.githubusercontent.com/cartographer- project/cartographer_ros/master/cartographer_ros.rosinstall wstool update -t src
- 安装cartographer_ros相关的依赖, 需要使用
rosdep
的命令来安装相应的包, 如果你已经执行过, 那么sudo rosdep init
会报错, 这个错误可以忽略。sudo rosdep init rosdep update rosdep install --from-paths src --ignore-src --rosdistro=${ROS_DISTRO} -y # 在Ubuntu 16 / ROS Kinetic的版本下,需要加载以下命令。 src/cartographer/scripts/install_proto3.sh
- Cartographer需要使用abseil-cpp库,通过以下命令手动安装
由于可能和ros自带的abseil-cpp库冲突,需要借助以下命令卸载。src/cartographer/scripts/install_abseil.sh
sudo apt-get remove ros-${ROS_DISTRO}-abseil-cpp
- 编译和安装
至于为何使用catkin_make_isolated工具, 可以参考博文链接:https://blog.csdn.net/walleva96/article/details/117782357catkin_make_isolated --install --use-ninja
编译问题:
编译的时候,会出现cmake找不到python3的问题, 如下log:
Could NOT find PythonLibs: Found unsuitable version "2.7.6", but required at least "3.0.0"
可以通过以下命令解决,将python3链接到python命令上。
ln -s /usr/bin/python3 /usr/bin/python
配置Lua参数
- 首先, 关于
轨迹 trajectory_builder
、建图 map_builder
的基本参数在代码文件链接中, 我们在构建自己的参数文件时, 要将其include
到配置文件中,然后进行对应的参数设置。
https://github.com/cartographer-project/cartographer/tree/master/configuration_files - 其次, 我们还需要适配机器人传感器,坐标系等相关的参数,基本参数说明如下:
可以参考链接: https://google-cartographer-ros.readthedocs.io/en/latest/configuration.html
map_frame
用于发布子地图, 作为机器人位姿的父坐标系, 一般设置为 "map"
tracking_frame
机器人进行slam算法跟踪的坐标系, 如果使用了imu一般就设置为"imu_link", 否则设置为"base_link/base_footprint"
published_frame
作为机器人位姿变换坐标系下的子坐标系, 用于发布机器人的坐姿位置。 如果系统中,有其他节点发布了"odom"坐标系, 那么,需要将该值配置为"odom", 让catographer会去建立map到odom之间的转换,来不断调整里程计可能带来的误差, 无里程计的时候, 该值就设置为"base_link" 即可。
特别要注意的是,如果系统中已经在发布"odom"坐标系的时候, 下方的"odom_frame"和"provide_odom_frame"就没必要设置了, 不然会冲突。
odom_frame
只有在将"provide_odom_frame" 设置为true的时候, 这个值才能够起作用, 并由cartographer通过激光匹配估计等手段来产生并发布。
这个坐标系在建图中的关系为'map_frame --> odom_frame --> published_frame', 该值通常设置为 "odom", 一般如果无里程计发布, 并且机器人又需要odom坐标系的时候就启用该功能, 由cartographer来发布相应的消息。
provide_odom_frame
如果使能的话, cartographer将会在map坐标系下,将机器人的位置姿态不断发布, 也就是会不断更新"odom_frame"坐标变换、
publish_frame_projected_to_2d
如果使能的话,机器人的"published_frame"值将会被严格限制在2维平面上, 比如有人将"published_frame"设置为"base_footprint"的话, 那么坐标系就不应该存在z轴方向上的变换而避免偏离地平面。
use_odometry
如果使能的话,cartographer将会订阅"odom"话题的数据, 此时odom传感器的数据一定要发布。
use_nav_sat
如果使能的话,cartographer将会订阅"fix"话题上的sensor_msgs/NavSatFix 的卫星导航相关的数据而融合到SLAM系统之中。
use_landmarks
如果使能, 将会订阅“landmarks”话题上的cartographer_ros_msgs/LandmarkList 数据。 该话题可以为空, 但是不能够不提供, 因为cartograopher为确保landmarks的可靠性将会严格限制传感器的时间顺序, 然而,也可以通过设置 trajectory builder中的"collate_landmarks"选项值为false, 来允许使用不确定的lanmark的值。
num_laser_scans
设置二维激光雷达的数量, 通过订阅"scan"话题中sensor_msgs/LaserScan数据。
如果系统中存在多个激光雷达, 那么就要发布相应的话题为"scan_1","scan_2"等等。
num_multi_echo_laser_scans
设置多回波激光雷达的数量, 通过订阅"echoes"话题中的sensor_msgs/MultiEchoLaserScan 数据。
如果存在多个多回波激光雷达传感器, 那么就要发布相应的话题为"echoes_1", "echoes_2". 这种传感器的话,每个测距值和灵敏度都会包含多个回波值。
num_subdivisions_per_laser_scan
激光雷达传感器或者多回波雷达传感器被分割成多个点云的数目, 该选项主要是为了当扫描器在移动的时候, 分割扫描数据能够确保更容易展现点云数据? 这个选项跟 trajectory builder中的"num_accumulated_range_data"值相对应, 该值用于累加组合分割的scan数据为一个完整可用于扫描匹配的点云数据。
num_point_clouds
需要订阅的点云话题数目,如果存在多个的话, 则订阅的话题名为 "points2_1", "points2_2"
lookup_transform_timeout_sec
Timeout in seconds to use for looking up transforms using tf2.
使用tf2查找坐标变换时,等待的超时时间。
submap_publish_period_sec
发布子地图的位置的时间间隔,一般设置为. 0.3 秒左右。
pose_publish_period_sec
发布位置姿态的时间间隔, 一般设置为 5e-3 表示 200 Hz.
publish_to_tf
是否发布坐标变换。
publish_tracked_pose
是否发布话题"tracked_pose"数据geometry_msgs/PoseStamped用于位姿跟踪。
trajectory_publish_period_sec
发布trajectory markers的间隔周期 一般设置为 30e-3, 表示30 milliseconds.
rangefinder_sampling_ratio
range finders传感器的抽样比例, 表示对该传感器的置信度, 值从0~1表示。
odometry_sampling_ratio
odometry 数据的抽样比例
fixed_frame_sampling_ratio
固定坐标系的抽样比例
imu_sampling_ratio
imu传感器的抽样比例
landmarks_sampling_ratio
landmarks数据的抽样比例
配置实例
只使用二维激光, 无里程计的范例:
include "map_builder.lua"
include "trajectory_builder.lua"
options = {
map_builder = MAP_BUILDER,
trajectory_builder = TRAJECTORY_BUILDER,
map_frame = "map",
tracking_frame = "base_footprint",
published_frame = "base_footprint",
provide_odom_frame = true,
odom_frame = "odom",
publish_frame_projected_to_2d = false,
publish_tracked_pose = true,
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.,
landmarks_sampling_ratio = 1.,
imu_sampling_ratio = 0.,
}
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 = 13.
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
附带里程计的配置范例:
include "map_builder.lua"
include "trajectory_builder.lua"
options = {
map_builder = MAP_BUILDER,
trajectory_builder = TRAJECTORY_BUILDER,
map_frame = "map",
tracking_frame = "base_footprint",
published_frame = "odom",
provide_odom_frame = false,
odom_frame = "odom",
publish_frame_projected_to_2d = false,
publish_tracked_pose = true,
use_pose_extrapolator = true,
use_odometry = true,
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.1,
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.,
landmarks_sampling_ratio = 1.,
imu_sampling_ratio = 0.,
}
MAP_BUILDER.use_trajectory_builder_2d = true
TRAJECTORY_BUILDER_2D.submaps.num_range_data = 35
TRAJECTORY_BUILDER_2D.min_range = 0.2
TRAJECTORY_BUILDER_2D.max_range = 15.
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.15
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.ceres_scan_matcher.ceres_solver_options.num_threads = 2
-- cartographer has motion filter, don't move too quick.
POSE_GRAPH.optimization_problem.huber_scale = 1e2
POSE_GRAPH.optimize_every_n_nodes = 30
POSE_GRAPH.constraint_builder.min_score = 0.65
return options