33 #include <Eigen/Eigen> 
   34 #include <pcl/filters/project_inliers.h> 
   35 #include <pcl/surface/convex_hull.h> 
   42                   const pcl::ModelCoefficients::Ptr model,
 
   43                   pcl::PointCloud<pcl::PointXYZRGB>& output,
 
   44                   shape_msgs::SolidPrimitive& shape,
 
   45                   geometry_msgs::Pose& 
pose)
 
   48   double min_volume = 1000.0;  
 
   49   Eigen::Matrix3f transformation;  
 
   53   for (
size_t i = 0; i < input.size(); ++i)
 
   55     Eigen::Vector4f pp(input[i].x, input[i].
y, input[i].z, 1);
 
   56     Eigen::Vector4f m(model->values[0], model->values[1], model->values[2], model->values[3]);
 
   57     double distance_to_plane = fabs(pp.dot(m));
 
   58     if (distance_to_plane > 
height)
 
   59       height = distance_to_plane;
 
   63   pcl::PointCloud<pcl::PointXYZRGB>::Ptr flat(
new pcl::PointCloud<pcl::PointXYZRGB>);
 
   64   pcl::ProjectInliers<pcl::PointXYZRGB> projection;
 
   65   projection.setModelType(pcl::SACMODEL_PLANE);
 
   66   projection.setInputCloud(input.makeShared());  
 
   67   projection.setModelCoefficients(model);
 
   68   projection.filter(*flat);
 
   71   pcl::PointCloud<pcl::PointXYZRGB>::Ptr flat_projected(
new pcl::PointCloud<pcl::PointXYZRGB>);
 
   72   Eigen::Vector3f normal(model->values[0], model->values[1], model->values[2]);
 
   73   Eigen::Quaternionf qz; qz.setFromTwoVectors(normal, Eigen::Vector3f::UnitZ());
 
   74   Eigen::Matrix3f plane_rotation = qz.toRotationMatrix();
 
   75   Eigen::Matrix3f inv_plane_rotation = plane_rotation.inverse();
 
   77   for (
size_t i = 0; i < flat->size(); ++i)
 
   80     p.getVector3fMap() = plane_rotation * (*flat)[i].getVector3fMap();
 
   81     flat_projected->push_back(p);
 
   85   pcl::PointCloud<pcl::PointXYZRGB> hull;
 
   86   pcl::ConvexHull<pcl::PointXYZRGB> convex_hull;
 
   87   convex_hull.setInputCloud(flat_projected);
 
   88   convex_hull.setDimension(2);
 
   89   convex_hull.reconstruct(hull);
 
   92   shape_msgs::SolidPrimitive rect;  
 
   94   rect.dimensions.resize(3);
 
   95   for (
size_t i = 0; i < hull.size() - 1; ++i)
 
   98     double rise = hull[i+1].y - hull[i].y;
 
   99     double run = hull[i+1].x - hull[i].x;
 
  102       double l = sqrt((rise * rise) + (
run * 
run));
 
  108     Eigen::Matrix3f rotation;
 
  109     rotation(0, 0) = 
run;
 
  110     rotation(0, 1) = rise;
 
  111     rotation(0, 2) = 0.0;
 
  112     rotation(1, 0) = -rise;
 
  113     rotation(1, 1) = 
run;
 
  114     rotation(1, 2) = 0.0;
 
  115     rotation(2, 0) = 0.0;
 
  116     rotation(2, 1) = 0.0;
 
  117     rotation(2, 2) = 1.0;
 
  118     Eigen::Matrix3f inv_rotation = rotation.inverse();
 
  121     pcl::PointCloud<pcl::PointXYZRGB> projected_cloud;
 
  122     for (
size_t j = 0; j < hull.size(); ++j)
 
  125       p.getVector3fMap() = rotation * hull[j].getVector3fMap();
 
  126       projected_cloud.push_back(p);
 
  130     double x_min = 1000.0;
 
  131     double x_max = -1000.0;
 
  132     double y_min = 1000.0;
 
  133     double y_max = -1000.0;
 
  134     for (
size_t j = 0; j < projected_cloud.size(); ++j)
 
  136       if (projected_cloud[j].x < x_min)
 
  137         x_min = projected_cloud[j].x;
 
  138       if (projected_cloud[j].x > x_max)
 
  139         x_max = projected_cloud[j].x;
 
  141       if (projected_cloud[j].
y < y_min)
 
  142         y_min = projected_cloud[j].y;
 
  143       if (projected_cloud[j].
y > y_max)
 
  144         y_max = projected_cloud[j].y;
 
  148     double area = (x_max - x_min) * (y_max - y_min);
 
  149     if (area*
height < min_volume)
 
  151       transformation = inv_plane_rotation * inv_rotation;
 
  153       rect.dimensions[0] = (x_max - x_min);
 
  154       rect.dimensions[1] = (y_max - y_min);
 
  155       rect.dimensions[2] = 
height;
 
  157       Eigen::Vector3f pose3f((x_max + x_min)/2.0, (y_max + y_min)/2.0,
 
  158                              projected_cloud[0].z + 
height/2.0);
 
  159       pose3f = transformation * pose3f;
 
  160       pose.position.x = pose3f(0);
 
  161       pose.position.y = pose3f(1);
 
  162       pose.position.z = pose3f(2);
 
  164       Eigen::Quaternionf q(transformation);
 
  165       pose.orientation.x = q.x();
 
  166       pose.orientation.y = q.y();
 
  167       pose.orientation.z = q.z();
 
  168       pose.orientation.w = q.w();
 
  170       min_volume = area * 
height;
 
  176   shape_msgs::SolidPrimitive cylinder;  
 
  177   cylinder.type = cylinder.CYLINDER;
 
  178   cylinder.dimensions.resize(2);
 
  179   for (
size_t i = 0; i < hull.size(); ++i)
 
  181     for (
size_t j = i + 1; j < hull.size(); ++j)
 
  186       p.x = (hull[i].x + hull[j].x) / 2.0;
 
  187       p.y = (hull[i].y + hull[j].y) / 2.0;
 
  190       for (
size_t k = 0; k < hull.size(); ++k)
 
  192         double dx = hull[k].x - p.x;
 
  193         double dy = hull[k].y - p.y;
 
  194         double r = sqrt((
dx * 
dx) + (
dy * 
dy));
 
  199       double volume = M_PI * radius * radius * 
height;
 
  200       if (volume < min_volume)
 
  202         transformation = inv_plane_rotation;
 
  204         cylinder.dimensions[0] = 
height;
 
  205         cylinder.dimensions[1] = radius;
 
  207         Eigen::Vector3f pose3f(p.x, p.y, hull[0].z + 
height/2.0);
 
  208         pose3f = transformation * pose3f;
 
  209         pose.position.x = pose3f(0);
 
  210         pose.position.y = pose3f(1);
 
  211         pose.position.z = pose3f(2);
 
  222   Eigen::Vector3f origin(
pose.position.x, 
pose.position.y, 
pose.position.z);
 
  223   for (
size_t j = 0; j < input.size(); ++j)
 
  226     p.getVector3fMap() = transformation * (input[j].getVector3fMap() - origin);
 
  233                   pcl::PointCloud<pcl::PointXYZRGB>& output,
 
  234                   shape_msgs::SolidPrimitive& shape,
 
  235                   geometry_msgs::Pose& 
pose)
 
  238   pcl::ModelCoefficients::Ptr coefficients(
new pcl::ModelCoefficients);
 
  239   coefficients->values.resize(4);
 
  240   coefficients->values[0] = 0.0;
 
  241   coefficients->values[1] = 0.0;
 
  242   coefficients->values[2] = 1.0;
 
  243   coefficients->values[3] = 1000.0;  
 
  244   for (
size_t i = 0; i < input.size(); ++i)
 
  246     if (input[i].z < coefficients->
values[3])
 
  247       coefficients->values[3] = input[i].z;
 
  249   coefficients->values[3] = -coefficients->values[3];
 
  254                                   shape_msgs::SolidPrimitive& shape,
 
  255                                   geometry_msgs::Pose& 
pose)
 
  257   double x_min = 1000.0;
 
  258   double x_max = -1000.0;
 
  259   double y_min = 1000.0;
 
  260   double y_max = -1000.0;
 
  261   double z_min = 1000.0;
 
  262   double z_max = -1000.0;
 
  264   for (
size_t i = 0; i < input.size(); ++i)
 
  266     if (input[i].x < x_min)
 
  268     if (input[i].x > x_max)
 
  271     if (input[i].
y < y_min)
 
  273     if (input[i].
y > y_max)
 
  276     if (input[i].z < z_min)
 
  278     if (input[i].z > z_max)
 
  282   pose.position.x = (x_min + x_max)/2.0;
 
  283   pose.position.y = (y_min + y_max)/2.0;
 
  284   pose.position.z = (z_min + z_max)/2.0;
 
  286   shape.type = shape.BOX;
 
  287   shape.dimensions.push_back(x_max-x_min);
 
  288   shape.dimensions.push_back(y_max-y_min);
 
  289   shape.dimensions.push_back(z_max-z_min);