(三) 基本参数配置

launch 和 lua 配置文件都是在install_isolated/share/cartographer_ros/launch/install_isolated/share/cartographer_ros/configuration_files/ 下,所以如果只修改了cartographer_ros软件包中的launch 和 lua 文件之后是需要重新编译的,编译之后才能将修改的文件安装到install_isolated文件中。

从cartographer启动时输出的信息可知,我们自己的lua加载的其他lua有:map_builder.lua, pose_graph.lua, trajectory_builder.lua, trajectory_builder_2d.lua. 它们的路径都在/usr/local/share/cartographer/configuration_files。如果我们需要改这些基本lua的参数,可以在自己lua里覆盖地修改,直接改原文件不太好,它们的关系如下:

map_builder.luatrajectory_build.lua起着总领的作用,前者包括的pose_graph.lua为后端优化的具体参数配置; 后者是前端的参数配置,分为2d和3d两个文件。

lua_parameter_dictionary.cc是用于lua参数的,如果这里有报错,基本是lua参数的语法问题

1
[/cartographer_node] [ScopedRosLogSink::send] line_63  F0402 21:57:53.000000 20519 lua_parameter_dictionary.cc:399] Check failed: HasKey(key) Key 'use_nav_sat' not in dictionary:

在lua文件里必须设置use_nav_sat参数,同样报错的参数都要添加

自定义lua的参数

我用的是home.lua, 先看options的内容,这是通用的参数。options块中定义的值定义了cartographer前端应当如何与机器人进行交互。 定义在options段后的值用于调试cartographer的内部信息

开头的map_builder = MAP_BUILDERtrajectory_builder = TRAJECTORY_BUILDER万年不变:

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
map_builder = MAP_BUILDER,
trajectory_builder = TRAJECTORY_BUILDER,
map_frame = "map",
tracking_frame = "imu",
published_frame = "odom",
odom_frame = "odom",
provide_odom_frame = false,
publish_frame_projected_to_2d = false,
publish_tracked_pose = false

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.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.,

# 补充
collate_fixed_frame = true 是否将数据放入阻塞队列
collate_landmarks = false -- 一般都是false

坐标系组

  • map_frame: 用于发布submaps的ROS坐标系,也是位姿的父坐标系,通常是map

  • tracking_frame: 通常,如果使用IMU,就是imu_link; 如果不用IMU,可以用laser。博物馆的lua写的base_link

有时遇到这样的报错:

1
Check failed: sensor_to_tracking->translation().norm() < 1e-5 The IMU frame must be colocated with the tracking frame. Transforming linear acceleration into the tracking frame will otherwise be imprecise

这是因为在使用IMU的情况下,tracking frame不是imu的link

  • published_frame: 位姿子坐标系的ROS坐标系,例如”odom”坐标系,如果一个odom坐标系由系统的不同部分提供,在这种情况下,map_frame中的odom姿势将被发布。 否则,将其设置为base_link可能是合适的

  • provide_odom_frame: true 适用于机器人本身没有odom坐标系的情况,如果启用,将发布局部、非闭环、持续的位姿,也就是odom_frame在map_frame中的坐标

  • odom_frame: 在provide_odom_frame为true才启用,坐标系在published_frame和map_frame之间用于发布局部SLAM结果,通常是”odom”
  • use_odometry: 如果启用,会订阅关于odom话题(或者叫其他名字)的nav_msgs/Odometry消息。应当提供里程信息,这些信息包含在SLAM里
  • use_nav_sat: 是否使用gps数据。如果启用,将订阅sensor_msgs/NavSatFix的话题,比如fix. 应当提供导航数据,将用于全局SLAM
  • use_landmarks: 如果启用,订阅cartographer_ros_msgs/LandmarkList的话题,比如landmarks. 应当提供Landmarks信息,这些信息包含在SLAM里

  • use_pose_extrapolator: 默认false. 发布tf时是使用 pose_extrapolator推断的位姿还是前端计算出来的位姿

1
2
3
4
stamped_transform.header.stamp =
node_options_.use_pose_extrapolator
? ToRos(now)
: ToRos(trajectory_data.local_slam_data->time);

旧版本没有这个参数,直接使用了now。这个参数认为位姿估计器很精确,但前提是雷达频率高,时间间隔短。最好是使用前端的时间戳

  • publish_frame_projected_to_2d: 默认false. 发布TF变换时,是否将tracking在Local坐标系中的坐标投影到2D平面上,这只是个显示功能,不影响SLAM。
  • publish_tracked_pose: 是否发布话题tracked_pose,也就是tracking坐标系在map坐标系的位姿,朝向与imu_link的x轴重合

num组

Cartographer可以订阅的主题有三种,我们一般用scan,还可以用echoespoints2,这三个是互斥的。分别对应lua中的num_laser_scans, num_multi_echo_laser_scans,num_point_clouds. 这三个参数必须都是 >= 0 且三者之和 >=1 代码在ComputeRepeatedTopicNames

lua中将num_laser_scans设置为1,则scan将用作SLAM的输入,如果num_laser_scans大于1,则多个编号的扫描主题(即scan_1,scan_2,scan_3,……直到并包括num_laser_scans)将用作SLAM的输入.

num_point_clouds为1时,默认订阅points2话题的数据

同理,如果将num_multi_echo_laser_scans设置为1,则echoes做输入,但仅使用第一个回声,如果大于1,则多个编号的回声主题(即echoes_1,echoes_2,echoes_3,……直到并包括num_multi_echo_laser_scans)将用作SLAM的输入。echoes的消息类型为sensor_msgs/MultiEchoLaserScan,不同之处在于sensor_msgs/LaserEcho[] rangessensor_msgs/LaserEcho[] intensities

首先需要雷达支持多echo,即每个脉冲发出以后,会有多个echo返回。我们知道一般雷达要避免扫描玻璃,因为laser会穿透过去,但多echo雷达不仅可以获得玻璃返回的echo,也能获得玻璃后面的墙返回的echo,这样我们就获得不同深度的信息,对建图定位的帮助更大。

points2也是这样,消息类型sensor_msgs/PointCloud2num_point_clouds适用于多线雷达,对于单线,设置为0

  • num_subdivisions_per_laser_scan: 将雷达一帧的数据拆分成几次发出来,必须>=1,默认10。在SensorBridge::HandleLaserScan中调用, 对点云points细分。比如雷达scan有200束激光,本参数为10,那么转换成点云后,对点云取很多小段处理:(0,20)、(20,40)……(190,200)。 对于普通雷达来说,此处为1即可

period 组

都在Node的构造函数里,是ROS定时器的发布间隔

  • lookup_transform_timeout_sec: 使用tf2查找tracking_frame和雷达坐标系变换的超时秒数,在函数TfBridge::LookupToTracking
  • submap_publish_period_sec: 发布话题submap_list的间隔
  • posepublish_period_sec: 对应`publish_local_trajectory_data_timerNode::PublishLocalTrajectoryData`. 例如5e-3,对应tf发布频率为200Hz
  • trajectory_publish_period_sec: 发布轨迹节点和Landmark的时间间隔,对应PublishTrajectoryNodeListPublishLandmarkPosesList

ratio 组

5种观测的权重比

  • rangefinder_sampling_ratio: Fixed ratio sampling for range finders messages.

  • odometry_sampling_ratio: Fixed ratio sampling for odometry messages. 如odom的数据非常不准,可以设置为0.3,以减小odom对整体优化的影响

  • fixed_frame_sampling_ratio: Fixed ratio sampling for fixed frame messages.

  • imu_sampling_ratio: Fixed ratio sampling for IMU messages.

  • landmarks_sampling_ratio: Fixed ratio sampling for landmarks messages.

options结束后,一般有一句:MAP_BUILDER.use_trajectory_builder_2d = true,这是因为map_builder.lua中的这个参数设置为false了,我们在这里可以重新赋值,选择使用2D还是3D

不使用机器人的IMU和Odom

1
2
3
4
5
6
7
8
map_frame = "map",
tracking_frame = "base_footprint",
published_frame = "base_footprint",
odom_frame = "odom",
provide_odom_frame = true,
publish_frame_projected_to_2d = false,
use_odometry = false,
TRAJECTORY_BUILDER_2D.use_imu_data = false --默认true

进行2d slam时,carto的默认配置是使用imu的,所以如果没有imu就要TRAJECTORY_BUILDER_2D.use_imu_data = false,否则会一直等待imu的数据而进行不下去。而3D slam 必须使用imu,所以不必修改这个参数。

  • 为什么3D必须有IMU,而2D可以不用?

在2D中,Cartographer支持运行相关的扫描匹配器,用于局部SLAM中寻找循环关闭的约束条件。它的计算代价很大,但通常会使odometry或IMU数据的加入变得不必要。2D也有假设平坦世界的好处,也就是说,上升是隐式定义的。
在三维中,IMU主要用于测量重力。重力在测量中是一个很有用的量,因为它不漂移,而且是一个非常强的信号,而且通常包含了大部分所要测量的加速度。

Node::LaunchSubscribers函数中有一段:

1
2
3
4
if (node_options_.map_builder_options.use_trajectory_builder_3d() ||
(node_options_.map_builder_options.use_trajectory_builder_2d() &&
options.trajectory_builder_options.trajectory_builder_2d_options()
.use_imu_data() ) )

显然源码里已经做了规定

  • 屏蔽机器人的里程计

如果我们不想使用轮式里程计, cartographer的lua无法屏蔽里程计,只能自己修改机器人的程序,不让它发布odom话题和odom--->base_footprint的tf变换。如果不修改,使用时会发现tf变换一会儿由 cartographer发布,一会儿由机器人程序发布,千万不能由两个节点发布同一个tf变换,从rviz看上去,RobotModel和LaserScan摇晃地很厉害。

这里有一个技巧, 观察一个tf变换是否由两个节点发布,用rosrun tf view_frame是看不出来的,应该用rosrun rqt_tf_tree rqt_tf_tree,然后用刷新按钮观察。

如果不用IMU,Odom + Lidar在局部存在纠偏失败的可能。 但是在里程计与imu不准的情况下,使用imu和odom反而建图效果会更差

使用机器人的odom和imu,lua做如下设置:

1
2
3
4
5
6
7
map_frame = "map",
tracking_frame = "imu",
published_frame = "odom",
odom_frame = "odom",
provide_odom_frame = false,
publish_frame_projected_to_2d = false,
use_odometry = true,

一开始,我增加了参数TRAJECTORY_BUILDER_2D.num_accumulated_range_data = 10,结果出现了scan一直在转的情况,使用tf_echo map和laser坐标系的关系,发现y位移一直在增大,但x z基本不变。去掉这个参数后,不再一直转了,但是过了几分钟还是有所偏,地图还出现了重影,这说明是机器人的里程计误差问题,需要校准,这个参数应该是放大了这种现象。

如果不想每过一段时间就校准,那么odombase_link的tf就用cartographer的,因为它有重定位,累计误差比较小,而且可以得到修正

对是否使用odom的两套程序如下:
不用odom的程序组合.png

使用机器人odom的程序组合.png
查看节点cartographer_node是否订阅了IMU和Odom,检查是否用到了它们

问题

  • 使用IMU后,有时启动时会报警:
    启动cartographer报错 1.png
    启动cartographer报错 2.png
    出问题的代码在cartographer::mapping::ImuTracker::AddImuLinearAccelerationObservation()。启动一下imu程序,如果rostopic echo /xqserial_server/IMU/linear_acceleration就会发现,imu线加速度开始为0,过了一秒左右才有数据,这应该是节点通信的问题。所以cartographer读取到的线加速度全是0,在程序里就会报错。此时再重启就没事了

  • 建图时地图围绕原点转圈,画出来的是一团黑,可能是用到的IMU的加速度有问题,需要校准IMU。还有可能是ceres的平移和旋转的权重没有进行重新配置。

  • 如果出现下面的输出,一般是scan话题没有订阅到:

    1
    [ WARN][/cartographer_node] [ScopedRosLogSink::send] line_55  W0711 20:05:58.000000 12245 ordered_multi_queue.cc:155] Queue waiting for data: (0, scan)

    正确的是这样:

    1
    [ INFO][/cartographer_node] [ScopedRosLogSink::send] line_51  I0711 20:14:56.000000 25541 ordered_multi_queue.cc:172] All sensor data for trajectory 0 is available starting at '637300664959145564'.
  • 常常启动后出现这个报警:
    tf报警.png
    这其实是tf坐标系的问题,cartographer源码里lookupTransform写的不好,不管也可以,详细分析可见

tf报警:Lookup would require extrapolation into the past

  • 机器人在地图中的位置不稳定,有轻微摆动,tf_echo如下:

base_footprint在map中的坐标.png
yaw有跳变, 判断是里程计累计误差

  • cartographer对雷达频率要求比较高,20Hz以上比较好,当频率达到30hz时,做纯旋转运动时不会产生地图的偏移。因为只有频率越高,2帧间的时间越短,误差才能越小。
  • 如果雷达比较差,地图边界会比较粗糙,用robosense雷达明显效果好

map_builder.lua 和 trajectory_builder.lua

内容只有几行:

1
2
3
4
5
6
7
8
include "pose_graph.lua"

MAP_BUILDER = {
use_trajectory_builder_2d = false,
use_trajectory_builder_3d = false,
num_background_threads = 4,
pose_graph = POSE_GRAPH,
}

map_builder.lua内容太简单了,配置是使用trajectory_build_2d还是trajectory_build_3d,以及后端使用的线程数。 use_trajectory_builder_2d在上面讲过改为true,其他一般不动,如果CPU性能好,可以增大num_background_threads

1
2
3
4
5
6
7
8
include "trajectory_builder_2d.lua"
include "trajectory_builder_3d.lua"

TRAJECTORY_BUILDER = {
trajectory_builder_2d = TRAJECTORY_BUILDER_2D,
trajectory_builder_3d = TRAJECTORY_BUILDER_3D,
pure_localization = false,
}

trajectory_builder.lua更简单,只有一个pure_localization区分是否使用carto用于机器人纯定位