main.cpp
Go to the documentation of this file.
00001 #include <iostream>
00002 #include <string.h>
00003 #include <fstream>
00004 #include <algorithm>
00005 #include <iterator>
00006 #include "kf_tracker/featureDetection.h"
00007 #include "kf_tracker/CKalmanFilter.h"
00008 #include <opencv2/core/core.hpp>
00009 #include <opencv2/highgui/highgui.hpp>
00010 #include <opencv2/imgproc/imgproc.hpp>
00011 #include <opencv2/video/video.hpp>
00012 #include "opencv2/video/tracking.hpp"
00013 #include <ros/ros.h>
00014 #include <pcl/io/pcd_io.h>
00015 #include <pcl/point_types.h>
00016 #include "pcl_ros/point_cloud.h"
00017 #include <geometry_msgs/Point.h>
00018 #include <std_msgs/Float32MultiArray.h>
00019 #include <std_msgs/Int32MultiArray.h>
00020 
00021 #include <sensor_msgs/PointCloud2.h>
00022 #include <pcl_conversions/pcl_conversions.h>
00023 #include <pcl/point_cloud.h>
00024 #include <pcl/point_types.h>
00025 #include <pcl/common/geometry.h>
00026 #include <pcl/filters/extract_indices.h>
00027 #include <pcl/filters/voxel_grid.h>
00028 #include <pcl/features/normal_3d.h>
00029 #include <pcl/kdtree/kdtree.h>
00030 #include <pcl/sample_consensus/method_types.h>
00031 #include <pcl/sample_consensus/model_types.h>
00032 #include <pcl/segmentation/sac_segmentation.h>
00033 #include <pcl/segmentation/extract_clusters.h>
00034 #include <pcl/common/centroid.h>
00035  
00036 #include <visualization_msgs/MarkerArray.h>
00037 #include <visualization_msgs/Marker.h>
00038 #include <limits>
00039 #include <utility>
00040 
00041 using namespace std;
00042 using namespace cv;
00043 
00044 
00045 ros::Publisher objID_pub;
00046 
00047     // KF init
00048     int stateDim=4;// [x,y,v_x,v_y]//,w,h]
00049     int measDim=2;// [z_x,z_y,z_w,z_h]
00050     int ctrlDim=0;
00051     cv::KalmanFilter KF0(stateDim,measDim,ctrlDim,CV_32F);
00052     cv::KalmanFilter KF1(stateDim,measDim,ctrlDim,CV_32F);
00053     cv::KalmanFilter KF2(stateDim,measDim,ctrlDim,CV_32F);
00054     cv::KalmanFilter KF3(stateDim,measDim,ctrlDim,CV_32F);
00055     cv::KalmanFilter KF4(stateDim,measDim,ctrlDim,CV_32F);
00056     cv::KalmanFilter KF5(stateDim,measDim,ctrlDim,CV_32F);
00057 
00058     ros::Publisher pub_cluster0;
00059     ros::Publisher pub_cluster1;
00060     ros::Publisher pub_cluster2;
00061     ros::Publisher pub_cluster3;
00062     ros::Publisher pub_cluster4;
00063     ros::Publisher pub_cluster5;
00064 
00065     ros::Publisher markerPub;
00066 
00067     std::vector<geometry_msgs::Point> prevClusterCenters;
00068 
00069 
00070     cv::Mat state(stateDim,1,CV_32F);
00071     cv::Mat_<float> measurement(2,1); 
00072 
00073     std::vector<int> objID;// Output of the data association using KF
00074    // measurement.setTo(Scalar(0));
00075 
00076 bool firstFrame=true;
00077 
00078 // calculate euclidean distance of two points
00079   double euclidean_distance(geometry_msgs::Point& p1, geometry_msgs::Point& p2)
00080   {
00081     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));
00082   }
00083 /*
00084 //Count unique object IDs. just to make sure same ID has not been assigned to two KF_Trackers.  
00085 int countIDs(vector<int> v)
00086 {
00087     transform(v.begin(), v.end(), v.begin(), abs); // O(n) where n = distance(v.end(), v.begin())
00088     sort(v.begin(), v.end()); // Average case O(n log n), worst case O(n^2) (usually implemented as quicksort.
00089     // To guarantee worst case O(n log n) replace with make_heap, then sort_heap.
00090 
00091     // Unique will take a sorted range, and move things around to get duplicated
00092     // items to the back and returns an iterator to the end of the unique section of the range
00093     auto unique_end = unique(v.begin(), v.end()); // Again n comparisons
00094     return distance(unique_end, v.begin()); // Constant time for random access iterators (like vector's)
00095 }
00096 */
00097 
00098 /*
00099 
00100 objID: vector containing the IDs of the clusters that should be associated with each KF_Tracker
00101 objID[0] corresponds to KFT0, objID[1] corresponds to KFT1 etc.
00102 */
00103 
00104 std::pair<int,int> findIndexOfMin(std::vector<std::vector<float> > distMat)
00105 {
00106     cout<<"findIndexOfMin cALLED\n";
00107     std::pair<int,int>minIndex;
00108     float minEl=std::numeric_limits<float>::max();
00109     cout<<"minEl="<<minEl<<"\n";
00110     for (int i=0; i<distMat.size();i++)
00111         for(int j=0;j<distMat.at(0).size();j++)
00112         {
00113             if( distMat[i][j]<minEl)
00114             {
00115                 minEl=distMat[i][j];
00116                 minIndex=std::make_pair(i,j);
00117 
00118             }
00119 
00120         }
00121     cout<<"minIndex="<<minIndex.first<<","<<minIndex.second<<"\n";
00122     return minIndex;
00123 }
00124 void KFT(const std_msgs::Float32MultiArray ccs)
00125 {
00126 
00127 
00128 
00129     // First predict, to update the internal statePre variable
00130 
00131     std::vector<cv::Mat> pred{KF0.predict(),KF1.predict(),KF2.predict(),KF3.predict(),KF4.predict(),KF5.predict()};
00132  //cout<<"Pred successfull\n";
00133 
00134     //cv::Point predictPt(prediction.at<float>(0),prediction.at<float>(1));
00135    // cout<<"Prediction 1 ="<<prediction.at<float>(0)<<","<<prediction.at<float>(1)<<"\n";
00136 
00137     // Get measurements
00138     // Extract the position of the clusters forom the multiArray. To check if the data
00139     // coming in, check the .z (every third) coordinate and that will be 0.0
00140     std::vector<geometry_msgs::Point> clusterCenters;//clusterCenters
00141    
00142     int i=0;
00143     for (std::vector<float>::const_iterator it=ccs.data.begin();it!=ccs.data.end();it+=3)
00144     {
00145         geometry_msgs::Point pt;
00146         pt.x=*it;
00147         pt.y=*(it+1);
00148         pt.z=*(it+2);
00149 
00150         clusterCenters.push_back(pt);
00151        
00152     }
00153 
00154   //  cout<<"CLusterCenters Obtained"<<"\n";
00155     std::vector<geometry_msgs::Point> KFpredictions;
00156     i=0;
00157     for (auto it=pred.begin();it!=pred.end();it++)
00158     {
00159         geometry_msgs::Point pt;
00160         pt.x=(*it).at<float>(0);
00161         pt.y=(*it).at<float>(1);
00162         pt.z=(*it).at<float>(2);
00163 
00164         KFpredictions.push_back(pt);
00165         
00166     }
00167   // cout<<"Got predictions"<<"\n";
00168 
00169     
00170     
00171     // Find the cluster that is more probable to be belonging to a given KF.
00172     objID.clear();//Clear the objID vector
00173     objID.resize(6);//Allocate default elements so that [i] doesnt segfault. Should be done better
00174     // Copy clusterCentres for modifying it and preventing multiple assignments of the same ID
00175     std::vector<geometry_msgs::Point> copyOfClusterCenters(clusterCenters);
00176     std::vector<std::vector<float> > distMat;
00177 
00178     for(int filterN=0;filterN<6;filterN++)
00179     {
00180         std::vector<float> distVec;
00181         for(int n=0;n<6;n++)
00182         {
00183             distVec.push_back(euclidean_distance(KFpredictions[filterN],copyOfClusterCenters[n]));
00184         }
00185 
00186         distMat.push_back(distVec);
00187       /*// Based on distVec instead of distMat (global min). Has problems with the person's leg going out of scope 
00188        int ID=std::distance(distVec.begin(),min_element(distVec.begin(),distVec.end()));
00189        //cout<<"finterlN="<<filterN<<"   minID="<<ID
00190        objID.push_back(ID);
00191       // Prevent assignment of the same object ID to multiple clusters
00192        copyOfClusterCenters[ID].x=100000;// A large value so that this center is not assigned to another cluster
00193        copyOfClusterCenters[ID].y=10000;
00194        copyOfClusterCenters[ID].z=10000;
00195       */
00196      cout<<"filterN="<<filterN<<"\n";
00197 
00198 
00199     }
00200 
00201     cout<<"distMat.size()"<<distMat.size()<<"\n";
00202     cout<<"distMat[0].size()"<<distMat.at(0).size()<<"\n";
00203     // DEBUG: print the distMat
00204     for ( const auto &row : distMat )
00205     {
00206        for ( const auto &s : row ) std::cout << s << ' ';
00207        std::cout << std::endl;
00208     }
00209 
00210 
00211 
00212     for(int clusterCount=0;clusterCount<6;clusterCount++)
00213     {
00214         // 1. Find min(distMax)==> (i,j);
00215         std::pair<int,int> minIndex(findIndexOfMin(distMat));
00216          cout<<"Received minIndex="<<minIndex.first<<","<<minIndex.second<<"\n";
00217         // 2. objID[i]=clusterCenters[j]; counter++
00218         objID[minIndex.first]=minIndex.second;
00219     
00220         // 3. distMat[i,:]=10000; distMat[:,j]=10000
00221         distMat[minIndex.first]=std::vector<float>(6,10000.0);// Set the row to a high number.
00222         for(int row=0;row<distMat.size();row++)//set the column to a high number
00223         {
00224             distMat[row][minIndex.second]=10000.0;
00225         }
00226         // 4. if(counter<6) got to 1.
00227         cout<<"clusterCount="<<clusterCount<<"\n";
00228 
00229     }
00230 
00231    // cout<<"Got object IDs"<<"\n";
00232     //countIDs(objID);// for verif/corner cases
00233 
00234     //display objIDs
00235   /* DEBUG
00236     cout<<"objID= ";
00237     for(auto it=objID.begin();it!=objID.end();it++)
00238         cout<<*it<<" ,";
00239     cout<<"\n";
00240     */
00241 
00242     visualization_msgs::MarkerArray clusterMarkers;
00243 
00244      for (int i=0;i<6;i++)
00245      {
00246         visualization_msgs::Marker m;
00247 
00248         m.id=i;
00249         m.type=visualization_msgs::Marker::CUBE;
00250         m.header.frame_id="/map";
00251         m.scale.x=0.3;         m.scale.y=0.3;         m.scale.z=0.3;
00252         m.action=visualization_msgs::Marker::ADD;
00253         m.color.a=1.0;
00254         m.color.r=i%2?1:0;
00255         m.color.g=i%3?1:0;
00256         m.color.b=i%4?1:0;
00257 
00258        //geometry_msgs::Point clusterC(clusterCenters.at(objID[i]));
00259         geometry_msgs::Point clusterC(KFpredictions[i]);
00260        m.pose.position.x=clusterC.x;
00261        m.pose.position.y=clusterC.y;
00262        m.pose.position.z=clusterC.z;
00263 
00264        clusterMarkers.markers.push_back(m);
00265      }
00266 
00267     prevClusterCenters=clusterCenters;
00268 
00269      markerPub.publish(clusterMarkers);
00270 
00271 
00272 
00273 
00274     std_msgs::Int32MultiArray obj_id;
00275     for(auto it=objID.begin();it!=objID.end();it++)
00276         obj_id.data.push_back(*it);
00277     // Publish the object IDs
00278     objID_pub.publish(obj_id);
00279     // convert clusterCenters from geometry_msgs::Point to floats
00280     std::vector<std::vector<float> > cc;
00281     for (int i=0;i<6;i++)
00282     {
00283         vector<float> pt;
00284         pt.push_back(clusterCenters[objID[i]].x);
00285         pt.push_back(clusterCenters[objID[i]].y);
00286         pt.push_back(clusterCenters[objID[i]].z);
00287         
00288         cc.push_back(pt);
00289     }
00290     //cout<<"cc[5][0]="<<cc[5].at(0)<<"cc[5][1]="<<cc[5].at(1)<<"cc[5][2]="<<cc[5].at(2)<<"\n";
00291     float meas0[2]={cc[0].at(0),cc[0].at(1)};
00292     float meas1[2]={cc[1].at(0),cc[1].at(1)};
00293     float meas2[2]={cc[2].at(0),cc[2].at(1)};
00294     float meas3[2]={cc[3].at(0),cc[3].at(1)};
00295     float meas4[2]={cc[4].at(0),cc[4].at(1)};
00296     float meas5[2]={cc[5].at(0),cc[5].at(1)};
00297 
00298 
00299 
00300     // The update phase 
00301     cv::Mat meas0Mat=cv::Mat(2,1,CV_32F,meas0);
00302     cv::Mat meas1Mat=cv::Mat(2,1,CV_32F,meas1);
00303     cv::Mat meas2Mat=cv::Mat(2,1,CV_32F,meas2);
00304     cv::Mat meas3Mat=cv::Mat(2,1,CV_32F,meas3);
00305     cv::Mat meas4Mat=cv::Mat(2,1,CV_32F,meas4);
00306     cv::Mat meas5Mat=cv::Mat(2,1,CV_32F,meas5);
00307 
00308 //cout<<"meas0Mat"<<meas0Mat<<"\n";
00309 if (!(meas0Mat.at<float>(0,0)==0.0f || meas0Mat.at<float>(1,0)==0.0f))
00310     Mat estimated0 = KF0.correct(meas0Mat);
00311 if (!(meas1[0]==0.0f || meas1[1]==0.0f))
00312     Mat estimated1 = KF1.correct(meas1Mat);
00313 if (!(meas2[0]==0.0f || meas2[1]==0.0f))
00314     Mat estimated2 = KF2.correct(meas2Mat);
00315 if (!(meas3[0]==0.0f || meas3[1]==0.0f))
00316     Mat estimated3 = KF3.correct(meas3Mat);
00317 if (!(meas4[0]==0.0f || meas4[1]==0.0f))
00318     Mat estimated4 = KF4.correct(meas4Mat);
00319 if (!(meas5[0]==0.0f || meas5[1]==0.0f))
00320     Mat estimated5 = KF5.correct(meas5Mat);
00321     
00322  
00323     // Publish the point clouds belonging to each clusters
00324 
00325 
00326    // cout<<"estimate="<<estimated.at<float>(0)<<","<<estimated.at<float>(1)<<"\n";
00327    // Point statePt(estimated.at<float>(0),estimated.at<float>(1));
00328 //cout<<"DONE KF_TRACKER\n";
00329    
00330 }
00331 void publish_cloud(ros::Publisher& pub, pcl::PointCloud<pcl::PointXYZ>::Ptr cluster){
00332   sensor_msgs::PointCloud2::Ptr clustermsg (new sensor_msgs::PointCloud2);
00333   pcl::toROSMsg (*cluster , *clustermsg);
00334   clustermsg->header.frame_id = "/map";
00335   clustermsg->header.stamp = ros::Time::now();
00336   pub.publish (*clustermsg);
00337 
00338 }
00339 
00340 
00341 void cloud_cb (const sensor_msgs::PointCloud2ConstPtr& input)
00342 
00343 {
00344    // cout<<"IF firstFrame="<<firstFrame<<"\n";
00345     // If this is the first frame, initialize kalman filters for the clustered objects
00346 if (firstFrame)
00347 {   
00348   // Initialize 6 Kalman Filters; Assuming 6 max objects in the dataset. 
00349   // Could be made generic by creating a Kalman Filter only when a new object is detected  
00350 
00351     float dvx=0.01f; //1.0
00352     float dvy=0.01f;//1.0
00353     float dx=1.0f;
00354     float dy=1.0f;
00355     KF0.transitionMatrix = *(Mat_<float>(4, 4) << dx,0,1,0,   0,dy,0,1,  0,0,dvx,0,  0,0,0,dvy);
00356     KF1.transitionMatrix = *(Mat_<float>(4, 4) << dx,0,1,0,   0,dy,0,1,  0,0,dvx,0,  0,0,0,dvy);
00357     KF2.transitionMatrix = *(Mat_<float>(4, 4) << dx,0,1,0,   0,dy,0,1,  0,0,dvx,0,  0,0,0,dvy);
00358     KF3.transitionMatrix = *(Mat_<float>(4, 4) << dx,0,1,0,   0,dy,0,1,  0,0,dvx,0,  0,0,0,dvy);
00359     KF4.transitionMatrix = *(Mat_<float>(4, 4) << dx,0,1,0,   0,dy,0,1,  0,0,dvx,0,  0,0,0,dvy);
00360     KF5.transitionMatrix = *(Mat_<float>(4, 4) << dx,0,1,0,   0,dy,0,1,  0,0,dvx,0,  0,0,0,dvy);
00361 
00362     cv::setIdentity(KF0.measurementMatrix);
00363     cv::setIdentity(KF1.measurementMatrix);
00364     cv::setIdentity(KF2.measurementMatrix);
00365     cv::setIdentity(KF3.measurementMatrix);
00366     cv::setIdentity(KF4.measurementMatrix);
00367     cv::setIdentity(KF5.measurementMatrix);
00368     // Process Noise Covariance Matrix Q
00369     // [ Ex 0  0    0 0    0 ]
00370     // [ 0  Ey 0    0 0    0 ]
00371     // [ 0  0  Ev_x 0 0    0 ]
00372     // [ 0  0  0    1 Ev_y 0 ]
00375     float sigmaP=0.01;
00376     float sigmaQ=0.1;
00377     setIdentity(KF0.processNoiseCov, Scalar::all(sigmaP));
00378     setIdentity(KF1.processNoiseCov, Scalar::all(sigmaP));
00379     setIdentity(KF2.processNoiseCov, Scalar::all(sigmaP));
00380     setIdentity(KF3.processNoiseCov, Scalar::all(sigmaP));
00381     setIdentity(KF4.processNoiseCov, Scalar::all(sigmaP));
00382     setIdentity(KF5.processNoiseCov, Scalar::all(sigmaP));
00383     // Meas noise cov matrix R
00384      cv::setIdentity(KF0.measurementNoiseCov, cv::Scalar(sigmaQ));//1e-1
00385      cv::setIdentity(KF1.measurementNoiseCov, cv::Scalar(sigmaQ));
00386      cv::setIdentity(KF2.measurementNoiseCov, cv::Scalar(sigmaQ));
00387      cv::setIdentity(KF3.measurementNoiseCov, cv::Scalar(sigmaQ));
00388      cv::setIdentity(KF4.measurementNoiseCov, cv::Scalar(sigmaQ));
00389      cv::setIdentity(KF5.measurementNoiseCov, cv::Scalar(sigmaQ));
00390 
00391 // Process the point cloud
00392      pcl::PointCloud<pcl::PointXYZ>::Ptr input_cloud (new pcl::PointCloud<pcl::PointXYZ>);
00393   pcl::PointCloud<pcl::PointXYZ>::Ptr clustered_cloud (new pcl::PointCloud<pcl::PointXYZ>);
00394       /* Creating the KdTree from input point cloud*/
00395   pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZ>);
00396 
00397   pcl::fromROSMsg (*input, *input_cloud);
00398 
00399   tree->setInputCloud (input_cloud);
00400 
00401 
00402   std::vector<pcl::PointIndices> cluster_indices;
00403   pcl::EuclideanClusterExtraction<pcl::PointXYZ> ec;
00404   ec.setClusterTolerance (0.08); 
00405   ec.setMinClusterSize (10);
00406   ec.setMaxClusterSize (600);
00407   ec.setSearchMethod (tree);
00408   ec.setInputCloud (input_cloud);
00409   /* Extract the clusters out of pc and save indices in cluster_indices.*/
00410   ec.extract (cluster_indices);
00411 
00412   
00413   std::vector<pcl::PointIndices>::const_iterator it;
00414   std::vector<int>::const_iterator pit;
00415   // Vector of cluster pointclouds
00416   std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr > cluster_vec;
00417     // Cluster centroids
00418   std::vector<pcl::PointXYZ> clusterCentroids;
00419 
00420   for(it = cluster_indices.begin(); it != cluster_indices.end(); ++it) {
00421           
00422          pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_cluster (new pcl::PointCloud<pcl::PointXYZ>);
00423          float x=0.0; float y=0.0;
00424          int numPts=0;
00425           for(pit = it->indices.begin(); pit != it->indices.end(); pit++) 
00426           {
00427           
00428                   cloud_cluster->points.push_back(input_cloud->points[*pit]);
00429                   x+=input_cloud->points[*pit].x;
00430                   y+=input_cloud->points[*pit].y;
00431                   numPts++;
00432 
00433 
00434                   //dist_this_point = pcl::geometry::distance(input_cloud->points[*pit],
00435                   //                                          origin);
00436                   //mindist_this_cluster = std::min(dist_this_point, mindist_this_cluster);
00437           }
00438 
00439          
00440       pcl::PointXYZ centroid;
00441       centroid.x=x/numPts;
00442       centroid.y=y/numPts;
00443       centroid.z=0.0;
00444       
00445       cluster_vec.push_back(cloud_cluster);
00446 
00447       //Get the centroid of the cluster
00448       clusterCentroids.push_back(centroid);
00449 
00450 
00451     }
00452 
00453     //Ensure at least 6 clusters exist to publish (later clusters may be empty)
00454     while (cluster_vec.size() < 6){
00455       pcl::PointCloud<pcl::PointXYZ>::Ptr empty_cluster (new pcl::PointCloud<pcl::PointXYZ>);
00456       empty_cluster->points.push_back(pcl::PointXYZ(0,0,0));
00457       cluster_vec.push_back(empty_cluster);
00458     }
00459 
00460         while (clusterCentroids.size()<6)
00461     {
00462       pcl::PointXYZ centroid;
00463       centroid.x=0.0;
00464       centroid.y=0.0;
00465       centroid.z=0.0;
00466       
00467        clusterCentroids.push_back(centroid);
00468     }
00469     
00470 
00471      // Set initial state
00472      KF0.statePre.at<float>(0)=clusterCentroids.at(0).x;
00473      KF0.statePre.at<float>(1)=clusterCentroids.at(0).y;
00474      KF0.statePre.at<float>(2)=0;// initial v_x
00475      KF0.statePre.at<float>(3)=0;//initial v_y
00476 
00477      // Set initial state
00478      KF1.statePre.at<float>(0)=clusterCentroids.at(1).x;
00479      KF1.statePre.at<float>(1)=clusterCentroids.at(1).y;
00480      KF1.statePre.at<float>(2)=0;// initial v_x
00481      KF1.statePre.at<float>(3)=0;//initial v_y
00482 
00483      // Set initial state
00484      KF2.statePre.at<float>(0)=clusterCentroids.at(2).x;
00485      KF2.statePre.at<float>(1)=clusterCentroids.at(2).y;
00486      KF2.statePre.at<float>(2)=0;// initial v_x
00487      KF2.statePre.at<float>(3)=0;//initial v_y
00488 
00489 
00490      // Set initial state
00491      KF3.statePre.at<float>(0)=clusterCentroids.at(3).x;
00492      KF3.statePre.at<float>(1)=clusterCentroids.at(3).y;
00493      KF3.statePre.at<float>(2)=0;// initial v_x
00494      KF3.statePre.at<float>(3)=0;//initial v_y
00495 
00496      // Set initial state
00497      KF4.statePre.at<float>(0)=clusterCentroids.at(4).x;
00498      KF4.statePre.at<float>(1)=clusterCentroids.at(4).y;
00499      KF4.statePre.at<float>(2)=0;// initial v_x
00500      KF4.statePre.at<float>(3)=0;//initial v_y
00501 
00502      // Set initial state
00503      KF5.statePre.at<float>(0)=clusterCentroids.at(5).x;
00504      KF5.statePre.at<float>(1)=clusterCentroids.at(5).y;
00505      KF5.statePre.at<float>(2)=0;// initial v_x
00506      KF5.statePre.at<float>(3)=0;//initial v_y
00507 
00508      firstFrame=false;
00509 
00510     for (int i=0;i<6;i++)
00511      {
00512         geometry_msgs::Point pt;
00513         pt.x=clusterCentroids.at(i).x;
00514         pt.y=clusterCentroids.at(i).y;
00515         prevClusterCenters.push_back(pt);
00516      }
00517    /*  // Print the initial state of the kalman filter for debugging
00518      cout<<"KF0.satePre="<<KF0.statePre.at<float>(0)<<","<<KF0.statePre.at<float>(1)<<"\n";
00519      cout<<"KF1.satePre="<<KF1.statePre.at<float>(0)<<","<<KF1.statePre.at<float>(1)<<"\n";
00520      cout<<"KF2.satePre="<<KF2.statePre.at<float>(0)<<","<<KF2.statePre.at<float>(1)<<"\n";
00521      cout<<"KF3.satePre="<<KF3.statePre.at<float>(0)<<","<<KF3.statePre.at<float>(1)<<"\n";
00522      cout<<"KF4.satePre="<<KF4.statePre.at<float>(0)<<","<<KF4.statePre.at<float>(1)<<"\n";
00523      cout<<"KF5.satePre="<<KF5.statePre.at<float>(0)<<","<<KF5.statePre.at<float>(1)<<"\n";
00524 
00525      //cin.ignore();// To be able to see the printed initial state of the KalmanFilter
00526      */
00527 }
00528 
00529  
00530 else
00531 { 
00532   //cout<<"ELSE firstFrame="<<firstFrame<<"\n";
00533   pcl::PointCloud<pcl::PointXYZ>::Ptr input_cloud (new pcl::PointCloud<pcl::PointXYZ>);
00534   pcl::PointCloud<pcl::PointXYZ>::Ptr clustered_cloud (new pcl::PointCloud<pcl::PointXYZ>);
00535       /* Creating the KdTree from input point cloud*/
00536   pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZ>);
00537 
00538   pcl::fromROSMsg (*input, *input_cloud);
00539 
00540   tree->setInputCloud (input_cloud);
00541 
00542   /* Here we are creating a vector of PointIndices, which contains the actual index
00543    * information in a vector<int>. The indices of each detected cluster are saved here.
00544    * Cluster_indices is a vector containing one instance of PointIndices for each detected 
00545    * cluster. Cluster_indices[0] contain all indices of the first cluster in input point cloud.
00546    */
00547   std::vector<pcl::PointIndices> cluster_indices;
00548   pcl::EuclideanClusterExtraction<pcl::PointXYZ> ec;
00549   ec.setClusterTolerance (0.3);
00550   ec.setMinClusterSize (10);
00551   ec.setMaxClusterSize (600);
00552   ec.setSearchMethod (tree);
00553   ec.setInputCloud (input_cloud);
00554 //cout<<"PCL init successfull\n";
00555   /* Extract the clusters out of pc and save indices in cluster_indices.*/
00556   ec.extract (cluster_indices);
00557 //cout<<"PCL extract successfull\n";
00558   /* To separate each cluster out of the vector<PointIndices> we have to 
00559    * iterate through cluster_indices, create a new PointCloud for each 
00560    * entry and write all points of the current cluster in the PointCloud. 
00561    */
00562   //pcl::PointXYZ origin (0,0,0);
00563   //float mindist_this_cluster = 1000;
00564   //float dist_this_point = 1000;
00565 
00566   std::vector<pcl::PointIndices>::const_iterator it;
00567   std::vector<int>::const_iterator pit;
00568   // Vector of cluster pointclouds
00569   std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr > cluster_vec;
00570 
00571      // Cluster centroids
00572   std::vector<pcl::PointXYZ> clusterCentroids;
00573 
00574   
00575 
00576   for(it = cluster_indices.begin(); it != cluster_indices.end(); ++it)
00577    {
00578         float x=0.0; float y=0.0;
00579          int numPts=0;
00580           pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_cluster (new pcl::PointCloud<pcl::PointXYZ>);
00581           for(pit = it->indices.begin(); pit != it->indices.end(); pit++) 
00582           {
00583           
00584                   cloud_cluster->points.push_back(input_cloud->points[*pit]);
00585 
00586 
00587                   x+=input_cloud->points[*pit].x;
00588                   y+=input_cloud->points[*pit].y;
00589                   numPts++;
00590 
00591                   //dist_this_point = pcl::geometry::distance(input_cloud->points[*pit],
00592                   //                                          origin);
00593                   //mindist_this_cluster = std::min(dist_this_point, mindist_this_cluster);
00594           }
00595 
00596     pcl::PointXYZ centroid;
00597       centroid.x=x/numPts;
00598       centroid.y=y/numPts;
00599       centroid.z=0.0;
00600       
00601       cluster_vec.push_back(cloud_cluster);
00602 
00603       //Get the centroid of the cluster
00604       clusterCentroids.push_back(centroid);
00605 
00606     }
00607    // cout<<"cluster_vec got some clusters\n";
00608 
00609     //Ensure at least 6 clusters exist to publish (later clusters may be empty)
00610     while (cluster_vec.size() < 6){
00611       pcl::PointCloud<pcl::PointXYZ>::Ptr empty_cluster (new pcl::PointCloud<pcl::PointXYZ>);
00612       empty_cluster->points.push_back(pcl::PointXYZ(0,0,0));
00613       cluster_vec.push_back(empty_cluster);
00614     }
00615 
00616      while (clusterCentroids.size()<6)
00617     {
00618       pcl::PointXYZ centroid;
00619       centroid.x=0.0;
00620       centroid.y=0.0;
00621       centroid.z=0.0;
00622       
00623        clusterCentroids.push_back(centroid);
00624     }
00625 
00626 
00627     std_msgs::Float32MultiArray cc;
00628     for(int i=0;i<6;i++)
00629     {
00630         cc.data.push_back(clusterCentroids.at(i).x);
00631         cc.data.push_back(clusterCentroids.at(i).y);
00632         cc.data.push_back(clusterCentroids.at(i).z);    
00633 
00634     }
00635    // cout<<"6 clusters initialized\n";
00636 
00637     //cc_pos.publish(cc);// Publish cluster mid-points.
00638     KFT(cc);
00639     int i=0;
00640     bool publishedCluster[6];
00641     for(auto it=objID.begin();it!=objID.end();it++)
00642         { //cout<<"Inside the for loop\n";
00643             
00644         
00645             switch(i)
00646             {
00647                 cout<<"Inside the switch case\n";
00648                 case 0: { 
00649                             publish_cloud(pub_cluster0,cluster_vec[*it]);
00650                             publishedCluster[i]=true;//Use this flag to publish only once for a given obj ID
00651                             i++;
00652                             break;
00653 
00654                         }
00655                 case 1: {
00656                             publish_cloud(pub_cluster1,cluster_vec[*it]);
00657                             publishedCluster[i]=true;//Use this flag to publish only once for a given obj ID
00658                             i++;
00659                             break;
00660 
00661                         }
00662                 case 2: {
00663                             publish_cloud(pub_cluster2,cluster_vec[*it]);
00664                             publishedCluster[i]=true;//Use this flag to publish only once for a given obj ID
00665                             i++;
00666                             break;
00667 
00668                         }
00669                 case 3: {
00670                             publish_cloud(pub_cluster3,cluster_vec[*it]);
00671                             publishedCluster[i]=true;//Use this flag to publish only once for a given obj ID
00672                             i++;
00673                             break;
00674 
00675                         }
00676                 case 4: {
00677                             publish_cloud(pub_cluster4,cluster_vec[*it]);
00678                             publishedCluster[i]=true;//Use this flag to publish only once for a given obj ID
00679                             i++;
00680                             break;
00681 
00682                         }
00683 
00684                 case 5: {
00685                             publish_cloud(pub_cluster5,cluster_vec[*it]);
00686                             publishedCluster[i]=true;//Use this flag to publish only once for a given obj ID
00687                             i++;
00688                             break;
00689 
00690                         }
00691                 default: break;
00692             }
00693         
00694         }
00695 
00696 } 
00697 
00698 }   
00699 
00700 
00701   
00702 
00703 int main(int argc, char** argv)
00704 {
00705     // ROS init
00706     ros::init (argc,argv,"kf_tracker");
00707     ros::NodeHandle nh;
00708 
00709    
00710     // Publishers to publish the state of the objects (pos and vel)
00711     //objState1=nh.advertise<geometry_msgs::Twist> ("obj_1",1);
00712 
00713 
00714 
00715 cout<<"About to setup callback\n";
00716 
00717 // Create a ROS subscriber for the input point cloud
00718   ros::Subscriber sub = nh.subscribe ("filtered_cloud", 1, cloud_cb);
00719   // Create a ROS publisher for the output point cloud
00720   pub_cluster0 = nh.advertise<sensor_msgs::PointCloud2> ("cluster_0", 1);
00721   pub_cluster1 = nh.advertise<sensor_msgs::PointCloud2> ("cluster_1", 1);
00722   pub_cluster2 = nh.advertise<sensor_msgs::PointCloud2> ("cluster_2", 1);
00723   pub_cluster3 = nh.advertise<sensor_msgs::PointCloud2> ("cluster_3", 1);
00724   pub_cluster4 = nh.advertise<sensor_msgs::PointCloud2> ("cluster_4", 1);
00725   pub_cluster5 = nh.advertise<sensor_msgs::PointCloud2> ("cluster_5", 1);
00726       // Subscribe to the clustered pointclouds
00727     //ros::Subscriber c1=nh.subscribe("ccs",100,KFT); 
00728     objID_pub = nh.advertise<std_msgs::Int32MultiArray>("obj_id", 1);
00729 /* Point cloud clustering
00730 */
00731     
00732   //cc_pos=nh.advertise<std_msgs::Float32MultiArray>("ccs",100);//clusterCenter1
00733   markerPub= nh.advertise<visualization_msgs::MarkerArray> ("viz",1);
00734 
00735 /* Point cloud clustering
00736 */    
00737 
00738 
00739     ros::spin();
00740 
00741 
00742 }


multi_object_tracking_lidar
Author(s): Praveen Palanisamy
autogenerated on Thu Apr 18 2019 02:40:55