26 #define PCL_NO_PRECOMPILE 
   28 #include <dynamic_reconfigure/server.h> 
   29 #include <pcl/common/eigen.h> 
   30 #include <pcl/common/transforms.h> 
   31 #include <pcl/filters/extract_indices.h> 
   32 #include <pcl/filters/passthrough.h> 
   33 #include <pcl/point_cloud.h> 
   34 #include <pcl/point_types.h> 
   35 #include <pcl/segmentation/sac_segmentation.h> 
   38 #include <sensor_msgs/PointCloud2.h> 
   39 #include <std_msgs/Empty.h> 
   40 #include <velo2cam_calibration/ClusterCentroids.h> 
   41 #include <velo2cam_calibration/LidarConfig.h> 
   74 void callback(
const PointCloud2::ConstPtr &laser_cloud) {
 
   77   pcl::PointCloud<Velodyne::Point>::Ptr velocloud(
 
   78       new pcl::PointCloud<Velodyne::Point>),
 
   79       velo_filtered(
new pcl::PointCloud<Velodyne::Point>),
 
   80       pattern_cloud(
new pcl::PointCloud<Velodyne::Point>),
 
   81       edges_cloud(
new pcl::PointCloud<Velodyne::Point>);
 
   91   pcl::PassThrough<Velodyne::Point> pass2;
 
   92   pass2.setInputCloud(velocloud);
 
   93   pass2.setFilterFieldName(
"range");
 
   95   pass2.filter(*velo_filtered);
 
   98   sensor_msgs::PointCloud2 range_ros;
 
  100   range_ros.header = laser_cloud->header;
 
  104   pcl::ModelCoefficients::Ptr coefficients(
new pcl::ModelCoefficients);
 
  105   pcl::PointIndices::Ptr inliers(
new pcl::PointIndices);
 
  107   pcl::SACSegmentation<Velodyne::Point> plane_segmentation;
 
  108   plane_segmentation.setModelType(pcl::SACMODEL_PARALLEL_PLANE);
 
  110   plane_segmentation.setMethodType(pcl::SAC_RANSAC);
 
  111   plane_segmentation.setAxis(Eigen::Vector3f(
axis_[0], 
axis_[1], 
axis_[2]));
 
  113   plane_segmentation.setOptimizeCoefficients(
true);
 
  114   plane_segmentation.setMaxIterations(1000);
 
  115   plane_segmentation.setInputCloud(velo_filtered);
 
  116   plane_segmentation.segment(*inliers, *coefficients);
 
  118   if (inliers->indices.size() == 0) {
 
  121         "[LiDAR] Could not estimate a planar model for the given dataset.");
 
  126   Eigen::VectorXf coefficients_v(4);
 
  127   coefficients_v(0) = coefficients->values[0];
 
  128   coefficients_v(1) = coefficients->values[1];
 
  129   coefficients_v(2) = coefficients->values[2];
 
  130   coefficients_v(3) = coefficients->values[3];
 
  133   vector<vector<Velodyne::Point *>> rings =
 
  135   for (vector<vector<Velodyne::Point *>>::iterator ring = rings.begin();
 
  136        ring < rings.end(); ++ring) {
 
  138     if (ring->empty()) 
continue;
 
  140     (*ring->begin())->intensity = 0;
 
  142     for (vector<Velodyne::Point *>::iterator pt = ring->begin() + 1;
 
  143          pt < ring->end() - 1; pt++) {
 
  147           max(max(prev->
range - (*pt)->range, succ->
range - (*pt)->range), 0.f);
 
  153   for (pcl::PointCloud<Velodyne::Point>::iterator pt =
 
  154            velocloud->points.begin();
 
  155        pt < velocloud->points.end(); ++pt) {
 
  156     if (pt->intensity > THRESHOLD) {
 
  157       edges_cloud->push_back(*pt);
 
  161   if (edges_cloud->points.size() == 0) {
 
  163     ROS_WARN(
"[LiDAR] Could not detect pattern edges.");
 
  168   pcl::SampleConsensusModelPlane<Velodyne::Point>::Ptr dit(
 
  169       new pcl::SampleConsensusModelPlane<Velodyne::Point>(edges_cloud));
 
  170   std::vector<int> inliers2;
 
  172   pcl::copyPointCloud<Velodyne::Point>(*edges_cloud, inliers2, *pattern_cloud);
 
  176   pcl::PointCloud<pcl::PointXYZ>::Ptr circles_cloud(
 
  177       new pcl::PointCloud<pcl::PointXYZ>),
 
  178       xy_cloud(
new pcl::PointCloud<pcl::PointXYZ>),
 
  179       aux_cloud(
new pcl::PointCloud<pcl::PointXYZ>),
 
  180       auxrotated_cloud(
new pcl::PointCloud<pcl::PointXYZ>),
 
  181       cloud_f(
new pcl::PointCloud<pcl::PointXYZ>),
 
  182       centroid_candidates(
new pcl::PointCloud<pcl::PointXYZ>);
 
  184   vector<vector<Velodyne::Point *>> rings2 =
 
  188   for (vector<vector<Velodyne::Point *>>::iterator ring = rings2.begin();
 
  189        ring < rings2.end(); ++ring) {
 
  190     for (vector<Velodyne::Point *>::iterator pt = ring->begin();
 
  191          pt < ring->end(); ++pt) {
 
  196       circles_cloud->push_back(point);
 
  202     sensor_msgs::PointCloud2 velocloud_ros2;
 
  204     velocloud_ros2.header = laser_cloud->header;
 
  209   Eigen::Vector3f xy_plane_normal_vector, floor_plane_normal_vector;
 
  210   xy_plane_normal_vector[0] = 0.0;
 
  211   xy_plane_normal_vector[1] = 0.0;
 
  212   xy_plane_normal_vector[2] = -1.0;
 
  214   floor_plane_normal_vector[0] = coefficients->values[0];
 
  215   floor_plane_normal_vector[1] = coefficients->values[1];
 
  216   floor_plane_normal_vector[2] = coefficients->values[2];
 
  218   Eigen::Affine3f rotation =
 
  220   pcl::transformPointCloud(*circles_cloud, *xy_cloud, rotation);
 
  225     sensor_msgs::PointCloud2 ros_rotated_pattern;
 
  227     ros_rotated_pattern.header = laser_cloud->header;
 
  232   pcl::PointXYZ aux_point;
 
  235   aux_point.z = (-coefficients_v(3) / coefficients_v(2));
 
  236   aux_cloud->push_back(aux_point);
 
  237   pcl::transformPointCloud(*aux_cloud, *auxrotated_cloud, rotation);
 
  238   double zcoord_xyplane = auxrotated_cloud->at(0).z;
 
  240   for (pcl::PointCloud<pcl::PointXYZ>::iterator pt = xy_cloud->points.begin();
 
  241        pt < xy_cloud->points.end(); ++pt) {
 
  242     pt->z = zcoord_xyplane;
 
  246   pcl::ModelCoefficients::Ptr coefficients3(
new pcl::ModelCoefficients);
 
  247   pcl::PointIndices::Ptr inliers3(
new pcl::PointIndices);
 
  249   pcl::SACSegmentation<pcl::PointXYZ> circle_segmentation;
 
  250   circle_segmentation.setModelType(pcl::SACMODEL_CIRCLE2D);
 
  252   circle_segmentation.setMethodType(pcl::SAC_RANSAC);
 
  253   circle_segmentation.setOptimizeCoefficients(
true);
 
  254   circle_segmentation.setMaxIterations(1000);
 
  255   circle_segmentation.setRadiusLimits(
 
  259   pcl::ExtractIndices<pcl::PointXYZ> extract;
 
  261     ROS_INFO(
"[LiDAR] Searching for points in cloud of size %lu",
 
  262              xy_cloud->points.size());
 
  263   while (xy_cloud->points.size() > 3) {
 
  264     circle_segmentation.setInputCloud(xy_cloud);
 
  265     circle_segmentation.segment(*inliers3, *coefficients3);
 
  266     if (inliers3->indices.size() == 0) {
 
  269             "[LiDAR] Optimized circle segmentation failed, trying unoptimized " 
  271       circle_segmentation.setOptimizeCoefficients(
false);
 
  273       circle_segmentation.setInputCloud(xy_cloud);
 
  274       circle_segmentation.segment(*inliers3, *coefficients3);
 
  277       circle_segmentation.setOptimizeCoefficients(
true);
 
  278       if (inliers3->indices.size() == 0) {
 
  284     pcl::PointXYZ center;
 
  285     center.x = *coefficients3->values.begin();
 
  286     center.y = *(coefficients3->values.begin() + 1);
 
  287     center.z = zcoord_xyplane;
 
  289     centroid_candidates->push_back(center);
 
  292     extract.setInputCloud(xy_cloud);
 
  293     extract.setIndices(inliers3);
 
  294     extract.setNegative(
true);
 
  295     extract.filter(*cloud_f);
 
  296     xy_cloud.swap(cloud_f);
 
  299       ROS_INFO(
"[LiDAR] Remaining points in cloud %lu",
 
  300                xy_cloud->points.size());
 
  305     ROS_WARN(
"[LiDAR] Not enough centers: %ld", centroid_candidates->size());
 
  319   std::vector<std::vector<int>> groups;
 
  321   double groups_scores[groups.size()];  
 
  322   for (
int i = 0; i < groups.size(); ++i) {
 
  323     std::vector<pcl::PointXYZ> candidates;
 
  325     for (
int j = 0; j < groups[i].size(); ++j) {
 
  326       pcl::PointXYZ center;
 
  327       center.x = centroid_candidates->at(groups[i][j]).x;
 
  328       center.y = centroid_candidates->at(groups[i][j]).y;
 
  329       center.z = centroid_candidates->at(groups[i][j]).z;
 
  330       candidates.push_back(center);
 
  336     groups_scores[i] = square_candidate.
is_valid()
 
  341   int best_candidate_idx = -1;
 
  342   double best_candidate_score = -1;
 
  343   for (
int i = 0; i < groups.size(); ++i) {
 
  344     if (best_candidate_score == 1 && groups_scores[i] == 1) {
 
  347           "[LiDAR] More than one set of candidates fit target's geometry. " 
  348           "Please, make sure your parameters are well set. Exiting callback");
 
  351     if (groups_scores[i] > best_candidate_score) {
 
  352       best_candidate_score = groups_scores[i];
 
  353       best_candidate_idx = i;
 
  357   if (best_candidate_idx == -1) {
 
  360         "[LiDAR] Unable to find a candidate set that matches target's " 
  366   pcl::PointCloud<pcl::PointXYZ>::Ptr rotated_back_cloud(
 
  367       new pcl::PointCloud<pcl::PointXYZ>());
 
  368   for (
int j = 0; j < groups[best_candidate_idx].size(); ++j) {
 
  369     pcl::PointXYZ center_rotated_back = pcl::transformPoint(
 
  370         centroid_candidates->at(groups[best_candidate_idx][j]),
 
  372     center_rotated_back.x = (-coefficients->values[1] * center_rotated_back.y -
 
  373                              coefficients->values[2] * center_rotated_back.z -
 
  374                              coefficients->values[3]) /
 
  375                             coefficients->values[0];
 
  377     rotated_back_cloud->push_back(center_rotated_back);
 
  382     std::vector<pcl::PointXYZ> sorted_centers;
 
  384     for (std::vector<pcl::PointXYZ>::iterator it = sorted_centers.begin();
 
  385          it < sorted_centers.end(); ++it) {
 
  386       savefile << it->x << 
", " << it->y << 
", " << it->z << 
", ";
 
  392     sensor_msgs::PointCloud2 ros_pointcloud;
 
  394     ros_pointcloud.header = laser_cloud->header;
 
  404   pcl_msgs::ModelCoefficients m_coeff;
 
  406   m_coeff.header = laser_cloud->header;
 
  414   pcl::PointCloud<pcl::PointXYZ>::Ptr centers_cloud(
 
  415       new pcl::PointCloud<pcl::PointXYZ>);
 
  432     sensor_msgs::PointCloud2 ros2_pointcloud;
 
  434     ros2_pointcloud.header = laser_cloud->header;
 
  436     velo2cam_calibration::ClusterCentroids to_send;
 
  437     to_send.header = laser_cloud->header;
 
  440     to_send.cloud = ros2_pointcloud;
 
  446       std::vector<pcl::PointXYZ> sorted_centers;
 
  448       for (std::vector<pcl::PointXYZ>::iterator it = sorted_centers.begin();
 
  449            it < sorted_centers.end(); ++it) {
 
  450         savefile << it->x << 
", " << it->y << 
", " << it->z << 
", ";
 
  470   ROS_INFO(
"[LiDAR] New passthrough_radius_min_ threshold: %f",
 
  473   ROS_INFO(
"[LiDAR] New passthrough_radius_max_ threshold: %f",
 
  480   ROS_INFO(
"[LiDAR] New normal axis for plane segmentation: %f, %f, %f",
 
  485   ROS_INFO(
"[LiDAR] New minimum distance between centroids: %f",
 
  488   ROS_INFO(
"[LiDAR] New maximum distance between centroids: %f",
 
  495     ROS_INFO(
"[LiDAR] Warm up done, pattern detection started");
 
  497     ROS_INFO(
"[LiDAR] Detection stopped. Warm up mode activated");
 
  501 int main(
int argc, 
char **argv) {
 
  506   pcl::console::setVerbosityLevel(pcl::console::L_ALWAYS);
 
  515       nh_.
advertise<velo2cam_calibration::ClusterCentroids>(
"centers_cloud", 1);
 
  537       pcl::PointCloud<pcl::PointXYZ>::Ptr(
new pcl::PointCloud<pcl::PointXYZ>);
 
  539   dynamic_reconfigure::Server<velo2cam_calibration::LidarConfig> server;
 
  540   dynamic_reconfigure::Server<velo2cam_calibration::LidarConfig>::CallbackType
 
  543   server.setCallback(
f);
 
  556     os << getenv(
"HOME") << 
"/v2c_experiments/" << csv_name;
 
  560       savefile << 
"det1_x, det1_y, det1_z, det2_x, det2_y, det2_z, det3_x, " 
  561                   "det3_y, det3_z, det4_x, det4_y, det4_z, cent1_x, cent1_y, " 
  562                   "cent1_z, cent2_x, cent2_y, cent2_z, cent3_x, cent3_y, " 
  563                   "cent3_z, cent4_x, cent4_y, cent4_z, it"