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


multi_object_tracking_lidar
Author(s): Praveen Palanisamy
autogenerated on Wed Mar 2 2022 00:40:33