main.cpp
Go to the documentation of this file.
1 #include <iostream>
2 #include <string.h>
3 #include <fstream>
4 #include <algorithm>
5 #include <iterator>
8 #include <opencv2/core/core.hpp>
9 #include <opencv2/highgui/highgui.hpp>
10 #include <opencv2/imgproc/imgproc.hpp>
11 #include <opencv2/video/video.hpp>
12 #include "opencv2/video/tracking.hpp"
13 #include <ros/ros.h>
14 #include <pcl/io/pcd_io.h>
15 #include <pcl/point_types.h>
16 #include "pcl_ros/point_cloud.h"
17 #include <geometry_msgs/Point.h>
18 #include <std_msgs/Float32MultiArray.h>
19 #include <std_msgs/Int32MultiArray.h>
20 
21 #include <sensor_msgs/PointCloud2.h>
23 #include <pcl/point_cloud.h>
24 #include <pcl/point_types.h>
25 #include <pcl/common/geometry.h>
26 #include <pcl/filters/extract_indices.h>
27 #include <pcl/filters/voxel_grid.h>
28 #include <pcl/features/normal_3d.h>
29 #include <pcl/kdtree/kdtree.h>
30 #include <pcl/sample_consensus/method_types.h>
31 #include <pcl/sample_consensus/model_types.h>
32 #include <pcl/segmentation/sac_segmentation.h>
33 #include <pcl/segmentation/extract_clusters.h>
34 #include <pcl/common/centroid.h>
35 
36 #include <visualization_msgs/MarkerArray.h>
37 #include <visualization_msgs/Marker.h>
38 #include <limits>
39 #include <utility>
40 
41 using namespace std;
42 using namespace cv;
43 
44 
46 
47  // KF init
48  int stateDim=4;// [x,y,v_x,v_y]//,w,h]
49  int measDim=2;// [z_x,z_y,z_w,z_h]
50  int ctrlDim=0;
51  cv::KalmanFilter KF0(stateDim,measDim,ctrlDim,CV_32F);
52  cv::KalmanFilter KF1(stateDim,measDim,ctrlDim,CV_32F);
53  cv::KalmanFilter KF2(stateDim,measDim,ctrlDim,CV_32F);
54  cv::KalmanFilter KF3(stateDim,measDim,ctrlDim,CV_32F);
55  cv::KalmanFilter KF4(stateDim,measDim,ctrlDim,CV_32F);
56  cv::KalmanFilter KF5(stateDim,measDim,ctrlDim,CV_32F);
57 
64 
66 
67  std::vector<geometry_msgs::Point> prevClusterCenters;
68 
69 
70  cv::Mat state(stateDim,1,CV_32F);
71  cv::Mat_<float> measurement(2,1);
72 
73  std::vector<int> objID;// Output of the data association using KF
74  // measurement.setTo(Scalar(0));
75 
76 bool firstFrame=true;
77 
78 // calculate euclidean distance of two points
79  double euclidean_distance(geometry_msgs::Point& p1, geometry_msgs::Point& p2)
80  {
81  return sqrt((p1.x - p2.x) * (p1.x - p2.x) + (p1.y - p2.y) * (p1.y - p2.y) + (p1.z - p2.z) * (p1.z - p2.z));
82  }
83 /*
84 //Count unique object IDs. just to make sure same ID has not been assigned to two KF_Trackers.
85 int countIDs(vector<int> v)
86 {
87  transform(v.begin(), v.end(), v.begin(), abs); // O(n) where n = distance(v.end(), v.begin())
88  sort(v.begin(), v.end()); // Average case O(n log n), worst case O(n^2) (usually implemented as quicksort.
89  // To guarantee worst case O(n log n) replace with make_heap, then sort_heap.
90 
91  // Unique will take a sorted range, and move things around to get duplicated
92  // items to the back and returns an iterator to the end of the unique section of the range
93  auto unique_end = unique(v.begin(), v.end()); // Again n comparisons
94  return distance(unique_end, v.begin()); // Constant time for random access iterators (like vector's)
95 }
96 */
97 
98 /*
99 
100 objID: vector containing the IDs of the clusters that should be associated with each KF_Tracker
101 objID[0] corresponds to KFT0, objID[1] corresponds to KFT1 etc.
102 */
103 
104 std::pair<int,int> findIndexOfMin(std::vector<std::vector<float> > distMat)
105 {
106  cout<<"findIndexOfMin cALLED\n";
107  std::pair<int,int>minIndex;
108  float minEl=std::numeric_limits<float>::max();
109  cout<<"minEl="<<minEl<<"\n";
110  for (int i=0; i<distMat.size();i++)
111  for(int j=0;j<distMat.at(0).size();j++)
112  {
113  if( distMat[i][j]<minEl)
114  {
115  minEl=distMat[i][j];
116  minIndex=std::make_pair(i,j);
117 
118  }
119 
120  }
121  cout<<"minIndex="<<minIndex.first<<","<<minIndex.second<<"\n";
122  return minIndex;
123 }
124 void KFT(const std_msgs::Float32MultiArray ccs)
125 {
126 
127 
128 
129  // First predict, to update the internal statePre variable
130 
131  std::vector<cv::Mat> pred{KF0.predict(),KF1.predict(),KF2.predict(),KF3.predict(),KF4.predict(),KF5.predict()};
132  //cout<<"Pred successfull\n";
133 
134  //cv::Point predictPt(prediction.at<float>(0),prediction.at<float>(1));
135  // cout<<"Prediction 1 ="<<prediction.at<float>(0)<<","<<prediction.at<float>(1)<<"\n";
136 
137  // Get measurements
138  // Extract the position of the clusters forom the multiArray. To check if the data
139  // coming in, check the .z (every third) coordinate and that will be 0.0
140  std::vector<geometry_msgs::Point> clusterCenters;//clusterCenters
141 
142  int i=0;
143  for (std::vector<float>::const_iterator it=ccs.data.begin();it!=ccs.data.end();it+=3)
144  {
145  geometry_msgs::Point pt;
146  pt.x=*it;
147  pt.y=*(it+1);
148  pt.z=*(it+2);
149 
150  clusterCenters.push_back(pt);
151 
152  }
153 
154  // cout<<"CLusterCenters Obtained"<<"\n";
155  std::vector<geometry_msgs::Point> KFpredictions;
156  i=0;
157  for (auto it=pred.begin();it!=pred.end();it++)
158  {
159  geometry_msgs::Point pt;
160  pt.x=(*it).at<float>(0);
161  pt.y=(*it).at<float>(1);
162  pt.z=(*it).at<float>(2);
163 
164  KFpredictions.push_back(pt);
165 
166  }
167  // cout<<"Got predictions"<<"\n";
168 
169 
170 
171  // Find the cluster that is more probable to be belonging to a given KF.
172  objID.clear();//Clear the objID vector
173  objID.resize(6);//Allocate default elements so that [i] doesnt segfault. Should be done better
174  // Copy clusterCentres for modifying it and preventing multiple assignments of the same ID
175  std::vector<geometry_msgs::Point> copyOfClusterCenters(clusterCenters);
176  std::vector<std::vector<float> > distMat;
177 
178  for(int filterN=0;filterN<6;filterN++)
179  {
180  std::vector<float> distVec;
181  for(int n=0;n<6;n++)
182  {
183  distVec.push_back(euclidean_distance(KFpredictions[filterN],copyOfClusterCenters[n]));
184  }
185 
186  distMat.push_back(distVec);
187  /*// Based on distVec instead of distMat (global min). Has problems with the person's leg going out of scope
188  int ID=std::distance(distVec.begin(),min_element(distVec.begin(),distVec.end()));
189  //cout<<"finterlN="<<filterN<<" minID="<<ID
190  objID.push_back(ID);
191  // Prevent assignment of the same object ID to multiple clusters
192  copyOfClusterCenters[ID].x=100000;// A large value so that this center is not assigned to another cluster
193  copyOfClusterCenters[ID].y=10000;
194  copyOfClusterCenters[ID].z=10000;
195  */
196  cout<<"filterN="<<filterN<<"\n";
197 
198 
199  }
200 
201  cout<<"distMat.size()"<<distMat.size()<<"\n";
202  cout<<"distMat[0].size()"<<distMat.at(0).size()<<"\n";
203  // DEBUG: print the distMat
204  for ( const auto &row : distMat )
205  {
206  for ( const auto &s : row ) std::cout << s << ' ';
207  std::cout << std::endl;
208  }
209 
210 
211 
212  for(int clusterCount=0;clusterCount<6;clusterCount++)
213  {
214  // 1. Find min(distMax)==> (i,j);
215  std::pair<int,int> minIndex(findIndexOfMin(distMat));
216  cout<<"Received minIndex="<<minIndex.first<<","<<minIndex.second<<"\n";
217  // 2. objID[i]=clusterCenters[j]; counter++
218  objID[minIndex.first]=minIndex.second;
219 
220  // 3. distMat[i,:]=10000; distMat[:,j]=10000
221  distMat[minIndex.first]=std::vector<float>(6,10000.0);// Set the row to a high number.
222  for(int row=0;row<distMat.size();row++)//set the column to a high number
223  {
224  distMat[row][minIndex.second]=10000.0;
225  }
226  // 4. if(counter<6) got to 1.
227  cout<<"clusterCount="<<clusterCount<<"\n";
228 
229  }
230 
231  // cout<<"Got object IDs"<<"\n";
232  //countIDs(objID);// for verif/corner cases
233 
234  //display objIDs
235  /* DEBUG
236  cout<<"objID= ";
237  for(auto it=objID.begin();it!=objID.end();it++)
238  cout<<*it<<" ,";
239  cout<<"\n";
240  */
241 
242  visualization_msgs::MarkerArray clusterMarkers;
243 
244  for (int i=0;i<6;i++)
245  {
246  visualization_msgs::Marker m;
247 
248  m.id=i;
249  m.type=visualization_msgs::Marker::CUBE;
250  m.header.frame_id="/map";
251  m.scale.x=0.3; m.scale.y=0.3; m.scale.z=0.3;
252  m.action=visualization_msgs::Marker::ADD;
253  m.color.a=1.0;
254  m.color.r=i%2?1:0;
255  m.color.g=i%3?1:0;
256  m.color.b=i%4?1:0;
257 
258  //geometry_msgs::Point clusterC(clusterCenters.at(objID[i]));
259  geometry_msgs::Point clusterC(KFpredictions[i]);
260  m.pose.position.x=clusterC.x;
261  m.pose.position.y=clusterC.y;
262  m.pose.position.z=clusterC.z;
263 
264  clusterMarkers.markers.push_back(m);
265  }
266 
267  prevClusterCenters=clusterCenters;
268 
269  markerPub.publish(clusterMarkers);
270 
271 
272 
273 
274  std_msgs::Int32MultiArray obj_id;
275  for(auto it=objID.begin();it!=objID.end();it++)
276  obj_id.data.push_back(*it);
277  // Publish the object IDs
278  objID_pub.publish(obj_id);
279  // convert clusterCenters from geometry_msgs::Point to floats
280  std::vector<std::vector<float> > cc;
281  for (int i=0;i<6;i++)
282  {
283  vector<float> pt;
284  pt.push_back(clusterCenters[objID[i]].x);
285  pt.push_back(clusterCenters[objID[i]].y);
286  pt.push_back(clusterCenters[objID[i]].z);
287 
288  cc.push_back(pt);
289  }
290  //cout<<"cc[5][0]="<<cc[5].at(0)<<"cc[5][1]="<<cc[5].at(1)<<"cc[5][2]="<<cc[5].at(2)<<"\n";
291  float meas0[2]={cc[0].at(0),cc[0].at(1)};
292  float meas1[2]={cc[1].at(0),cc[1].at(1)};
293  float meas2[2]={cc[2].at(0),cc[2].at(1)};
294  float meas3[2]={cc[3].at(0),cc[3].at(1)};
295  float meas4[2]={cc[4].at(0),cc[4].at(1)};
296  float meas5[2]={cc[5].at(0),cc[5].at(1)};
297 
298 
299 
300  // The update phase
301  cv::Mat meas0Mat=cv::Mat(2,1,CV_32F,meas0);
302  cv::Mat meas1Mat=cv::Mat(2,1,CV_32F,meas1);
303  cv::Mat meas2Mat=cv::Mat(2,1,CV_32F,meas2);
304  cv::Mat meas3Mat=cv::Mat(2,1,CV_32F,meas3);
305  cv::Mat meas4Mat=cv::Mat(2,1,CV_32F,meas4);
306  cv::Mat meas5Mat=cv::Mat(2,1,CV_32F,meas5);
307 
308 //cout<<"meas0Mat"<<meas0Mat<<"\n";
309 if (!(meas0Mat.at<float>(0,0)==0.0f || meas0Mat.at<float>(1,0)==0.0f))
310  Mat estimated0 = KF0.correct(meas0Mat);
311 if (!(meas1[0]==0.0f || meas1[1]==0.0f))
312  Mat estimated1 = KF1.correct(meas1Mat);
313 if (!(meas2[0]==0.0f || meas2[1]==0.0f))
314  Mat estimated2 = KF2.correct(meas2Mat);
315 if (!(meas3[0]==0.0f || meas3[1]==0.0f))
316  Mat estimated3 = KF3.correct(meas3Mat);
317 if (!(meas4[0]==0.0f || meas4[1]==0.0f))
318  Mat estimated4 = KF4.correct(meas4Mat);
319 if (!(meas5[0]==0.0f || meas5[1]==0.0f))
320  Mat estimated5 = KF5.correct(meas5Mat);
321 
322 
323  // Publish the point clouds belonging to each clusters
324 
325 
326  // cout<<"estimate="<<estimated.at<float>(0)<<","<<estimated.at<float>(1)<<"\n";
327  // Point statePt(estimated.at<float>(0),estimated.at<float>(1));
328 //cout<<"DONE KF_TRACKER\n";
329 
330 }
331 void publish_cloud(ros::Publisher& pub, pcl::PointCloud<pcl::PointXYZ>::Ptr cluster){
332  sensor_msgs::PointCloud2::Ptr clustermsg (new sensor_msgs::PointCloud2);
333  pcl::toROSMsg (*cluster , *clustermsg);
334  clustermsg->header.frame_id = "/map";
335  clustermsg->header.stamp = ros::Time::now();
336  pub.publish (*clustermsg);
337 
338 }
339 
340 
341 void cloud_cb (const sensor_msgs::PointCloud2ConstPtr& input)
342 
343 {
344  // cout<<"IF firstFrame="<<firstFrame<<"\n";
345  // If this is the first frame, initialize kalman filters for the clustered objects
346 if (firstFrame)
347 {
348  // Initialize 6 Kalman Filters; Assuming 6 max objects in the dataset.
349  // Could be made generic by creating a Kalman Filter only when a new object is detected
350 
351  float dvx=0.01f; //1.0
352  float dvy=0.01f;//1.0
353  float dx=1.0f;
354  float dy=1.0f;
355  KF0.transitionMatrix = *(Mat_<float>(4, 4) << dx,0,1,0, 0,dy,0,1, 0,0,dvx,0, 0,0,0,dvy);
356  KF1.transitionMatrix = *(Mat_<float>(4, 4) << dx,0,1,0, 0,dy,0,1, 0,0,dvx,0, 0,0,0,dvy);
357  KF2.transitionMatrix = *(Mat_<float>(4, 4) << dx,0,1,0, 0,dy,0,1, 0,0,dvx,0, 0,0,0,dvy);
358  KF3.transitionMatrix = *(Mat_<float>(4, 4) << dx,0,1,0, 0,dy,0,1, 0,0,dvx,0, 0,0,0,dvy);
359  KF4.transitionMatrix = *(Mat_<float>(4, 4) << dx,0,1,0, 0,dy,0,1, 0,0,dvx,0, 0,0,0,dvy);
360  KF5.transitionMatrix = *(Mat_<float>(4, 4) << dx,0,1,0, 0,dy,0,1, 0,0,dvx,0, 0,0,0,dvy);
361 
362  cv::setIdentity(KF0.measurementMatrix);
363  cv::setIdentity(KF1.measurementMatrix);
364  cv::setIdentity(KF2.measurementMatrix);
365  cv::setIdentity(KF3.measurementMatrix);
366  cv::setIdentity(KF4.measurementMatrix);
367  cv::setIdentity(KF5.measurementMatrix);
368  // Process Noise Covariance Matrix Q
369  // [ Ex 0 0 0 0 0 ]
370  // [ 0 Ey 0 0 0 0 ]
371  // [ 0 0 Ev_x 0 0 0 ]
372  // [ 0 0 0 1 Ev_y 0 ]
375  float sigmaP=0.01;
376  float sigmaQ=0.1;
377  setIdentity(KF0.processNoiseCov, Scalar::all(sigmaP));
378  setIdentity(KF1.processNoiseCov, Scalar::all(sigmaP));
379  setIdentity(KF2.processNoiseCov, Scalar::all(sigmaP));
380  setIdentity(KF3.processNoiseCov, Scalar::all(sigmaP));
381  setIdentity(KF4.processNoiseCov, Scalar::all(sigmaP));
382  setIdentity(KF5.processNoiseCov, Scalar::all(sigmaP));
383  // Meas noise cov matrix R
384  cv::setIdentity(KF0.measurementNoiseCov, cv::Scalar(sigmaQ));//1e-1
385  cv::setIdentity(KF1.measurementNoiseCov, cv::Scalar(sigmaQ));
386  cv::setIdentity(KF2.measurementNoiseCov, cv::Scalar(sigmaQ));
387  cv::setIdentity(KF3.measurementNoiseCov, cv::Scalar(sigmaQ));
388  cv::setIdentity(KF4.measurementNoiseCov, cv::Scalar(sigmaQ));
389  cv::setIdentity(KF5.measurementNoiseCov, cv::Scalar(sigmaQ));
390 
391 // Process the point cloud
392  pcl::PointCloud<pcl::PointXYZ>::Ptr input_cloud (new pcl::PointCloud<pcl::PointXYZ>);
393  pcl::PointCloud<pcl::PointXYZ>::Ptr clustered_cloud (new pcl::PointCloud<pcl::PointXYZ>);
394  /* Creating the KdTree from input point cloud*/
395  pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZ>);
396 
397  pcl::fromROSMsg (*input, *input_cloud);
398 
399  tree->setInputCloud (input_cloud);
400 
401 
402  std::vector<pcl::PointIndices> cluster_indices;
403  pcl::EuclideanClusterExtraction<pcl::PointXYZ> ec;
404  ec.setClusterTolerance (0.08);
405  ec.setMinClusterSize (10);
406  ec.setMaxClusterSize (600);
407  ec.setSearchMethod (tree);
408  ec.setInputCloud (input_cloud);
409  /* Extract the clusters out of pc and save indices in cluster_indices.*/
410  ec.extract (cluster_indices);
411 
412 
413  std::vector<pcl::PointIndices>::const_iterator it;
414  std::vector<int>::const_iterator pit;
415  // Vector of cluster pointclouds
416  std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr > cluster_vec;
417  // Cluster centroids
418  std::vector<pcl::PointXYZ> clusterCentroids;
419 
420  for(it = cluster_indices.begin(); it != cluster_indices.end(); ++it) {
421 
422  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_cluster (new pcl::PointCloud<pcl::PointXYZ>);
423  float x=0.0; float y=0.0;
424  int numPts=0;
425  for(pit = it->indices.begin(); pit != it->indices.end(); pit++)
426  {
427 
428  cloud_cluster->points.push_back(input_cloud->points[*pit]);
429  x+=input_cloud->points[*pit].x;
430  y+=input_cloud->points[*pit].y;
431  numPts++;
432 
433 
434  //dist_this_point = pcl::geometry::distance(input_cloud->points[*pit],
435  // origin);
436  //mindist_this_cluster = std::min(dist_this_point, mindist_this_cluster);
437  }
438 
439 
440  pcl::PointXYZ centroid;
441  centroid.x=x/numPts;
442  centroid.y=y/numPts;
443  centroid.z=0.0;
444 
445  cluster_vec.push_back(cloud_cluster);
446 
447  //Get the centroid of the cluster
448  clusterCentroids.push_back(centroid);
449 
450 
451  }
452 
453  //Ensure at least 6 clusters exist to publish (later clusters may be empty)
454  while (cluster_vec.size() < 6){
455  pcl::PointCloud<pcl::PointXYZ>::Ptr empty_cluster (new pcl::PointCloud<pcl::PointXYZ>);
456  empty_cluster->points.push_back(pcl::PointXYZ(0,0,0));
457  cluster_vec.push_back(empty_cluster);
458  }
459 
460  while (clusterCentroids.size()<6)
461  {
462  pcl::PointXYZ centroid;
463  centroid.x=0.0;
464  centroid.y=0.0;
465  centroid.z=0.0;
466 
467  clusterCentroids.push_back(centroid);
468  }
469 
470 
471  // Set initial state
472  KF0.statePre.at<float>(0)=clusterCentroids.at(0).x;
473  KF0.statePre.at<float>(1)=clusterCentroids.at(0).y;
474  KF0.statePre.at<float>(2)=0;// initial v_x
475  KF0.statePre.at<float>(3)=0;//initial v_y
476 
477  // Set initial state
478  KF1.statePre.at<float>(0)=clusterCentroids.at(1).x;
479  KF1.statePre.at<float>(1)=clusterCentroids.at(1).y;
480  KF1.statePre.at<float>(2)=0;// initial v_x
481  KF1.statePre.at<float>(3)=0;//initial v_y
482 
483  // Set initial state
484  KF2.statePre.at<float>(0)=clusterCentroids.at(2).x;
485  KF2.statePre.at<float>(1)=clusterCentroids.at(2).y;
486  KF2.statePre.at<float>(2)=0;// initial v_x
487  KF2.statePre.at<float>(3)=0;//initial v_y
488 
489 
490  // Set initial state
491  KF3.statePre.at<float>(0)=clusterCentroids.at(3).x;
492  KF3.statePre.at<float>(1)=clusterCentroids.at(3).y;
493  KF3.statePre.at<float>(2)=0;// initial v_x
494  KF3.statePre.at<float>(3)=0;//initial v_y
495 
496  // Set initial state
497  KF4.statePre.at<float>(0)=clusterCentroids.at(4).x;
498  KF4.statePre.at<float>(1)=clusterCentroids.at(4).y;
499  KF4.statePre.at<float>(2)=0;// initial v_x
500  KF4.statePre.at<float>(3)=0;//initial v_y
501 
502  // Set initial state
503  KF5.statePre.at<float>(0)=clusterCentroids.at(5).x;
504  KF5.statePre.at<float>(1)=clusterCentroids.at(5).y;
505  KF5.statePre.at<float>(2)=0;// initial v_x
506  KF5.statePre.at<float>(3)=0;//initial v_y
507 
508  firstFrame=false;
509 
510  for (int i=0;i<6;i++)
511  {
512  geometry_msgs::Point pt;
513  pt.x=clusterCentroids.at(i).x;
514  pt.y=clusterCentroids.at(i).y;
515  prevClusterCenters.push_back(pt);
516  }
517  /* // Print the initial state of the kalman filter for debugging
518  cout<<"KF0.satePre="<<KF0.statePre.at<float>(0)<<","<<KF0.statePre.at<float>(1)<<"\n";
519  cout<<"KF1.satePre="<<KF1.statePre.at<float>(0)<<","<<KF1.statePre.at<float>(1)<<"\n";
520  cout<<"KF2.satePre="<<KF2.statePre.at<float>(0)<<","<<KF2.statePre.at<float>(1)<<"\n";
521  cout<<"KF3.satePre="<<KF3.statePre.at<float>(0)<<","<<KF3.statePre.at<float>(1)<<"\n";
522  cout<<"KF4.satePre="<<KF4.statePre.at<float>(0)<<","<<KF4.statePre.at<float>(1)<<"\n";
523  cout<<"KF5.satePre="<<KF5.statePre.at<float>(0)<<","<<KF5.statePre.at<float>(1)<<"\n";
524 
525  //cin.ignore();// To be able to see the printed initial state of the KalmanFilter
526  */
527 }
528 
529 
530 else
531 {
532  //cout<<"ELSE firstFrame="<<firstFrame<<"\n";
533  pcl::PointCloud<pcl::PointXYZ>::Ptr input_cloud (new pcl::PointCloud<pcl::PointXYZ>);
534  pcl::PointCloud<pcl::PointXYZ>::Ptr clustered_cloud (new pcl::PointCloud<pcl::PointXYZ>);
535  /* Creating the KdTree from input point cloud*/
536  pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZ>);
537 
538  pcl::fromROSMsg (*input, *input_cloud);
539 
540  tree->setInputCloud (input_cloud);
541 
542  /* Here we are creating a vector of PointIndices, which contains the actual index
543  * information in a vector<int>. The indices of each detected cluster are saved here.
544  * Cluster_indices is a vector containing one instance of PointIndices for each detected
545  * cluster. Cluster_indices[0] contain all indices of the first cluster in input point cloud.
546  */
547  std::vector<pcl::PointIndices> cluster_indices;
548  pcl::EuclideanClusterExtraction<pcl::PointXYZ> ec;
549  ec.setClusterTolerance (0.3);
550  ec.setMinClusterSize (10);
551  ec.setMaxClusterSize (600);
552  ec.setSearchMethod (tree);
553  ec.setInputCloud (input_cloud);
554 //cout<<"PCL init successfull\n";
555  /* Extract the clusters out of pc and save indices in cluster_indices.*/
556  ec.extract (cluster_indices);
557 //cout<<"PCL extract successfull\n";
558  /* To separate each cluster out of the vector<PointIndices> we have to
559  * iterate through cluster_indices, create a new PointCloud for each
560  * entry and write all points of the current cluster in the PointCloud.
561  */
562  //pcl::PointXYZ origin (0,0,0);
563  //float mindist_this_cluster = 1000;
564  //float dist_this_point = 1000;
565 
566  std::vector<pcl::PointIndices>::const_iterator it;
567  std::vector<int>::const_iterator pit;
568  // Vector of cluster pointclouds
569  std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr > cluster_vec;
570 
571  // Cluster centroids
572  std::vector<pcl::PointXYZ> clusterCentroids;
573 
574 
575 
576  for(it = cluster_indices.begin(); it != cluster_indices.end(); ++it)
577  {
578  float x=0.0; float y=0.0;
579  int numPts=0;
580  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_cluster (new pcl::PointCloud<pcl::PointXYZ>);
581  for(pit = it->indices.begin(); pit != it->indices.end(); pit++)
582  {
583 
584  cloud_cluster->points.push_back(input_cloud->points[*pit]);
585 
586 
587  x+=input_cloud->points[*pit].x;
588  y+=input_cloud->points[*pit].y;
589  numPts++;
590 
591  //dist_this_point = pcl::geometry::distance(input_cloud->points[*pit],
592  // origin);
593  //mindist_this_cluster = std::min(dist_this_point, mindist_this_cluster);
594  }
595 
596  pcl::PointXYZ centroid;
597  centroid.x=x/numPts;
598  centroid.y=y/numPts;
599  centroid.z=0.0;
600 
601  cluster_vec.push_back(cloud_cluster);
602 
603  //Get the centroid of the cluster
604  clusterCentroids.push_back(centroid);
605 
606  }
607  // cout<<"cluster_vec got some clusters\n";
608 
609  //Ensure at least 6 clusters exist to publish (later clusters may be empty)
610  while (cluster_vec.size() < 6){
611  pcl::PointCloud<pcl::PointXYZ>::Ptr empty_cluster (new pcl::PointCloud<pcl::PointXYZ>);
612  empty_cluster->points.push_back(pcl::PointXYZ(0,0,0));
613  cluster_vec.push_back(empty_cluster);
614  }
615 
616  while (clusterCentroids.size()<6)
617  {
618  pcl::PointXYZ centroid;
619  centroid.x=0.0;
620  centroid.y=0.0;
621  centroid.z=0.0;
622 
623  clusterCentroids.push_back(centroid);
624  }
625 
626 
627  std_msgs::Float32MultiArray cc;
628  for(int i=0;i<6;i++)
629  {
630  cc.data.push_back(clusterCentroids.at(i).x);
631  cc.data.push_back(clusterCentroids.at(i).y);
632  cc.data.push_back(clusterCentroids.at(i).z);
633 
634  }
635  // cout<<"6 clusters initialized\n";
636 
637  //cc_pos.publish(cc);// Publish cluster mid-points.
638  KFT(cc);
639  int i=0;
640  bool publishedCluster[6];
641  for(auto it=objID.begin();it!=objID.end();it++)
642  { //cout<<"Inside the for loop\n";
643 
644 
645  switch(i)
646  {
647  cout<<"Inside the switch case\n";
648  case 0: {
649  publish_cloud(pub_cluster0,cluster_vec[*it]);
650  publishedCluster[i]=true;//Use this flag to publish only once for a given obj ID
651  i++;
652  break;
653 
654  }
655  case 1: {
656  publish_cloud(pub_cluster1,cluster_vec[*it]);
657  publishedCluster[i]=true;//Use this flag to publish only once for a given obj ID
658  i++;
659  break;
660 
661  }
662  case 2: {
663  publish_cloud(pub_cluster2,cluster_vec[*it]);
664  publishedCluster[i]=true;//Use this flag to publish only once for a given obj ID
665  i++;
666  break;
667 
668  }
669  case 3: {
670  publish_cloud(pub_cluster3,cluster_vec[*it]);
671  publishedCluster[i]=true;//Use this flag to publish only once for a given obj ID
672  i++;
673  break;
674 
675  }
676  case 4: {
677  publish_cloud(pub_cluster4,cluster_vec[*it]);
678  publishedCluster[i]=true;//Use this flag to publish only once for a given obj ID
679  i++;
680  break;
681 
682  }
683 
684  case 5: {
685  publish_cloud(pub_cluster5,cluster_vec[*it]);
686  publishedCluster[i]=true;//Use this flag to publish only once for a given obj ID
687  i++;
688  break;
689 
690  }
691  default: break;
692  }
693 
694  }
695 
696 }
697 
698 }
699 
700 
701 
702 
703 int main(int argc, char** argv)
704 {
705  // ROS init
706  ros::init (argc,argv,"kf_tracker");
707  ros::NodeHandle nh;
708 
709 
710  // Publishers to publish the state of the objects (pos and vel)
711  //objState1=nh.advertise<geometry_msgs::Twist> ("obj_1",1);
712 
713 
714 
715 cout<<"About to setup callback\n";
716 
717 // Create a ROS subscriber for the input point cloud
718  ros::Subscriber sub = nh.subscribe ("filtered_cloud", 1, cloud_cb);
719  // Create a ROS publisher for the output point cloud
720  pub_cluster0 = nh.advertise<sensor_msgs::PointCloud2> ("cluster_0", 1);
721  pub_cluster1 = nh.advertise<sensor_msgs::PointCloud2> ("cluster_1", 1);
722  pub_cluster2 = nh.advertise<sensor_msgs::PointCloud2> ("cluster_2", 1);
723  pub_cluster3 = nh.advertise<sensor_msgs::PointCloud2> ("cluster_3", 1);
724  pub_cluster4 = nh.advertise<sensor_msgs::PointCloud2> ("cluster_4", 1);
725  pub_cluster5 = nh.advertise<sensor_msgs::PointCloud2> ("cluster_5", 1);
726  // Subscribe to the clustered pointclouds
727  //ros::Subscriber c1=nh.subscribe("ccs",100,KFT);
728  objID_pub = nh.advertise<std_msgs::Int32MultiArray>("obj_id", 1);
729 /* Point cloud clustering
730 */
731 
732  //cc_pos=nh.advertise<std_msgs::Float32MultiArray>("ccs",100);//clusterCenter1
733  markerPub= nh.advertise<visualization_msgs::MarkerArray> ("viz",1);
734 
735 /* Point cloud clustering
736 */
737 
738 
739  ros::spin();
740 
741 
742 }
void setIdentity(geometry_msgs::Transform &tx)
void KFT(const std_msgs::Float32MultiArray ccs)
Definition: main.cpp:124
int stateDim
Definition: main.cpp:48
void publish(const boost::shared_ptr< M > &message) const
f
ros::Publisher pub_cluster5
Definition: main.cpp:63
cv::KalmanFilter KF3(stateDim, measDim, ctrlDim, CV_32F)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
cv::KalmanFilter KF2(stateDim, measDim, ctrlDim, CV_32F)
int main(int argc, char **argv)
Definition: main.cpp:703
cv::Mat_< float > measurement(2, 1)
cv::KalmanFilter KF5(stateDim, measDim, ctrlDim, CV_32F)
XmlRpcServer s
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
TFSIMD_FORCE_INLINE const tfScalar & y() const
std::vector< geometry_msgs::Point > prevClusterCenters
Definition: main.cpp:67
ROSCPP_DECL void spin(Spinner &spinner)
std::vector< int > objID
Definition: main.cpp:73
ros::Publisher pub_cluster3
Definition: main.cpp:61
bool firstFrame
Definition: main.cpp:76
void cloud_cb(const sensor_msgs::PointCloud2ConstPtr &input)
Definition: main.cpp:341
cv::Mat state(stateDim, 1, CV_32F)
cv::KalmanFilter KF0(stateDim, measDim, ctrlDim, CV_32F)
TFSIMD_FORCE_INLINE const tfScalar & x() const
int ctrlDim
Definition: main.cpp:50
ros::Publisher pub_cluster4
Definition: main.cpp:62
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
int measDim
Definition: main.cpp:49
cv::KalmanFilter KF4(stateDim, measDim, ctrlDim, CV_32F)
TFSIMD_FORCE_INLINE const tfScalar & z() const
ros::Publisher objID_pub
Definition: main.cpp:45
double euclidean_distance(geometry_msgs::Point &p1, geometry_msgs::Point &p2)
Definition: main.cpp:79
ros::Publisher markerPub
Definition: main.cpp:65
std::pair< int, int > findIndexOfMin(std::vector< std::vector< float > > distMat)
Definition: main.cpp:104
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
static Time now()
void publish_cloud(ros::Publisher &pub, pcl::PointCloud< pcl::PointXYZ >::Ptr cluster)
Definition: main.cpp:331
ros::Publisher pub_cluster0
Definition: main.cpp:58
ros::Publisher pub_cluster2
Definition: main.cpp:60
ros::Publisher pub_cluster1
Definition: main.cpp:59
cv::KalmanFilter KF1(stateDim, measDim, ctrlDim, CV_32F)


multi_object_tracking_lidar
Author(s): Praveen Palanisamy
autogenerated on Sat Jul 18 2020 03:29:17