26 #define TARGET_NUM_CIRCLES 4 
   28 #include <dynamic_reconfigure/server.h> 
   31 #include <pcl/common/transforms.h> 
   32 #include <pcl/filters/extract_indices.h> 
   33 #include <pcl/sample_consensus/sac_model_plane.h> 
   34 #include <pcl/segmentation/sac_segmentation.h> 
   36 #include <pcl_msgs/ModelCoefficients.h> 
   37 #include <pcl_msgs/PointIndices.h> 
   39 #include <sensor_msgs/PointCloud2.h> 
   40 #include <std_msgs/Empty.h> 
   41 #include <velo2cam_calibration/StereoConfig.h> 
   42 #include <velo2cam_calibration/ClusterCentroids.h> 
   73 void callback(
const PointCloud2::ConstPtr &camera_cloud,
 
   74               const pcl_msgs::ModelCoefficients::ConstPtr &cam_plane_coeffs) {
 
   81   pcl::PointCloud<pcl::PointXYZ>::Ptr cam_cloud(
 
   82       new pcl::PointCloud<pcl::PointXYZ>());
 
   88   Eigen::VectorXf coefficients_v(4);
 
   89   coefficients_v(0) = cam_plane_coeffs->values[0];
 
   90   coefficients_v(1) = cam_plane_coeffs->values[1];
 
   91   coefficients_v(2) = cam_plane_coeffs->values[2];
 
   92   coefficients_v(3) = cam_plane_coeffs->values[3];
 
   94   pcl::PointCloud<pcl::PointXYZ>::Ptr cam_plane_cloud(
 
   95       new pcl::PointCloud<pcl::PointXYZ>());
 
   96   pcl::SampleConsensusModelPlane<pcl::PointXYZ>::Ptr dit(
 
   97       new pcl::SampleConsensusModelPlane<pcl::PointXYZ>(cam_cloud));
 
   98   std::vector<int> plane_inliers;
 
  101   pcl::copyPointCloud<pcl::PointXYZ>(*cam_cloud, plane_inliers,
 
  106     PointCloud2 plane_edges_ros;
 
  108     plane_edges_ros.header = camera_cloud->header;
 
  112   pcl::PointCloud<pcl::PointXYZ>::Ptr temp_cloud(
 
  113       new pcl::PointCloud<pcl::PointXYZ>);
 
  114   pcl::ModelCoefficients::Ptr coefficients(
new pcl::ModelCoefficients);
 
  115   pcl::PointIndices::Ptr inliers(
new pcl::PointIndices);
 
  116   pcl::ExtractIndices<pcl::PointXYZ> extract;
 
  119   pcl::PointCloud<pcl::PointXYZ>::Ptr xy_cloud(
 
  120       new pcl::PointCloud<pcl::PointXYZ>);
 
  121   Eigen::Vector3f xy_plane_normal_vector, floor_plane_normal_vector;
 
  122   xy_plane_normal_vector[0] = 0.0;
 
  123   xy_plane_normal_vector[1] = 0.0;
 
  124   xy_plane_normal_vector[2] = -1.0;
 
  126   floor_plane_normal_vector[0] = cam_plane_coeffs->values[0];
 
  127   floor_plane_normal_vector[1] = cam_plane_coeffs->values[1];
 
  128   floor_plane_normal_vector[2] = cam_plane_coeffs->values[2];
 
  130   std::vector<int> indices;
 
  131   pcl::removeNaNFromPointCloud(*cam_plane_cloud, *cam_plane_cloud, indices);
 
  133   Eigen::Affine3f rotation =
 
  135   pcl::transformPointCloud(*cam_plane_cloud, *xy_cloud, rotation);
 
  137   pcl::PointCloud<pcl::PointXYZ>::Ptr aux_cloud(
 
  138       new pcl::PointCloud<pcl::PointXYZ>);
 
  139   pcl::PointXYZ aux_point;
 
  142   aux_point.z = (-coefficients_v(3) / coefficients_v(2));
 
  143   aux_cloud->push_back(aux_point);
 
  145   pcl::PointCloud<pcl::PointXYZ>::Ptr auxrotated_cloud(
 
  146       new pcl::PointCloud<pcl::PointXYZ>);
 
  147   pcl::transformPointCloud(*aux_cloud, *auxrotated_cloud, rotation);
 
  149   double zcoord_xyplane = auxrotated_cloud->at(0).z;
 
  152   for (pcl::PointCloud<pcl::PointXYZ>::iterator pt = xy_cloud->points.begin();
 
  153        pt < xy_cloud->points.end(); ++pt) {
 
  154     pt->z = zcoord_xyplane;
 
  159     PointCloud2 xy_pattern_ros;
 
  161     xy_pattern_ros.header = camera_cloud->header;
 
  166   pcl::SACSegmentation<pcl::PointXYZ> seg;
 
  168   seg.setModelType(pcl::SACMODEL_CIRCLE2D);
 
  170   seg.setMethodType(pcl::SAC_RANSAC);
 
  171   seg.setOptimizeCoefficients(
true);
 
  172   seg.setMaxIterations(1000);
 
  176   pcl::PointCloud<pcl::PointXYZ>::Ptr circle_cloud(
 
  177       new pcl::PointCloud<pcl::PointXYZ>);
 
  179   std::vector<std::vector<float>> found_centers;
 
  182     seg.setInputCloud(xy_cloud);
 
  183     seg.segment(*inliers, *coefficients);
 
  184     if (inliers->indices.size() == 0) {
 
  185       if (found_centers.size() < 1) {
 
  187             "[Stereo] Could not estimate a circle model for the given " 
  193         ROS_INFO(
"[Stereo] Found circle: %lu inliers", inliers->indices.size());
 
  197     extract.setInputCloud(xy_cloud);
 
  198     extract.setIndices(inliers);
 
  199     extract.setNegative(
false);
 
  200     extract.filter(*circle_cloud);
 
  203     pcl::PointXYZ center;
 
  204     center.x = *coefficients->values.begin();
 
  205     center.y = *(coefficients->values.begin() + 1);
 
  206     center.z = zcoord_xyplane;
 
  208     std::vector<float> found_center;
 
  209     found_center.push_back(center.x);
 
  210     found_center.push_back(center.y);
 
  211     found_center.push_back(center.z);
 
  212     found_centers.push_back(found_center);
 
  215     extract.setNegative(
true);
 
  216     extract.filter(*temp_cloud);
 
  217     xy_cloud.swap(temp_cloud);
 
  219   } 
while (xy_cloud->points.size() > 3);
 
  221   if (found_centers.size() <
 
  224     ROS_WARN(
"Not enough centers: %ld", found_centers.size());
 
  238   std::vector<std::vector<int>> groups;
 
  240   double groups_scores[groups.size()];  
 
  241   for (
int i = 0; i < groups.size(); ++i) {
 
  242     std::vector<pcl::PointXYZ> candidates;
 
  244     for (
int j = 0; j < groups[i].size(); ++j) {
 
  245       pcl::PointXYZ center;
 
  246       center.x = found_centers[groups[i][j]][0];
 
  247       center.y = found_centers[groups[i][j]][1];
 
  248       center.z = found_centers[groups[i][j]][2];
 
  249       candidates.push_back(center);
 
  255     groups_scores[i] = square_candidate.
is_valid()
 
  260   int best_candidate_idx = -1;
 
  261   double best_candidate_score = -1;
 
  262   for (
int i = 0; i < groups.size(); ++i) {
 
  263     if (best_candidate_score == 1 && groups_scores[i] == 1) {
 
  266           "[Stereo] More than one set of candidates fit target's geometry. " 
  267           "Please, make sure your parameters are well set. Exiting callback");
 
  270     if (groups_scores[i] > best_candidate_score) {
 
  271       best_candidate_score = groups_scores[i];
 
  272       best_candidate_idx = i;
 
  276   if (best_candidate_idx == -1) {
 
  279         "[Stereo] Unable to find a candidate set that matches target's " 
  284   pcl::PointCloud<pcl::PointXYZ>::Ptr rotated_back_cloud(
 
  285       new pcl::PointCloud<pcl::PointXYZ>());
 
  286   for (
int j = 0; j < groups[best_candidate_idx].size(); ++j) {
 
  288     point.x = found_centers[groups[best_candidate_idx][j]][0];
 
  289     point.y = found_centers[groups[best_candidate_idx][j]][1];
 
  290     point.z = found_centers[groups[best_candidate_idx][j]][2];
 
  292     pcl::PointXYZ center_rotated_back =
 
  293         pcl::transformPoint(point, rotation.inverse());
 
  294     center_rotated_back.z =
 
  295         (-cam_plane_coeffs->values[0] * center_rotated_back.x -
 
  296          cam_plane_coeffs->values[1] * center_rotated_back.y -
 
  297          cam_plane_coeffs->values[3]) /
 
  298         cam_plane_coeffs->values[2];
 
  300     rotated_back_cloud->push_back(center_rotated_back);
 
  305     std::vector<pcl::PointXYZ> sorted_centers;
 
  307     for (std::vector<pcl::PointXYZ>::iterator it = sorted_centers.begin();
 
  308          it < sorted_centers.end(); ++it) {
 
  309       savefile << it->x << 
", " << it->y << 
", " << it->z << 
", ";
 
  315     PointCloud2 cumulative_ros;
 
  317     cumulative_ros.header = camera_cloud->header;
 
  321   pcl_msgs::PointIndices p_ind;
 
  324   p_ind.header = camera_cloud->header;
 
  326   pcl_msgs::ModelCoefficients m_coeff;
 
  329   m_coeff.header = camera_cloud->header;
 
  341   pcl::PointCloud<pcl::PointXYZ>::Ptr final_cloud(
 
  342       new pcl::PointCloud<pcl::PointXYZ>);
 
  359       std::vector<pcl::PointXYZ> sorted_centers;
 
  361       for (std::vector<pcl::PointXYZ>::iterator it = sorted_centers.begin();
 
  362            it < sorted_centers.end(); ++it) {
 
  363         savefile << it->x << 
", " << it->y << 
", " << it->z << 
", ";
 
  368     sensor_msgs::PointCloud2 final_ros;
 
  370     final_ros.header = camera_cloud->header;
 
  372     velo2cam_calibration::ClusterCentroids to_send;
 
  373     to_send.header = camera_cloud->header;
 
  376     to_send.cloud = final_ros;
 
  402     ROS_INFO(
"[Stereo] Warm up done, pattern detection started");
 
  404     ROS_INFO(
"[Stereo] Detection stopped. Warm up mode activated");
 
  408 int main(
int argc, 
char **argv) {
 
  415       cam_plane_coeffs_sub_;
 
  418   cam_plane_coeffs_sub_.
subscribe(
nh_, 
"cam_plane_coeffs", 1);
 
  429       nh_.
advertise<velo2cam_calibration::ClusterCentroids>(
"centers_cloud", 1);
 
  432       pcl::PointCloud<pcl::PointXYZ>::Ptr(
new pcl::PointCloud<pcl::PointXYZ>);
 
  435                                                     pcl_msgs::ModelCoefficients>
 
  438                                               cam_plane_coeffs_sub_);
 
  455   dynamic_reconfigure::Server<velo2cam_calibration::StereoConfig> server;
 
  456   dynamic_reconfigure::Server<velo2cam_calibration::StereoConfig>::CallbackType
 
  459   server.setCallback(
f);
 
  472     os << getenv(
"HOME") << 
"/v2c_experiments/" << csv_name;
 
  476       savefile << 
"det1_x, det1_y, det1_z, det2_x, det2_y, det2_z, det3_x, " 
  477                   "det3_y, det3_z, det4_x, det4_y, det4_z, cent1_x, cent1_y, " 
  478                   "cent1_z, cent2_x, cent2_y, cent2_z, cent3_x, cent3_y, " 
  479                   "cent3_z, cent4_x, cent4_y, cent4_z, it"