36 #define BOOST_PARAMETER_MAX_ARITY 7 
   39 #include <boost/tuple/tuple_comparison.hpp> 
   44     convex_(plane), resolution_(resolution)
 
   55     const Eigen::Vector3f& 
p)
 
   61     return boost::make_tuple<int, int>(boost::math::round(
p[0] / 
resolution_),
 
   73     for (std::set<IndexPair>::iterator it = 
cells_.begin();
 
   77       for (
int xi = - 
num; xi <= 
num; xi++) {
 
   78         for (
int yi = - 
num; yi <= 
num; yi++) {
 
   79           if (abs(xi) + abs(yi) <= 
num) {
 
   80             IndexPair new_pair = boost::make_tuple<int, int>(
 
   81               the_index.get<0>() + xi,
 
   82               the_index.get<1>() + yi);
 
   83             ret->cells_.insert(new_pair);
 
   94     for (std::set<IndexPair>::iterator it = 
cells_.begin();
 
   98       bool should_removed = 
false;
 
   99       for (
int xi = - 
num; xi <= 
num; xi++) {
 
  100         for (
int yi = - 
num; yi <= 
num; yi++) {
 
  101           if (abs(xi) + abs(yi) <= 
num) {
 
  102             IndexPair check_pair = boost::make_tuple<int, int>(
 
  103               the_index.get<0>() + xi,
 
  104               the_index.get<1>() + yi);
 
  106               should_removed = 
true;
 
  111       if (!should_removed) {
 
  112         ret->cells_.insert(the_index);
 
  154     return Eigen::Vector3f(pair.get<0>() * 
resolution_,
 
  163     return convex_->coordinates() * local_point;
 
  176     Vertices global_vertices = intersect_polygon->getVertices();
 
  177     Eigen::Affine3f inv_coords = 
convex_->coordinates().inverse();
 
  178     for (
size_t i = 0; 
i < global_vertices.size(); 
i++) {
 
  179       local_vertices.push_back(inv_coords * global_vertices[
i]);
 
  183     double min_x = DBL_MAX;
 
  184     double min_y = DBL_MAX;
 
  185     double max_x = - DBL_MAX;
 
  186     double max_y = - DBL_MAX;
 
  187     for (
size_t i = 0; 
i < local_vertices.size(); 
i++) {
 
  188       min_x = ::fmin(min_x, local_vertices[
i][0]);
 
  189       min_y = ::fmin(min_y, local_vertices[
i][1]);
 
  190       max_x = ::fmax(max_x, local_vertices[
i][0]);
 
  191       max_y = ::fmax(max_y, local_vertices[
i][1]);
 
  196     std::vector<Polygon::Ptr> triangles
 
  197       = intersect_polygon->decomposeToTriangles();
 
  198     for (
double x = min_x; x <= max_x; x += 
resolution_) {
 
  199       for (
double y = min_y; y <= max_y; y += 
resolution_) {
 
  200         Eigen::Vector3f local_p(x, y, 0);
 
  201         Eigen::Vector3f 
p = 
convex_->coordinates() * local_p;
 
  203         bool insidep = 
false;
 
  204         for (
size_t i = 0; 
i < triangles.size(); 
i++) {
 
  205           if (triangles[
i]->isInside(
p)) {
 
  219     pcl::PointCloud<pcl::PointNormal>::Ptr& cloud,
 
  220     double distance_threshold,
 
  221     std::set<int>& non_plane_indices)
 
  224       cloud, distance_threshold, M_PI / 2.0, non_plane_indices);
 
  228     pcl::PointCloud<pcl::PointNormal>::Ptr& cloud,
 
  229     double distance_threshold,
 
  230     double normal_threshold,
 
  231     std::set<int>& non_plane_indices)
 
  233     Eigen::Affine3f local_coordinates = 
convex_->coordinates();
 
  234     Eigen::Affine3f inv_local_coordinates = local_coordinates.inverse();
 
  237     pcl::ExtractPolygonalPrismData<pcl::PointNormal> prism_extract;
 
  238     pcl::PointCloud<pcl::PointNormal>::Ptr
 
  239       hull_cloud (
new pcl::PointCloud<pcl::PointNormal>);
 
  240     pcl::PointCloud<pcl::PointNormal>::Ptr
 
  241       hull_output (
new pcl::PointCloud<pcl::PointNormal>);
 
  242     pcl::PointCloud<pcl::PointNormal>::Ptr
 
  243       rehull_cloud (
new pcl::PointCloud<pcl::PointNormal>);
 
  244     convex_->boundariesToPointCloud<pcl::PointNormal>(*hull_cloud);
 
  252     hull_cloud->points.push_back(hull_cloud->points[0]);
 
  254     prism_extract.setInputCloud(cloud);
 
  255     prism_extract.setHeightLimits(-distance_threshold, distance_threshold);
 
  256     prism_extract.setInputPlanarHull(hull_cloud);
 
  259     pcl::PointIndices output_indices;
 
  260     prism_extract.segment(output_indices);
 
  261     std::set<int> output_set(output_indices.indices.begin(),
 
  262                              output_indices.indices.end());
 
  263     Eigen::Vector3f n = 
convex_->getNormal();
 
  264     for (
size_t i = 0; 
i < cloud->points.size(); 
i++) {
 
  265       if (output_set.find(
i) != output_set.end()) {
 
  267         pcl::PointNormal 
p = cloud->points[
i];
 
  268         Eigen::Vector3f n_p = 
p.getNormalVector3fMap();
 
  269         if (std::abs(n.dot(n_p)) > cos(normal_threshold)) {
 
  270           non_plane_indices.insert(
i);
 
  276     for (
size_t i = 0; 
i < output_indices.indices.size(); 
i++) {
 
  278       int point_index = output_indices.indices[
i];
 
  279       pcl::PointNormal 
p = cloud->points[point_index];
 
  280       Eigen::Vector3f ep = 
p.getVector3fMap();
 
  281       Eigen::Vector3f local_ep = inv_local_coordinates * ep;
 
  285     return output_indices.indices.size();
 
  289     pcl::PointCloud<pcl::PointNormal>::Ptr& cloud,
 
  290     double distance_threshold)
 
  298     jsk_recognition_msgs::SimpleOccupancyGrid ros_msg;
 
  299     std::vector<float> coeff;
 
  300     convex_->toCoefficients(coeff);
 
  302     ros_msg.coefficients[0] = coeff[0];
 
  303     ros_msg.coefficients[1] = coeff[1];
 
  304     ros_msg.coefficients[2] = coeff[2];
 
  305     ros_msg.coefficients[3] = coeff[3];
 
  307     for (std::set<IndexPair>::iterator it = 
cells_.begin();
 
  312       geometry_msgs::Point 
p;
 
  313       pointFromVectorToXYZ<Eigen::Vector3f, geometry_msgs::Point>(
 
  315       ros_msg.cells.push_back(
p);
 
  321     const jsk_recognition_msgs::SimpleOccupancyGrid& rosmsg,
 
  322     const Eigen::Affine3f& offset = Eigen::Affine3f::Identity())
 
  336     Eigen::Affine3f plane_coords = plane.
coordinates();
 
  337     Eigen::Vector3f plane_origin(plane_coords.translation());
 
  340     pcl::PointCloud<pcl::PointNormal>::Ptr
 
  341       vertices (
new pcl::PointCloud<pcl::PointNormal>);
 
  342     for (
size_t i = 0; 
i < rosmsg.cells.size(); 
i++) {
 
  343       Eigen::Vector3f local_p(rosmsg.cells[
i].x, rosmsg.cells[
i].y, 0);
 
  344       Eigen::Vector3f global_p = plane.
coordinates() * local_p;
 
  352       vertices->points.push_back(
p);
 
  354     pcl::ConvexHull<pcl::PointNormal> chull;
 
  356     chull.setInputCloud (vertices);
 
  357     pcl::PointCloud<pcl::PointNormal>::Ptr
 
  358       convex_vertices_cloud (
new pcl::PointCloud<pcl::PointNormal>);
 
  359     chull.reconstruct (*convex_vertices_cloud);
 
  362       = pointCloudToVertices<pcl::PointNormal>(*convex_vertices_cloud);
 
  365     if (!convex->isSameDirection(plane)) {
 
  369       std::reverse_copy(convex_vertices.begin(), convex_vertices.end(),
 
  370                         std::back_inserter(reversed_convex_vertices));
 
  373     Eigen::Vector3f convex_origin(convex->coordinates().translation());
 
  374     Eigen::Vector3f convex_normal = convex->getNormal();
 
  379     GridPlane ret(convex, rosmsg.resolution);