-
Notifications
You must be signed in to change notification settings - Fork 90
/
component_clustering.cpp
455 lines (412 loc) · 19.2 KB
/
component_clustering.cpp
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
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
#include <array>
#include <pcl/io/pcd_io.h>
#include <nav_msgs/OccupancyGrid.h>
#include "component_clustering.h"
using namespace std;
using namespace pcl;
//int numGrid = 2;
float roiM = 50; // 限制周围距离25m
int kernelSize = 3;
// 下面什么参数?
double g_resolution = 1.0;
int g_cell_width =50; // 宽
int g_cell_height=50;
double g_offset_x=0;
double g_offset_y = 25;
double g_offset_z = -2;
double HEIGHT_LIMIT = 0.1; // from sensor
double CAR_LENGTH = 4.5; // 车的宽高
double CAR_WIDTH = 2;
//costmap paramter
// 初始化网格Grid状态
void mapCartesianGrid(PointCloud<PointXYZ>::Ptr elevatedCloud,
array<array<int, numGrid>, numGrid> & cartesianData){
array<array<int, numGrid>, numGrid> gridNum{}; // gridNum 此数组专门统计落在每个grid的点云数, gridNums[250][250]是指: elevatedCloud点的XY平面离散为m×n单元的网格(见paper图 Figure4-5)
for(int cellX = 0; cellX < numGrid; cellX++){ // cellX
for(int cellY = 0; cellY < numGrid; cellY++){ // cellY
gridNum[cellX][cellY] = 0; // 全部填充初始化为0
}
}
// elevatedCloud 映射到笛卡尔坐标系 //并 统计落在这个grid的有多少个点!!!
for(int i = 0; i < elevatedCloud->size(); i++){ // 遍历高点数
float x = elevatedCloud->points[i].x; // x(-15, -5),y(-50, 50)
float y = elevatedCloud->points[i].y;
float xC = x+roiM/2; // float roiM = 50;(0~50)
float yC = y+roiM/2; // (0~50)
// exclude outside roi points 排除外部roi points x,y属于(-25, 25)下面才继续执行
if(xC < 0 || xC >= roiM || yC < 0 || yC >=roiM) continue; // continue后,下面不执行。gridNum[xI][yI] 值不变 限制范围(0,50)
int xI = floor(numGrid*xC/roiM); // xI .yI const int numGrid = 250; floor(x)返回的是小于或等于x的最大整数
int yI = floor(numGrid*yC/roiM); // 50x50 映射到→250x250
gridNum[xI][yI] = gridNum[xI][yI] + 1; // 统计落在这个grid的有多少个点!!!
// cout << "gridNum[xI][yI]: " << gridNum[xI][yI] << "-------------统计落在这个grid的有多少个点!!!------------" << endl; // gridNum[xI][yI]
// cartesianData[xI][yI] = -1;
// if(xI == 0)
// {
// if(yI == 0)
// {
// cartesianData[xI+1][yI] = -1;
// cartesianData[xI][yI+1] = -1;
// cartesianData[xI+1][yI+1] = -1;
// }
// else if(yI < numGrid - 1)
// {
// cartesianData[xI][yI-1] = -1;
// cartesianData[xI][yI+1] = -1;
// cartesianData[xI+1][yI-1] = -1;
// cartesianData[xI+1][yI] = -1;
// cartesianData[xI+1][yI+1] = -1;
// }
// else if(yI == numGrid - 1)
// {
// cartesianData[xI][yI-1] = -1;
// cartesianData[xI+1][yI-1] = -1;
// cartesianData[xI+1][yI] = -1;
// }
// }
// else if(xI < numGrid - 1)
// {
// if(yI == 0)
// {
// cartesianData[xI-1][yI] = -1;
// cartesianData[xI-1][yI+1] = -1;
// cartesianData[xI][yI+1] = -1;
// cartesianData[xI+1][yI] = -1;
// cartesianData[xI+1][yI+1] = -1;
// }
// else if(yI < numGrid - 1)
// {
// cartesianData[xI-1][yI-1] = -1;
// cartesianData[xI-1][yI] = -1;
// cartesianData[xI-1][yI+1] = -1;
// cartesianData[xI][yI-1] = -1;
// cartesianData[xI][yI+1] = -1;
// cartesianData[xI+1][yI-1] = -1;
// cartesianData[xI+1][yI] = -1;
// cartesianData[xI+1][yI+1] = -1;
// }
// else if(yI == numGrid - 1)
// {
// cartesianData[xI-1][yI-1] = -1;
// cartesianData[xI-1][yI] = -1;
// cartesianData[xI][yI-1] = -1;
// cartesianData[xI+1][yI-1] = -1;
// cartesianData[xI+1][yI] = -1;
// }
// }
// else if(xI == numGrid - 1)
// {
// if(yI == 0)
// {
// cartesianData[xI-1][yI] = -1;
// cartesianData[xI-1][yI+1] = -1;
// cartesianData[xI][yI+1] = -1;
// }
// else if(yI < numGrid - 1)
// {
// cartesianData[xI-1][yI-1] = -1;
// cartesianData[xI-1][yI] = -1;
// cartesianData[xI-1][yI+1] = -1;
// cartesianData[xI][yI-1] = -1;
// cartesianData[xI][yI+1] = -1;
// }
// else if(yI == numGrid - 1)
// {
// cartesianData[xI-1][yI-1] = -1;
// cartesianData[xI-1][yI] = -1;
// cartesianData[xI][yI-1] = -1;
// }
// }
// int a = 0;
}
// 将x,y位置的单个单元格选作中心单元格,并且clusterID计数器加1。
// 然后所有相邻的相邻像元(即x-1,y + 1,x,y +1,x +1,y +1 x -1,y,x +1,y,x -1,y -1,x,检查y − 1,x + 1,y + 1)的占用状态,并用当前集群ID标记。
// 对m×n网格中的每个x,y重复此过程,直到为所有非空群集分配了ID。
for(int xI = 0; xI < numGrid; xI++){ // const int numGrid = 250;
for(int yI = 0; yI < numGrid; yI++){
if(gridNum[xI][yI] > 1){ // 一个点的直接舍弃?
cartesianData[xI][yI] = -1; // 网格分配有2种初始状态,分别为空(0),已占用(-1)和已分配。随后,将x,y位置的单个单元格选作中心单元格,并且clusterID计数器加1
//下面为设置当前点的周围点数值为-1
if(xI == 0)
{
if(yI == 0)
{
cartesianData[xI+1][yI] = -1; // 角相邻的3个相邻像元
cartesianData[xI][yI+1] = -1;
cartesianData[xI+1][yI+1] = -1;
}
else if(yI < numGrid - 1)
{
cartesianData[xI][yI-1] = -1; // 边有5个相邻点
cartesianData[xI][yI+1] = -1;
cartesianData[xI+1][yI-1] = -1;
cartesianData[xI+1][yI] = -1;
cartesianData[xI+1][yI+1] = -1;
}
else if(yI == numGrid - 1) // 角相邻的3个相邻像元
{
cartesianData[xI][yI-1] = -1;
cartesianData[xI+1][yI-1] = -1;
cartesianData[xI+1][yI] = -1;
}
}
else if(xI < numGrid - 1)
{
if(yI == 0)
{
cartesianData[xI-1][yI] = -1;
cartesianData[xI-1][yI+1] = -1;
cartesianData[xI][yI+1] = -1;
cartesianData[xI+1][yI] = -1;
cartesianData[xI+1][yI+1] = -1;
}
else if(yI < numGrid - 1) // 一般情况四周有8个相邻点
{
cartesianData[xI-1][yI-1] = -1;
cartesianData[xI-1][yI] = -1;
cartesianData[xI-1][yI+1] = -1;
cartesianData[xI][yI-1] = -1;
cartesianData[xI][yI+1] = -1;
cartesianData[xI+1][yI-1] = -1;
cartesianData[xI+1][yI] = -1;
cartesianData[xI+1][yI+1] = -1;
}
else if(yI == numGrid - 1)
{
cartesianData[xI-1][yI-1] = -1;
cartesianData[xI-1][yI] = -1;
cartesianData[xI][yI-1] = -1;
cartesianData[xI+1][yI-1] = -1;
cartesianData[xI+1][yI] = -1;
}
}
else if(xI == numGrid - 1)
{
if(yI == 0)
{
cartesianData[xI-1][yI] = -1;
cartesianData[xI-1][yI+1] = -1;
cartesianData[xI][yI+1] = -1;
}
else if(yI < numGrid - 1)
{
cartesianData[xI-1][yI-1] = -1;
cartesianData[xI-1][yI] = -1;
cartesianData[xI-1][yI+1] = -1;
cartesianData[xI][yI-1] = -1;
cartesianData[xI][yI+1] = -1;
}
else if(yI == numGrid - 1)
{
cartesianData[xI-1][yI-1] = -1;
cartesianData[xI-1][yI] = -1;
cartesianData[xI][yI-1] = -1;
}
}
}
}
}
// for(int xI = 0; xI < numGrid; xI++){ // const int numGrid = 250;
// for(int yI = 0; yI < numGrid; yI++){
// cout << " cartesianData[xI][yI] is "<< xI<<" " << yI <<" " << cartesianData[xI][yI]<< "========设置为-1========" <<endl;
// }}
}
// findComponent会引用search函数 聚类 图搜索 这是什么聚类方法???
void search(array<array<int, numGrid>, numGrid> & cartesianData, int clusterId, int cellX, int cellY){ // cellX(0-249), cellY(0-249)
cartesianData[cellX][cellY] = clusterId; // 赋值,将周边邻居值赋值同样的clusterId
int mean = kernelSize/2; // kernelSize = 3; mean = 1
for (int kX = 0; kX < kernelSize; kX++){ // kernelSize = 3;循环3次
int kXI = kX-mean; // 0, -1 , 1 // cout << "kXI is "<<kXI<<endl;
if((cellX + kXI) < 0 || (cellX + kXI) >= numGrid) continue; // numGrid = 250;
for( int kY = 0; kY < kernelSize;kY++){
int kYI = kY-mean; // 减去均值?????
if((cellY + kYI) < 0 || (cellY + kYI) >= numGrid) continue;
if(cartesianData[cellX + kXI][cellY + kYI] == -1){
search(cartesianData, clusterId, cellX +kXI, cellY + kYI); // 循环搜索
}
}
}
}
// 对m×n网格中的每个x,y重复此过程,直到为所有非空cluster分配了ID。
void findComponent(array<array<int, numGrid>, numGrid> & cartesianData, int &clusterId){
for(int cellX = 0; cellX < numGrid; cellX++){ // 循环每个点 numGrid = 250;
for(int cellY = 0; cellY < numGrid; cellY++){
// cout << "cartesianData[cellX][cellY] is "<< cellX<<" " << cellY <<" " << cartesianData[cellX][cellY] <<endl; // 大多数是0??为什么
if(cartesianData[cellX][cellY] == -1){ // 随后,将x,y位置的单个单元格选作中心单元格,并且clusterID计数器加1 (网格分配有2种初始状态,分别为空(0),已占用(-1))
clusterId ++; // 对m×n网格中的每个x,y重复此过程,直到为所有非空cluster分配了ID。 // cout << "clusterId is "<< clusterId <<endl; // 特别少 初始聚类数量
search(cartesianData, clusterId, cellX, cellY); // 对每一个点进行搜索 cellX(0-249), cellY(0-249)
}
}
}
}
// object_tracking/src/cluster/main.cpp会引用此函数
void componentClustering(PointCloud<pcl::PointXYZ>::Ptr elevatedCloud,
array<array<int, numGrid>, numGrid> & cartesianData,
int & numCluster){
// map 120m radius data(polar grid data) into 100x100 cartesian grid, parameter might need to be modified
// 将120m半径数据(极坐标数据)映射到100x100笛卡尔网格中,可能需要修改参数
// in this case 30mx30m with 100x100x grid 在这种情况下,30mx30m带有100x100x网格
mapCartesianGrid(elevatedCloud, cartesianData); // 第一步设置网格Grid状态 网格数组:cartesianData
findComponent(cartesianData, numCluster); // 第二步
}
// void makeClusteredCloud(PointCloud<pcl::PointXYZ>::Ptr& elevatedCloud,
// array<array<int, numGrid>, numGrid> cartesianData,
// PointCloud<pcl::PointXYZRGB>::Ptr& clusterCloud){
// array<array<int, numGrid>, numGrid> is_obs{0};
// for(int i = 0; i < elevatedCloud->size(); i++){
// float x = elevatedCloud->points[i].x;
// float y = elevatedCloud->points[i].y;
// float z = elevatedCloud->points[i].z;
// float xC = x+roiM/2;
// float yC = y+roiM/2;
// // exclude outside roi points
// if(xC < 0 || xC >= roiM || yC < 0 || yC >=roiM) continue;
// int xI = floor(numGrid*xC/roiM);
// int yI = floor(numGrid*yC/roiM);
// int clusterNum;
// if(is_obs[xI][yI] == 1)continue;
// else
// {
// clusterNum = cartesianData[xI][yI];
// is_obs[xI][yI] == 1;
// }
// if(clusterNum != 0){
// PointXYZRGB o;
// o.x = floor(x) + grid_size/2;
// o.y = floor(y) + grid_size/2;
// o.z = -1;
// o.r = (500*clusterNum)%255;
// o.g = (100*clusterNum)%255;
// o.b = (150*clusterNum)%255;
// clusterCloud->push_back(o);
// }
// }
// }
// object_tracking/src/cluster/main.cpp会引用此函数
void makeClusteredCloud(PointCloud<pcl::PointXYZ>::Ptr& elevatedCloud,
array<array<int, numGrid>, numGrid> cartesianData,
PointCloud<pcl::PointXYZ>::Ptr& clusterCloud){
for(int i = 0; i < elevatedCloud->size(); i++){
float x = elevatedCloud->points[i].x;
float y = elevatedCloud->points[i].y;
float z = elevatedCloud->points[i].z;
float xC = x+roiM/2;
float yC = y+roiM/2;
// exclude outside roi points
if(xC < 0 || xC >= roiM || yC < 0 || yC >=roiM) continue;
int xI = floor(numGrid*xC/roiM); // (0~249)
int yI = floor(numGrid*yC/roiM); // (0~249)
// cout << "xI is "<< xI <<endl;
// cout << "yI is "<< yI <<endl;
// cout << "cartesianData is "<< cartesianData[xI][yI]<<endl; // (1,2,3,4,...,numCluster)
int clusterNum = cartesianData[xI][yI]; // 数值 每一点云点对应的栅格聚类数字标签
if(clusterNum != 0){
PointXYZ o;
o.x = grid_size*xI - roiM/2 + grid_size/2; // 网格大小?? roiM = 50 grid_size = (0.200000003F)
o.y = grid_size*yI - roiM/2 + grid_size/2; // 转换成(-25 ~ 25)范围
o.z = -1; // 高度统一设置为-1
// o.r = (500*clusterNum)%255; // 不同类不同颜色 error: ‘struct pcl::PointXYZ’ has no member named ‘r’,用pcl::PointXYZRGBA?
// o.g = (100*clusterNum)%255;
// o.b = (150*clusterNum)%255;
clusterCloud->push_back(o); //
}
}
}
void setObsMsg(PointCloud<pcl::PointXYZ>::Ptr& elevatedCloud,
array<array<int, numGrid>, numGrid> cartesianData,
object_tracking::ObstacleList &clu_obs)
{
// array<array<int, numGrid>, numGrid> is_obs{0};
for(int i = 0; i < elevatedCloud->size(); i++){
float x = elevatedCloud->points[i].x;
float y = elevatedCloud->points[i].y;
float z = elevatedCloud->points[i].z;
float xC = x+roiM/2;
float yC = y+roiM/2;
// exclude outside roi points
if(xC < 0 || xC >= roiM || yC < 0 || yC >=roiM) continue;
int xI = floor(numGrid*xC/roiM);
int yI = floor(numGrid*yC/roiM);
// if(is_obs[xI][yI] == 1)continue;
int clusterNum = cartesianData[xI][yI];
// is_obs[xI][yI] == 1;
if(clusterNum != 0){
object_tracking::Obstacle obs_list;
obs_list.x = grid_size*xI - roiM/2 + grid_size/2;
obs_list.y = grid_size*yI - roiM/2 + grid_size/2;
obs_list.z = -1;
obs_list.cluster = clusterNum;
clu_obs.header.frame_id = elevatedCloud->header.frame_id;
clu_obs.cellLength = grid_size;
clu_obs.cellWidth = grid_size;
clu_obs.obstacles.push_back(obs_list);
cartesianData[xI][yI] = 0;
}
}
}
//void makeClusterVector(PointCloud<pcl::PointXYZ>::Ptr& elevatedCloud,
// array<array<int, numGrid>, numGrid> cartesianData,
// vector<PointCloud<pcl::PointXYZ>>& clusteredObjects){
// for(int i = 0; i < elevatedCloud->size(); i++){
// float x = elevatedCloud->points[i].x;
// float y = elevatedCloud->points[i].y;
// float z = elevatedCloud->points[i].z;
// float xC = x+roiM/2;
// float yC = y+roiM/2;
// // exclude outside roi points
// if(xC < 0 || xC >= roiM || yC < 0 || yC >=roiM) continue;
// int xI = floor(numGrid*xC/roiM);
// int yI = floor(numGrid*yC/roiM);
//
// int clusterNum = cartesianData[xI][yI];
// if(clusterNum != 0){
// PointXYZRGB o;
// o.x = x;
// o.y = y;
// o.z = z;
// o.r = (500*clusterNum)%255;
// o.g = (100*clusterNum)%255;
// o.b = (150*clusterNum)%255;
//// clusterCloud->push_back(o);
// }
// }
//}
// object_tracking/src/cluster/main.cpp会引用此函数
void setOccupancyGrid(nav_msgs::OccupancyGrid *og)
{
og->info.resolution = g_resolution;
og->info.width = g_cell_width;
og->info.height = g_cell_height;
og->info.origin.position.x = (-1) * (g_cell_width / 2.0) * g_resolution + g_offset_x;
og->info.origin.position.y = (-1) * (g_cell_height / 2.0) * g_resolution + g_offset_y;
og->info.origin.position.z = g_offset_z;
og->info.origin.orientation.x = 0.0;
og->info.origin.orientation.y = 0.0;
og->info.origin.orientation.z = 0.0;
og->info.origin.orientation.w = 1.0;
}
// object_tracking/src/cluster/main.cpp会引用此函数 代价地图
std::vector<int> createCostMap(const pcl::PointCloud<pcl::PointXYZ> &scan)
{
std::vector<int> cost_map(g_cell_width * g_cell_height, 0);
double map_center_x = (g_cell_width / 2.0) * g_resolution - g_offset_x;
double map_center_y = (g_cell_height / 2.0) * g_resolution - g_offset_y;
// scan points are in sensor frame
for (const auto &p : scan.points)
{
if (p.z > HEIGHT_LIMIT)
continue;
if (std::fabs(p.x) < CAR_LENGTH && std::fabs(p.y) < CAR_WIDTH)
continue;
// Calculate grid index
int grid_y = (p.x + map_center_x) / g_resolution;
int grid_x = (p.y + map_center_y) / g_resolution;
if (grid_y < 0 || grid_y >= g_cell_width || grid_x < 0 || grid_x >= g_cell_height)
continue;
int index = g_cell_width * grid_x + grid_y;
cost_map[index] += 15;
// Max cost value is 100
if (cost_map[index] > 100)
cost_map[index] = 100;
}
return cost_map;
}