测量模型主要用来做scan-match。
光束模型比较古老,实际已经不怎么使用,它的缺陷比较明显:在杂乱的环境(非结构化环境clutter)中,输入的小变化会导致输出的大变化。amcl中实现了这个模型,但是可以选择用还是不用
似然场模型不仅适应于结构化和非结构化的环境,而且在任何环境中的期望值对位姿都是平滑的,还可以通过查表的得到栅格的似然度。
工具函数和类
1 | // Transform from local to global coords (a + b) |
laserReceived 中的准备工作
这一段是紧接着laserReceived中运动模型的准备工作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
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76// 刚启动amcl时不执行,机器人移动后执行, update the filter
if(lasers_update_[laser_index]) // 在运动模型的准备工作里赋值true
{
AMCLLaserData ldata;
// 成员sensor是指向传感器的指针
ldata.sensor = lasers_[laser_index];
// 动态数组ranges的大小,可以用 rostopic echo --noarr /scan 获得
ldata.range_count = laser_scan->ranges.size();
// 雷达在base_link坐标系的最小和最大偏角
tf::Quaternion q;
// 获得雷达的扫描起始角度,例如思岚A2的是-3.124,带时间戳和坐标系名称
q.setRPY(0.0, 0.0, laser_scan->angle_min);
tf::Stamped<tf::Quaternion> min_q(q, laser_scan->header.stamp,
laser_scan->header.frame_id);
// angle_increment为角度分辨率,例如思岚A2的是0.017, inc_q: 起始角度+角度分辨率
q.setRPY(0.0, 0.0, laser_scan->angle_min + laser_scan->angle_increment为);
tf::Stamped<tf::Quaternion> inc_q(q, laser_scan->header.stamp,
laser_scan->header.frame_id);
try
{ // 获得两个角度在base_link坐标系中的Quaternion
tf_->transformQuaternion(base_frame_id_, min_q, min_q);
tf_->transformQuaternion(base_frame_id_, inc_q, inc_q);
}
catch(tf::TransformException& e)
{
ROS_WARN("Unable to transform min/max laser angles into base frame: %s",
e.what());
return;
}
// 现在是base_link中的起始yaw和偏航角分辨率,单位rad
double angle_min = tf::getYaw(min_q);
double angle_increment = tf::getYaw(inc_q) - angle_min;
// 把角度映射到[-pi ~ pi]的范围
angle_increment = fmod(angle_increment + 5*M_PI, 2*M_PI) - M_PI;
ROS_DEBUG("Laser %d angles in base frame: min: %.3f inc: %.3f", laser_index, angle_min, angle_increment);
// Apply range min/max thresholds, if the user supplied them
// 来自参数 laser_max_range 和 laser_min_range, 准备后面使用
if(laser_max_range_ > 0.0)
ldata.range_max = std::min(laser_scan->range_max, (float)laser_max_range_);
else
ldata.range_max = laser_scan->range_max;
double range_min;
if(laser_min_range_ > 0.0)
range_min = std::max(laser_scan->range_min, (float)laser_min_range_);
else
range_min = laser_scan->range_min;
// 二维数组,AMCLLaserData 的析构函数会释放这段内存
// 每行第1个元素是激光射程,第2个是相对机器人的夹角
ldata.ranges = new double[ldata.range_count][2];
ROS_ASSERT(ldata.ranges);
for(int i=0;i<ldata.range_count;i++)
{
// amcl还没有最小射程的概念,如果range的值不正常,小于最小值,则映射为最大值
// 雷达数据的赋值
if(laser_scan->ranges[i] <= range_min)
ldata.ranges[i][0] = ldata.range_max;
else // 射程的正常赋值,来自话题scan
ldata.ranges[i][0] = laser_scan->ranges[i];
// Compute bearing 夹角的赋值
ldata.ranges[i][1] = angle_min + (i * angle_increment);
}
// 核心函数, 更新传感器数据
lasers_[laser_index]->UpdateSensor(pf_, (AMCLSensorData*)&ldata);
lasers_update_[laser_index] = false; // 完成更新传感器数据,标志位变为false
pf_odom_pose_ = pose;
}
UpdateSensor函数
的调用过程:1
2
3bool AMCLLaser::UpdateSensor(pf_t *pf, AMCLSensorData *data)
// pf_sensor_model_fn_t是函数指针的类型
pf_update_sensor(pf, (pf_sensor_model_fn_t) LikelihoodFieldModel, data);
涉及两个函数: LikelihoodFieldModel
似然域模型,pf_update_sensor
粒子更新
LikelihoodFieldModel 函数
1 | double AMCLLaser::LikelihoodFieldModel(AMCLLaserData *data, pf_sample_set_t* set) |
大致的思想是这样:
不解的地方:测量模型的最后使用的公式是p += pz*pz*pz
,并不是书上的p *= pz
,怀疑3个pz对应 [x,y,θ]
sample->weight
在之前赋值为 1/max_particles
1 | // 将激光点的世界坐标转为栅格地图的坐标 |
公式 step = (laser_range_count - 1) / (max_beams - 1);
:
因为时间问题,不对所有点进行似然计算,而是间隔选点,step就是步长.
lser_rang_count
可以用rostopic echo --noarr /scan
得到,max_beams
由自己设置. 如果step小于1,程序里会设置为1.
因为寻找最近障碍物是最耗时的,可以将似然域预先计算好,搜索时直接查表即可。我理解的查表是查激光点在查栅格地图的坐标。
似然域模型的最后重新确定了每个粒子的重要性权重sample->weight
pf_update_sensor 函数
1 | // 根据观测值更新滤波器 |
代码比较简单,就是196页的AMCL算法的7~11行。 不解的地方是 sample->weight最后又除以了粒子总权重