3 #include "opencv2/video/tracking.hpp"
7 #include <geometry_msgs/Point.h>
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>
17 #include <std_msgs/Float32MultiArray.h>
18 #include <std_msgs/Int32MultiArray.h>
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>
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));
96 void KFT(
const std_msgs::Float32MultiArray ccs) {
100 std::vector<cv::Mat> pred{
KF0.predict(),
KF1.predict(),
KF2.predict(),
101 KF3.predict(),
KF4.predict(),
KF5.predict()};
111 std::vector<geometry_msgs::Point> clusterCenters;
114 for (std::vector<float>::const_iterator it = ccs.data.begin();
115 it != ccs.data.end(); it += 3) {
116 geometry_msgs::Point pt;
121 clusterCenters.push_back(pt);
125 std::vector<geometry_msgs::Point> KFpredictions;
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);
133 KFpredictions.push_back(pt);
169 for (
int filterN = 0; filterN < 6; filterN++) {
170 std::vector<float> distVec;
171 for (
int n = 0; n < 6; n++)
176 objID.push_back(std::distance(distVec.begin(),
177 min_element(distVec.begin(), distVec.end())));
184 for (
int i = 0; i < 6; i++) {
192 std_msgs::Int32MultiArray obj_id;
193 for (
auto it =
objID.begin(); it !=
objID.end(); it++)
194 obj_id.data.push_back(*it);
197 std::vector<std::vector<float>> cc;
198 for (
int i = 0; i < clusterCenters.size(); i++) {
200 pt.push_back(clusterCenters[i].x);
201 pt.push_back(clusterCenters[i].y);
202 pt.push_back(clusterCenters[i].z);
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)};
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);
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);
238 pcl::PointCloud<pcl::PointXYZ>::Ptr cluster) {
239 sensor_msgs::PointCloud2::Ptr clustermsg(
new sensor_msgs::PointCloud2);
241 clustermsg->header.frame_id =
"map";
246 void cloud_cb(
const sensor_msgs::PointCloud2ConstPtr &input)
249 cout <<
"IF firstFrame=" <<
firstFrame <<
"\n";
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);
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);
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));
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>);
302 pcl::search::KdTree<pcl::PointXYZ>::Ptr tree(
303 new pcl::search::KdTree<pcl::PointXYZ>);
307 tree->setInputCloud(input_cloud);
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);
323 ec.extract(cluster_indices);
333 std::vector<pcl::PointIndices>::const_iterator it;
334 std::vector<int>::const_iterator pit;
336 std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> cluster_vec;
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++) {
343 cloud_cluster->points.push_back(input_cloud->points[*pit]);
350 cluster_vec.push_back(cloud_cluster);
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);
362 KF0.statePre.at<
float>(0) =
363 cluster_vec[0]->points[cluster_vec[0]->points.size() / 2].x;
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;
368 KF0.statePre.at<
float>(3) = 0;
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;
376 KF1.statePre.at<
float>(3) = 0;
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;
384 KF2.statePre.at<
float>(3) = 0;
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;
392 KF3.statePre.at<
float>(3) = 0;
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;
400 KF4.statePre.at<
float>(3) = 0;
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;
408 KF5.statePre.at<
float>(3) = 0;
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";
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;
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>);
447 pcl::search::KdTree<pcl::PointXYZ>::Ptr tree(
448 new pcl::search::KdTree<pcl::PointXYZ>);
452 tree->setInputCloud(input_cloud);
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";
469 ec.extract(cluster_indices);
470 cout <<
"PCL extract successfull\n";
479 std::vector<pcl::PointIndices>::const_iterator it;
480 std::vector<int>::const_iterator pit;
482 std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> cluster_vec;
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++) {
489 cloud_cluster->points.push_back(input_cloud->points[*pit]);
496 cluster_vec.push_back(cloud_cluster);
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);
507 std_msgs::Float32MultiArray cc;
508 for (
int i = 0; i < 6; i++) {
510 cluster_vec[i]->points[cluster_vec[i]->points.size() / 2].x);
512 cluster_vec[i]->points[cluster_vec[i]->points.size() / 2].y);
514 cluster_vec[i]->points[cluster_vec[i]->points.size() / 2].z);
516 cout <<
"6 clusters initialized\n";
521 bool publishedCluster[6];
522 for (
auto it =
objID.begin(); it !=
objID.end(); it++) {
523 cout <<
"Inside the for loop\n";
526 cout <<
"Inside the switch case\n";
529 publishedCluster[i] =
536 publishedCluster[i] =
543 publishedCluster[i] =
550 publishedCluster[i] =
557 publishedCluster[i] =
565 publishedCluster[i] =
577 int main(
int argc,
char **argv) {
585 cout <<
"About to setup callback\n";