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" 14 #include <pcl/io/pcd_io.h> 15 #include <pcl/point_types.h> 17 #include <geometry_msgs/Point.h> 18 #include <std_msgs/Float32MultiArray.h> 19 #include <std_msgs/Int32MultiArray.h> 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> 36 #include <visualization_msgs/MarkerArray.h> 37 #include <visualization_msgs/Marker.h> 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));
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++)
113 if( distMat[i][j]<minEl)
116 minIndex=std::make_pair(i,j);
121 cout<<
"minIndex="<<minIndex.first<<
","<<minIndex.second<<
"\n";
124 void KFT(
const std_msgs::Float32MultiArray ccs)
131 std::vector<cv::Mat> pred{
KF0.predict(),
KF1.predict(),
KF2.predict(),
KF3.predict(),
KF4.predict(),
KF5.predict()};
140 std::vector<geometry_msgs::Point> clusterCenters;
143 for (std::vector<float>::const_iterator it=ccs.data.begin();it!=ccs.data.end();it+=3)
145 geometry_msgs::Point pt;
150 clusterCenters.push_back(pt);
155 std::vector<geometry_msgs::Point> KFpredictions;
157 for (
auto it=pred.begin();it!=pred.end();it++)
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);
164 KFpredictions.push_back(pt);
175 std::vector<geometry_msgs::Point> copyOfClusterCenters(clusterCenters);
176 std::vector<std::vector<float> > distMat;
178 for(
int filterN=0;filterN<6;filterN++)
180 std::vector<float> distVec;
183 distVec.push_back(
euclidean_distance(KFpredictions[filterN],copyOfClusterCenters[n]));
186 distMat.push_back(distVec);
196 cout<<
"filterN="<<filterN<<
"\n";
201 cout<<
"distMat.size()"<<distMat.size()<<
"\n";
202 cout<<
"distMat[0].size()"<<distMat.at(0).size()<<
"\n";
204 for (
const auto &row : distMat )
206 for (
const auto &
s : row ) std::cout <<
s <<
' ';
207 std::cout << std::endl;
212 for(
int clusterCount=0;clusterCount<6;clusterCount++)
216 cout<<
"Received minIndex="<<minIndex.first<<
","<<minIndex.second<<
"\n";
218 objID[minIndex.first]=minIndex.second;
221 distMat[minIndex.first]=std::vector<float>(6,10000.0);
222 for(
int row=0;row<distMat.size();row++)
224 distMat[row][minIndex.second]=10000.0;
227 cout<<
"clusterCount="<<clusterCount<<
"\n";
242 visualization_msgs::MarkerArray clusterMarkers;
244 for (
int i=0;i<6;i++)
246 visualization_msgs::Marker m;
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;
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;
264 clusterMarkers.markers.push_back(m);
269 markerPub.
publish(clusterMarkers);
274 std_msgs::Int32MultiArray obj_id;
275 for(
auto it=
objID.begin();it!=
objID.end();it++)
276 obj_id.data.push_back(*it);
280 std::vector<std::vector<float> > cc;
281 for (
int i=0;i<6;i++)
284 pt.push_back(clusterCenters[
objID[i]].
x);
285 pt.push_back(clusterCenters[
objID[i]].
y);
286 pt.push_back(clusterCenters[
objID[i]].
z);
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)};
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);
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.0
f || meas1[1]==0.0
f))
312 Mat estimated1 =
KF1.correct(meas1Mat);
313 if (!(meas2[0]==0.0
f || meas2[1]==0.0
f))
314 Mat estimated2 =
KF2.correct(meas2Mat);
315 if (!(meas3[0]==0.0
f || meas3[1]==0.0
f))
316 Mat estimated3 =
KF3.correct(meas3Mat);
317 if (!(meas4[0]==0.0
f || meas4[1]==0.0
f))
318 Mat estimated4 =
KF4.correct(meas4Mat);
319 if (!(meas5[0]==0.0
f || meas5[1]==0.0
f))
320 Mat estimated5 =
KF5.correct(meas5Mat);
332 sensor_msgs::PointCloud2::Ptr clustermsg (
new sensor_msgs::PointCloud2);
334 clustermsg->header.frame_id =
"/map";
341 void cloud_cb (
const sensor_msgs::PointCloud2ConstPtr& input)
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);
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);
384 cv::setIdentity(
KF0.measurementNoiseCov, cv::Scalar(sigmaQ));
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));
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>);
395 pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (
new pcl::search::KdTree<pcl::PointXYZ>);
399 tree->setInputCloud (input_cloud);
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);
410 ec.extract (cluster_indices);
413 std::vector<pcl::PointIndices>::const_iterator it;
414 std::vector<int>::const_iterator pit;
416 std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr > cluster_vec;
418 std::vector<pcl::PointXYZ> clusterCentroids;
420 for(it = cluster_indices.begin(); it != cluster_indices.end(); ++it) {
422 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_cluster (
new pcl::PointCloud<pcl::PointXYZ>);
423 float x=0.0;
float y=0.0;
425 for(pit = it->indices.begin(); pit != it->indices.end(); pit++)
428 cloud_cluster->points.push_back(input_cloud->points[*pit]);
429 x+=input_cloud->points[*pit].x;
430 y+=input_cloud->points[*pit].y;
440 pcl::PointXYZ centroid;
445 cluster_vec.push_back(cloud_cluster);
448 clusterCentroids.push_back(centroid);
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);
460 while (clusterCentroids.size()<6)
462 pcl::PointXYZ centroid;
467 clusterCentroids.push_back(centroid);
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;
475 KF0.statePre.at<
float>(3)=0;
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;
481 KF1.statePre.at<
float>(3)=0;
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;
487 KF2.statePre.at<
float>(3)=0;
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;
494 KF3.statePre.at<
float>(3)=0;
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;
500 KF4.statePre.at<
float>(3)=0;
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;
506 KF5.statePre.at<
float>(3)=0;
510 for (
int i=0;i<6;i++)
512 geometry_msgs::Point pt;
513 pt.x=clusterCentroids.at(i).x;
514 pt.y=clusterCentroids.at(i).y;
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>);
536 pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (
new pcl::search::KdTree<pcl::PointXYZ>);
540 tree->setInputCloud (input_cloud);
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);
556 ec.extract (cluster_indices);
566 std::vector<pcl::PointIndices>::const_iterator it;
567 std::vector<int>::const_iterator pit;
569 std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr > cluster_vec;
572 std::vector<pcl::PointXYZ> clusterCentroids;
576 for(it = cluster_indices.begin(); it != cluster_indices.end(); ++it)
578 float x=0.0;
float y=0.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++)
584 cloud_cluster->points.push_back(input_cloud->points[*pit]);
587 x+=input_cloud->points[*pit].x;
588 y+=input_cloud->points[*pit].y;
596 pcl::PointXYZ centroid;
601 cluster_vec.push_back(cloud_cluster);
604 clusterCentroids.push_back(centroid);
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);
616 while (clusterCentroids.size()<6)
618 pcl::PointXYZ centroid;
623 clusterCentroids.push_back(centroid);
627 std_msgs::Float32MultiArray cc;
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);
640 bool publishedCluster[6];
641 for(
auto it=
objID.begin();it!=
objID.end();it++)
647 cout<<
"Inside the switch case\n";
650 publishedCluster[i]=
true;
657 publishedCluster[i]=
true;
664 publishedCluster[i]=
true;
671 publishedCluster[i]=
true;
678 publishedCluster[i]=
true;
686 publishedCluster[i]=
true;
703 int main(
int argc,
char** argv)
715 cout<<
"About to setup callback\n";
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);
728 objID_pub = nh.
advertise<std_msgs::Int32MultiArray>(
"obj_id", 1);
733 markerPub= nh.
advertise<visualization_msgs::MarkerArray> (
"viz",1);
void setIdentity(geometry_msgs::Transform &tx)
void KFT(const std_msgs::Float32MultiArray ccs)
void publish(const boost::shared_ptr< M > &message) const
ros::Publisher pub_cluster5
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)
cv::Mat_< float > measurement(2, 1)
cv::KalmanFilter KF5(stateDim, measDim, ctrlDim, CV_32F)
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
ROSCPP_DECL void spin(Spinner &spinner)
ros::Publisher pub_cluster3
void cloud_cb(const sensor_msgs::PointCloud2ConstPtr &input)
cv::Mat state(stateDim, 1, CV_32F)
cv::KalmanFilter KF0(stateDim, measDim, ctrlDim, CV_32F)
TFSIMD_FORCE_INLINE const tfScalar & x() const
ros::Publisher pub_cluster4
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
cv::KalmanFilter KF4(stateDim, measDim, ctrlDim, CV_32F)
TFSIMD_FORCE_INLINE const tfScalar & z() const
double euclidean_distance(geometry_msgs::Point &p1, geometry_msgs::Point &p2)
std::pair< int, int > findIndexOfMin(std::vector< std::vector< float > > distMat)
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
void publish_cloud(ros::Publisher &pub, pcl::PointCloud< pcl::PointXYZ >::Ptr cluster)
ros::Publisher pub_cluster0
ros::Publisher pub_cluster2
ros::Publisher pub_cluster1
cv::KalmanFilter KF1(stateDim, measDim, ctrlDim, CV_32F)