-
Notifications
You must be signed in to change notification settings - Fork 94
/
adaptive_clustering.cpp
271 lines (232 loc) · 10.5 KB
/
adaptive_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
// Copyright (C) 2018 Zhi Yan and Li Sun
// This program is free software: you can redistribute it and/or modify it
// under the terms of the GNU General Public License as published by the Free
// Software Foundation, either version 3 of the License, or (at your option)
// any later version.
// This program is distributed in the hope that it will be useful, but WITHOUT
// ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
// FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
// more details.
// You should have received a copy of the GNU General Public License along
// with this program. If not, see <http://www.gnu.org/licenses/>.
// ROS
#include <ros/ros.h>
#include <sensor_msgs/PointCloud2.h>
#include <geometry_msgs/PoseArray.h>
#include <visualization_msgs/MarkerArray.h>
#include "adaptive_clustering/ClusterArray.h"
// PCL
#include <pcl_conversions/pcl_conversions.h>
#include <pcl/filters/voxel_grid.h>
#include <pcl/segmentation/extract_clusters.h>
#include <pcl/common/common.h>
#include <pcl/common/centroid.h>
//#define LOG
ros::Publisher cluster_array_pub_;
ros::Publisher cloud_filtered_pub_;
ros::Publisher pose_array_pub_;
ros::Publisher marker_array_pub_;
bool print_fps_;
int leaf_;
float z_axis_min_;
float z_axis_max_;
int cluster_size_min_;
int cluster_size_max_;
const int region_max_ = 10; // Change this value to match how far you want to detect.
int regions_[100];
int frames; clock_t start_time; bool reset = true;//fps
void pointCloudCallback(const sensor_msgs::PointCloud2::ConstPtr& ros_pc2_in) {
if(print_fps_)if(reset){frames=0;start_time=clock();reset=false;}//fps
/*** Convert ROS message to PCL ***/
pcl::PointCloud<pcl::PointXYZI>::Ptr pcl_pc_in(new pcl::PointCloud<pcl::PointXYZI>);
pcl::fromROSMsg(*ros_pc2_in, *pcl_pc_in);
/*** Downsampling ground & ceiling removal ***/
pcl::IndicesPtr pc_indices(new std::vector<int>);
for(int i = 0; i < pcl_pc_in->size(); i) {
if(i % leaf_ == 0) {
if(pcl_pc_in->points[i].z >= z_axis_min_ && pcl_pc_in->points[i].z <= z_axis_max_) {
pc_indices->push_back(i);
}
}
}
/*** Divide the point cloud into nested circular regions ***/
boost::array<std::vector<int>, region_max_> indices_array;
for(int i = 0; i < pc_indices->size(); i ) {
float range = 0.0;
for(int j = 0; j < region_max_; j ) {
float d2 = pcl_pc_in->points[(*pc_indices)[i]].x * pcl_pc_in->points[(*pc_indices)[i]].x
pcl_pc_in->points[(*pc_indices)[i]].y * pcl_pc_in->points[(*pc_indices)[i]].y
pcl_pc_in->points[(*pc_indices)[i]].z * pcl_pc_in->points[(*pc_indices)[i]].z;
if(d2 > range * range && d2 <= (range regions_[j]) * (range regions_[j])) {
indices_array[j].push_back((*pc_indices)[i]);
break;
}
range = regions_[j];
}
}
/*** Euclidean clustering ***/
float tolerance = 0.0;
std::vector<pcl::PointCloud<pcl::PointXYZI>::Ptr, Eigen::aligned_allocator<pcl::PointCloud<pcl::PointXYZI>::Ptr > > clusters;
for(int i = 0; i < region_max_; i ) {
tolerance = 0.1;
if(indices_array[i].size() > cluster_size_min_) {
boost::shared_ptr<std::vector<int> > indices_array_ptr(new std::vector<int>(indices_array[i]));
pcl::search::KdTree<pcl::PointXYZI>::Ptr tree(new pcl::search::KdTree<pcl::PointXYZI>);
tree->setInputCloud(pcl_pc_in, indices_array_ptr);
std::vector<pcl::PointIndices> cluster_indices;
pcl::EuclideanClusterExtraction<pcl::PointXYZI> ec;
ec.setClusterTolerance(tolerance);
ec.setMinClusterSize(cluster_size_min_);
ec.setMaxClusterSize(cluster_size_max_);
ec.setSearchMethod(tree);
ec.setInputCloud(pcl_pc_in);
ec.setIndices(indices_array_ptr);
ec.extract(cluster_indices);
for(std::vector<pcl::PointIndices>::const_iterator it = cluster_indices.begin(); it != cluster_indices.end(); it ) {
pcl::PointCloud<pcl::PointXYZI>::Ptr cluster(new pcl::PointCloud<pcl::PointXYZI>);
for(std::vector<int>::const_iterator pit = it->indices.begin(); pit != it->indices.end(); pit) {
cluster->points.push_back(pcl_pc_in->points[*pit]);
}
cluster->width = cluster->size();
cluster->height = 1;
cluster->is_dense = true;
clusters.push_back(cluster);
}
}
}
/*** Output ***/
if(cloud_filtered_pub_.getNumSubscribers() > 0) {
pcl::PointCloud<pcl::PointXYZI>::Ptr pcl_pc_out(new pcl::PointCloud<pcl::PointXYZI>);
sensor_msgs::PointCloud2 ros_pc2_out;
pcl::copyPointCloud(*pcl_pc_in, *pc_indices, *pcl_pc_out);
pcl::toROSMsg(*pcl_pc_out, ros_pc2_out);
cloud_filtered_pub_.publish(ros_pc2_out);
}
adaptive_clustering::ClusterArray cluster_array;
geometry_msgs::PoseArray pose_array;
visualization_msgs::MarkerArray marker_array;
for(int i = 0; i < clusters.size(); i ) {
if(cluster_array_pub_.getNumSubscribers() > 0) {
sensor_msgs::PointCloud2 ros_pc2_out;
pcl::toROSMsg(*clusters[i], ros_pc2_out);
cluster_array.clusters.push_back(ros_pc2_out);
}
if(pose_array_pub_.getNumSubscribers() > 0) {
Eigen::Vector4f centroid;
pcl::compute3DCentroid(*clusters[i], centroid);
geometry_msgs::Pose pose;
pose.position.x = centroid[0];
pose.position.y = centroid[1];
pose.position.z = centroid[2];
pose.orientation.w = 1;
pose_array.poses.push_back(pose);
#ifdef LOG
Eigen::Vector4f min, max;
pcl::getMinMax3D(*clusters[i], min, max);
std::cerr << ros_pc2_in->header.seq << " "
<< ros_pc2_in->header.stamp << " "
<< min[0] << " "
<< min[1] << " "
<< min[2] << " "
<< max[0] << " "
<< max[1] << " "
<< max[2] << " "
<< std::endl;
#endif
}
if(marker_array_pub_.getNumSubscribers() > 0) {
Eigen::Vector4f min, max;
pcl::getMinMax3D(*clusters[i], min, max);
visualization_msgs::Marker marker;
marker.header = ros_pc2_in->header;
marker.ns = "adaptive_clustering";
marker.id = i;
marker.type = visualization_msgs::Marker::LINE_LIST;
geometry_msgs::Point p[24];
p[0].x = max[0]; p[0].y = max[1]; p[0].z = max[2];
p[1].x = min[0]; p[1].y = max[1]; p[1].z = max[2];
p[2].x = max[0]; p[2].y = max[1]; p[2].z = max[2];
p[3].x = max[0]; p[3].y = min[1]; p[3].z = max[2];
p[4].x = max[0]; p[4].y = max[1]; p[4].z = max[2];
p[5].x = max[0]; p[5].y = max[1]; p[5].z = min[2];
p[6].x = min[0]; p[6].y = min[1]; p[6].z = min[2];
p[7].x = max[0]; p[7].y = min[1]; p[7].z = min[2];
p[8].x = min[0]; p[8].y = min[1]; p[8].z = min[2];
p[9].x = min[0]; p[9].y = max[1]; p[9].z = min[2];
p[10].x = min[0]; p[10].y = min[1]; p[10].z = min[2];
p[11].x = min[0]; p[11].y = min[1]; p[11].z = max[2];
p[12].x = min[0]; p[12].y = max[1]; p[12].z = max[2];
p[13].x = min[0]; p[13].y = max[1]; p[13].z = min[2];
p[14].x = min[0]; p[14].y = max[1]; p[14].z = max[2];
p[15].x = min[0]; p[15].y = min[1]; p[15].z = max[2];
p[16].x = max[0]; p[16].y = min[1]; p[16].z = max[2];
p[17].x = max[0]; p[17].y = min[1]; p[17].z = min[2];
p[18].x = max[0]; p[18].y = min[1]; p[18].z = max[2];
p[19].x = min[0]; p[19].y = min[1]; p[19].z = max[2];
p[20].x = max[0]; p[20].y = max[1]; p[20].z = min[2];
p[21].x = min[0]; p[21].y = max[1]; p[21].z = min[2];
p[22].x = max[0]; p[22].y = max[1]; p[22].z = min[2];
p[23].x = max[0]; p[23].y = min[1]; p[23].z = min[2];
for(int i = 0; i < 24; i ) {
marker.points.push_back(p[i]);
}
marker.scale.x = 0.02;
marker.color.a = 1.0;
marker.color.r = 0.0;
marker.color.g = 1.0;
marker.color.b = 0.5;
marker.lifetime = ros::Duration(0.1);
marker_array.markers.push_back(marker);
}
}
if(cluster_array.clusters.size()) {
cluster_array.header = ros_pc2_in->header;
cluster_array_pub_.publish(cluster_array);
}
if(pose_array.poses.size()) {
pose_array.header = ros_pc2_in->header;
pose_array_pub_.publish(pose_array);
}
if(marker_array.markers.size()) {
marker_array_pub_.publish(marker_array);
}
if(print_fps_)if( frames>10){std::cerr<<"[adaptive_clustering] fps = "<<float(frames)/(float(clock()-start_time)/CLOCKS_PER_SEC)<<", timestamp = "<<clock()/CLOCKS_PER_SEC<<std::endl;reset = true;}//fps
}
int main(int argc, char **argv) {
ros::init(argc, argv, "adaptive_clustering");
/*** Subscribers ***/
ros::NodeHandle nh;
ros::Subscriber point_cloud_sub = nh.subscribe<sensor_msgs::PointCloud2>("velodyne_points", 1, pointCloudCallback);
/*** Publishers ***/
ros::NodeHandle private_nh("~");
cluster_array_pub_ = private_nh.advertise<adaptive_clustering::ClusterArray>("clusters", 100);
cloud_filtered_pub_ = private_nh.advertise<sensor_msgs::PointCloud2>("cloud_filtered", 100);
pose_array_pub_ = private_nh.advertise<geometry_msgs::PoseArray>("poses", 100);
marker_array_pub_ = private_nh.advertise<visualization_msgs::MarkerArray>("markers", 100);
/*** Parameters ***/
std::string sensor_model;
private_nh.param<std::string>("sensor_model", sensor_model, "VLP-16"); // VLP-16, HDL-32E, HDL-64E
private_nh.param<bool>("print_fps", print_fps_, false);
private_nh.param<int>("leaf", leaf_, 1);
private_nh.param<float>("z_axis_min", z_axis_min_, -0.8);
private_nh.param<float>("z_axis_max", z_axis_max_, 2.0);
private_nh.param<int>("cluster_size_min", cluster_size_min_, 3);
private_nh.param<int>("cluster_size_max", cluster_size_max_, 2200000);
// Divide the point cloud into nested circular regions centred at the sensor.
// For more details, see our IROS-17 paper "Online learning for human classification in 3D LiDAR-based tracking"
if(sensor_model.compare("VLP-16") == 0) {
regions_[0] = 2; regions_[1] = 3; regions_[2] = 3; regions_[3] = 3; regions_[4] = 3;
regions_[5] = 3; regions_[6] = 3; regions_[7] = 2; regions_[8] = 3; regions_[9] = 3;
regions_[10]= 3; regions_[11]= 3; regions_[12]= 3; regions_[13]= 3;
} else if (sensor_model.compare("HDL-32E") == 0) {
regions_[0] = 4; regions_[1] = 5; regions_[2] = 4; regions_[3] = 5; regions_[4] = 4;
regions_[5] = 5; regions_[6] = 5; regions_[7] = 4; regions_[8] = 5; regions_[9] = 4;
regions_[10]= 5; regions_[11]= 5; regions_[12]= 4; regions_[13]= 5;
} else if (sensor_model.compare("HDL-64E") == 0) {
regions_[0] = 14; regions_[1] = 14; regions_[2] = 14; regions_[3] = 15; regions_[4] = 14;
} else {
ROS_FATAL("Unknown sensor model!");
}
ros::spin();
return 0;
}