00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #define BOOST_PARAMETER_MAX_ARITY 7
00037
00038 #include "jsk_recognition_utils/geo/polygon.h"
00039 #include "jsk_recognition_utils/geo_util.h"
00040 #include <jsk_topic_tools/log_utils.h>
00041 #include "jsk_recognition_utils/pcl/ear_clipping_patched.h"
00042 #include "jsk_recognition_utils/sensor_model_utils.h"
00043
00044 namespace jsk_recognition_utils
00045 {
00046 Polygon Polygon::createPolygonWithSkip(const Vertices& vertices)
00047 {
00048 const double thr = 0.01;
00049 Polygon not_skipped_polygon(vertices);
00050 Vertices skipped_vertices;
00051 for (size_t i = 0; i < vertices.size(); i++) {
00052 size_t next_i = not_skipped_polygon.nextIndex(i);
00053 Eigen::Vector3f v0 = vertices[i];
00054 Eigen::Vector3f v1 = vertices[next_i];
00055 if ((v1 - v0).norm() > thr) {
00056 skipped_vertices.push_back(vertices[i]);
00057 }
00058 }
00059 return Polygon(skipped_vertices);
00060 }
00061
00062 Eigen::Vector3f Polygon::centroid()
00063 {
00064 Eigen::Vector3f c(0, 0, 0);
00065 if (vertices_.size() == 0) {
00066 return c;
00067 }
00068 else {
00069 for (size_t i = 0; i < vertices_.size(); i++) {
00070 c = c + vertices_[i];
00071 }
00072 return c / vertices_.size();
00073 }
00074 }
00075
00076 std::vector<Plane::Ptr> convertToPlanes(
00077 std::vector<pcl::ModelCoefficients::Ptr> coefficients)
00078 {
00079 std::vector<Plane::Ptr> ret;
00080 for (size_t i = 0; i < coefficients.size(); i++) {
00081 ret.push_back(Plane::Ptr (new Plane(coefficients[i]->values)));
00082 }
00083 return ret;
00084 }
00085
00086
00087 Polygon::Polygon(const Vertices& vertices):
00088 Plane((vertices[1] - vertices[0]).cross(vertices[2] - vertices[0]).normalized(), vertices[0]),
00089 vertices_(vertices)
00090 {
00091
00092 }
00093
00094 Polygon::Polygon(const Vertices& vertices,
00095 const std::vector<float>& coefficients):
00096 Plane(coefficients), vertices_(vertices)
00097 {
00098
00099 }
00100
00101 Polygon::~Polygon()
00102 {
00103
00104 }
00105
00106 size_t Polygon::getFarestPointIndex(const Eigen::Vector3f& O)
00107 {
00108 double max_distance = - DBL_MAX;
00109 size_t max_index = 0;
00110 for (size_t i = 0; i < vertices_.size(); i++) {
00111 Eigen::Vector3f v = vertices_[i];
00112 double d = (O - v).norm();
00113 if (max_distance < d) {
00114 max_distance = d;
00115 max_index = i;
00116 }
00117 }
00118 return max_index;
00119 }
00120
00121 PointIndexPair Polygon::getNeighborIndex(size_t index)
00122 {
00123 return boost::make_tuple<size_t, size_t>(
00124 previousIndex(index), nextIndex(index));
00125 }
00126
00127 double Polygon::area()
00128 {
00129 if (isTriangle()) {
00130 return (vertices_[1] - vertices_[0]).cross(vertices_[2] - vertices_[0]).norm() / 2.0;
00131 }
00132 else {
00133 std::vector<Polygon::Ptr> triangles = decomposeToTriangles();
00134 double sum = 0;
00135 for (size_t i = 0; i < triangles.size(); i++) {
00136 sum += triangles[i]->area();
00137 }
00138 return sum;
00139 }
00140 }
00141
00142 Eigen::Vector3f Polygon::directionAtPoint(size_t i)
00143 {
00144 Eigen::Vector3f O = vertices_[i];
00145 Eigen::Vector3f A = vertices_[previousIndex(i)];
00146 Eigen::Vector3f B = vertices_[nextIndex(i)];
00147 Eigen::Vector3f OA = A - O;
00148 Eigen::Vector3f OB = B - O;
00149 Eigen::Vector3f n = (OA.normalized()).cross(OB.normalized());
00150 if (n.norm() == 0) {
00151
00152
00153
00154
00155
00156
00157
00158 }
00159 return n.normalized();
00160 }
00161
00162 bool Polygon::isTriangle() {
00163 return vertices_.size() == 3;
00164 }
00165
00166 void Polygon::getLocalMinMax(double& min_x, double& min_y,
00167 double& max_x, double& max_y)
00168 {
00169 min_x = DBL_MAX;
00170 min_y = DBL_MAX;
00171 max_x = - DBL_MAX;
00172 max_y = - DBL_MAX;
00173
00174 Eigen::Affine3f inv_coords = coordinates().inverse();
00175 for (size_t i = 0; i < vertices_.size(); i++) {
00176
00177 Eigen::Vector3f local_point = inv_coords * vertices_[i];
00178 min_x = ::fmin(local_point[0], min_x);
00179 min_y = ::fmin(local_point[1], min_y);
00180 max_x = ::fmax(local_point[0], max_x);
00181 max_y = ::fmax(local_point[1], max_y);
00182 }
00183 }
00184
00185 Eigen::Vector3f Polygon::randomSampleLocalPoint(boost::mt19937& random_generator)
00186 {
00187
00188 double min_x, min_y, max_x, max_y;
00189 getLocalMinMax(min_x, min_y, max_x, max_y);
00190 std::vector<Polygon::Ptr> triangles = decomposeToTriangles();
00191 while (true) {
00192 double x = randomUniform(min_x, max_x, random_generator);
00193 double y = randomUniform(min_y, max_y, random_generator);
00194 Eigen::Vector3f local_v = Eigen::Vector3f(x, y, 0);
00195 Eigen::Vector3f v = coordinates() * local_v;
00196
00197
00198
00199
00200
00201
00202
00203 if (isInside(v)) {
00204 return local_v;
00205 }
00206 else {
00207
00208 }
00209 }
00210 }
00211
00212 std::vector<Segment::Ptr> Polygon::edges() const
00213 {
00214 std::vector<Segment::Ptr> ret;
00215 ret.reserve(vertices_.size());
00216 for (size_t i = 0; i < vertices_.size() - 1; i++) {
00217
00218 ret.push_back(Segment::Ptr(new Segment(vertices_[i], vertices_[i+1])));
00219 }
00220
00221 ret.push_back(Segment::Ptr(new Segment(vertices_[vertices_.size() - 1], vertices_[0])));
00222 return ret;
00223 }
00224
00225 Eigen::Vector3f Polygon::nearestPoint(const Eigen::Vector3f& p,
00226 double& distance)
00227 {
00228 Eigen::Vector3f projected_p;
00229 Plane::project(p, projected_p);
00230 if (isInside(projected_p)) {
00231 distance = (p - projected_p).norm();
00232 return projected_p;
00233 }
00234 else {
00235 std::vector<Segment::Ptr> boundary_edges = edges();
00236 double min_distnace = DBL_MAX;
00237 Eigen::Vector3f nearest_point;
00238
00239 for (size_t i = 0; i < boundary_edges.size(); i++) {
00240 Segment::Ptr edge = boundary_edges[i];
00241 Eigen::Vector3f foot;
00242 double d = edge->distance(p, foot);
00243 if (min_distnace > d) {
00244 nearest_point = foot;
00245 min_distnace = d;
00246 }
00247 }
00248 distance = min_distnace;
00249 return nearest_point;
00250 }
00251 }
00252
00253 size_t Polygon::getNumVertices() {
00254 return vertices_.size();
00255 }
00256
00257 Eigen::Vector3f Polygon::getVertex(size_t i) {
00258 return vertices_[i];
00259 }
00260
00261 Polygon::PtrPair Polygon::separatePolygon(size_t index)
00262 {
00263 PointIndexPair neighbor_index = getNeighborIndex(index);
00264 Vertices triangle_vertices;
00265 triangle_vertices.push_back(vertices_[index]);
00266 triangle_vertices.push_back(vertices_[neighbor_index.get<1>()]);
00267 triangle_vertices.push_back(vertices_[neighbor_index.get<0>()]);
00268 Polygon::Ptr triangle(new Polygon(triangle_vertices));
00269 Vertices rest_vertices;
00270
00271 for (size_t i = neighbor_index.get<1>(); i != index;) {
00272
00273 if (i == neighbor_index.get<1>()) {
00274 rest_vertices.push_back(vertices_[i]);
00275 }
00276 else {
00277 if (directionAtPoint(i).norm() != 0.0) {
00278 rest_vertices.push_back(vertices_[i]);
00279 }
00280 else {
00281 JSK_ROS_ERROR("removed: %lu", i);
00282 }
00283 }
00284 i = nextIndex(i);
00285 }
00286 Polygon::Ptr rest(new Polygon(rest_vertices));
00287 return boost::make_tuple<Polygon::Ptr, Polygon::Ptr>(
00288 triangle, rest);
00289 }
00290
00291 bool Polygon::isPossibleToRemoveTriangleAtIndex(
00292 size_t index,
00293 const Eigen::Vector3f& direction)
00294 {
00295 Polygon::PtrPair candidate = separatePolygon(index);
00296 Polygon::Ptr triangle_candidate = candidate.get<0>();
00297 Polygon::Ptr rest_candidate = candidate.get<1>();
00298
00299 Eigen::Vector3f the_direction = directionAtPoint(index);
00300
00301 if (the_direction.norm() == 0.0) {
00302 JSK_ROS_ERROR("malformed polygon");
00303 exit(1);
00304 }
00305 if (direction.dot(the_direction) < 0) {
00306 #ifdef DEBUG_GEO_UTIL
00307 JSK_ROS_INFO("triangle is not same direction");
00308 JSK_ROS_INFO("direction: [%f, %f, %f]", direction[0], direction[1], direction[2]);
00309 JSK_ROS_INFO("the_direction: [%f, %f, %f]",
00310 the_direction[0],
00311 the_direction[1],
00312 the_direction[2]);
00313 for (size_t i = 0; i < vertices_.size(); i++) {
00314 Eigen::Vector3f v = directionAtPoint(i);
00315 JSK_ROS_INFO("the_direction[%lu]: [%f, %f, %f]",
00316 i, v[0], v[1], v[2]);
00317
00318 }
00319 #endif
00320 return false;
00321 }
00322 else {
00323
00324
00325 for (size_t i = 0; i < rest_candidate->vertices_.size(); i++) {
00326 if (i == 0 || i == rest_candidate->vertices_.size() - 1) {
00327 continue;
00328 }
00329 else {
00330 Eigen::Vector3f P = rest_candidate->getVertex(i);
00331 Eigen::Vector3f A = triangle_candidate->getVertex(0);
00332 Eigen::Vector3f B = triangle_candidate->getVertex(1);
00333 Eigen::Vector3f C = triangle_candidate->getVertex(2);
00334 Eigen::Vector3f CA = A - C;
00335 Eigen::Vector3f BC = C - B;
00336 Eigen::Vector3f AB = B - A;
00337 Eigen::Vector3f AP = P - A;
00338 Eigen::Vector3f BP = P - B;
00339 Eigen::Vector3f CP = P - C;
00340 Eigen::Vector3f Across = CA.normalized().cross(AP.normalized()).normalized();
00341 Eigen::Vector3f Bcross = AB.normalized().cross(BP.normalized()).normalized();
00342 Eigen::Vector3f Ccross = BC.normalized().cross(CP.normalized()).normalized();
00343 #ifdef DEBUG_GEO_UTIL
00344 JSK_ROS_INFO("P: [%f, %f, %f]", P[0], P[1], P[2]);
00345 JSK_ROS_INFO("A: [%f, %f, %f]", A[0], A[1], A[2]);
00346 JSK_ROS_INFO("B: [%f, %f, %f]", B[0], B[1], B[2]);
00347 JSK_ROS_INFO("C: [%f, %f, %f]", C[0], C[1], C[2]);
00348 JSK_ROS_INFO("Across: [%f, %f, %f]", Across[0], Across[1], Across[2]);
00349 JSK_ROS_INFO("Bcross: [%f, %f, %f]", Bcross[0], Bcross[1], Bcross[2]);
00350 JSK_ROS_INFO("Ccross: [%f, %f, %f]", Ccross[0], Ccross[1], Ccross[2]);
00351 JSK_ROS_INFO("Across-Bcross: %f", Across.dot(Bcross));
00352 JSK_ROS_INFO("Bcross-Ccross: %f", Bcross.dot(Ccross));
00353 JSK_ROS_INFO("Ccross-Across: %f", Ccross.dot(Across));
00354 #endif
00355 if (((Across.dot(Bcross) > 0 &&
00356 Bcross.dot(Ccross) > 0 &&
00357 Ccross.dot(Across) > 0) ||
00358 (Across.dot(Bcross) < 0 &&
00359 Bcross.dot(Ccross) < 0 &&
00360 Ccross.dot(Across) < 0))) {
00361
00362 return false;
00363 }
00364
00365
00366
00367
00368
00369 }
00370 }
00371 return true;
00372 }
00373 }
00374
00375 void Polygon::transformBy(const Eigen::Affine3d& transform)
00376 {
00377 Eigen::Affine3f float_affine;
00378 convertEigenAffine3(transform, float_affine);
00379 transformBy(float_affine);
00380 }
00381
00382 void Polygon::transformBy(const Eigen::Affine3f& transform)
00383 {
00384
00385
00386
00387
00388 cached_triangles_.clear();
00389 for (size_t i = 0; i < vertices_.size(); i++) {
00390 vertices_[i] = transform * vertices_[i];
00391 }
00392
00393 normal_ = (vertices_[1] - vertices_[0]).cross(vertices_[2] - vertices_[0]).normalized();
00394 d_ = - normal_.dot(vertices_[0]) / normal_.norm();
00395 initializeCoordinates();
00396 }
00397
00398 bool Polygon::maskImage(const jsk_recognition_utils::CameraDepthSensor& model,
00399 cv::Mat& image) const
00400 {
00401 std::vector<cv::Point> projected_vertices
00402 = project3DPointstoPixel(model.getPinholeCameraModel(), vertices_);
00403 bool all_outside = true;
00404
00405 for (size_t i = 0; i < projected_vertices.size(); i++) {
00406 if (model.isInside(projected_vertices[i])) {
00407 all_outside = false;
00408 }
00409 }
00410 image = model.image(CV_8UC1);
00411
00412 for (size_t i = 0; i < vertices_.size(); i++) {
00413 if (vertices_[i][2] < 0) {
00414 return false;
00415 }
00416 }
00417 const cv::Point* element_points[1] = {&projected_vertices[0]};
00418 int number_of_points = (int)projected_vertices.size();
00419
00420 cv::fillPoly(image,
00421 element_points,
00422 &number_of_points,
00423 1,
00424 cv::Scalar(255));
00425 return !all_outside;
00426 }
00427
00428 void Polygon::drawLineToImage(const jsk_recognition_utils::CameraDepthSensor& model,
00429 cv::Mat& image,
00430 const cv::Scalar& color) const
00431 {
00432 std::vector<cv::Point> projected_vertices
00433 = project3DPointstoPixel(model.getPinholeCameraModel(), vertices_);
00434
00435 for (size_t i = 0; i < projected_vertices.size() - 1; i++) {
00436 cv::Point from = projected_vertices[i];
00437 cv::Point to = projected_vertices[i+1];
00438 if (model.isInside(from) || model.isInside(to)) {
00439 cv::line(image, from, to, color);
00440 }
00441 }
00442 cv::Point from = projected_vertices[projected_vertices.size() - 1];
00443 cv::Point to = projected_vertices[0];
00444 if (model.isInside(from) || model.isInside(to)) {
00445 cv::line(image, from, to, color);
00446 }
00447 }
00448
00449 bool Polygon::isConvex()
00450 {
00451 #ifdef DEBUG_GEO_UTIL
00452 for (size_t i = 0; i < getNumVertices(); i++) {
00453 Eigen::Vector3f n = directionAtPoint(i);
00454 JSK_ROS_INFO("n[%lu] [%f, %f, %f]", i, n[0], n[1], n[2]);
00455 }
00456 #endif
00457 Eigen::Vector3f n0 = directionAtPoint(0);
00458 for (size_t i = 1; i < getNumVertices(); i++) {
00459 Eigen::Vector3f n = directionAtPoint(i);
00460 if (n0.dot(n) < 0) {
00461 return false;
00462 }
00463 }
00464 return true;
00465 }
00466
00467 std::vector<Polygon::Ptr> Polygon::decomposeToTriangles()
00468 {
00469 if (cached_triangles_.size() != 0) {
00470 return cached_triangles_;
00471 }
00472 std::vector<Polygon::Ptr> ret;
00473
00474
00475 if (isTriangle()) {
00476 ret.push_back(Polygon::Ptr( new Polygon(*this)));
00477 return ret;
00478 }
00479
00480 pcl::EarClippingPatched clip;
00481
00482 pcl::PolygonMesh::Ptr input_mesh (new pcl::PolygonMesh);
00483 pcl::PCLPointCloud2 mesh_cloud;
00484 pcl::PointCloud<pcl::PointXYZ> mesh_pcl_cloud;
00485 boundariesToPointCloud<pcl::PointXYZ>(mesh_pcl_cloud);
00486 std::vector<pcl::Vertices> mesh_vertices(1);
00487 for (size_t i = 0; i < vertices_.size(); i++) {
00488 mesh_vertices[0].vertices.push_back(i);
00489 }
00490
00491 mesh_pcl_cloud.height = 1;
00492 mesh_pcl_cloud.width = mesh_pcl_cloud.points.size();
00493 pcl::toPCLPointCloud2<pcl::PointXYZ>(mesh_pcl_cloud, mesh_cloud);
00494
00495 input_mesh->polygons = mesh_vertices;
00496 input_mesh->cloud = mesh_cloud;
00497 clip.setInputMesh(input_mesh);
00498 pcl::PolygonMesh output;
00499 clip.process(output);
00500 assert(output.polygons.size() != 0);
00501
00502 for (size_t i = 0; i < output.polygons.size(); i++) {
00503 pcl::Vertices output_polygon_vertices = output.polygons[i];
00504 Vertices vs(output_polygon_vertices.vertices.size());
00505 for (size_t j = 0; j < output_polygon_vertices.vertices.size(); j++) {
00506 pcl::PointXYZ p
00507 = mesh_pcl_cloud.points[output_polygon_vertices.vertices[j]];
00508 Eigen::Vector3f v;
00509 pointFromXYZToVector<pcl::PointXYZ, Eigen::Vector3f>(p, v);
00510 vs[j] = v;
00511 }
00512 ret.push_back(Polygon::Ptr(new Polygon(vs, toCoefficients())));
00513 }
00514 cached_triangles_ = ret;
00515 return ret;
00516 }
00517
00518 Eigen::Vector3f Polygon::getNormalFromVertices()
00519 {
00520 if (vertices_.size() >= 3) {
00521 return (vertices_[1] - vertices_[0]).cross(vertices_[2] - vertices_[0]).normalized();
00522 }
00523 else {
00524 JSK_ROS_ERROR("the number of vertices is not enough");
00525 return Eigen::Vector3f(0, 0, 0);
00526 }
00527 }
00528
00529 size_t Polygon::previousIndex(size_t i)
00530 {
00531 if (i == 0) {
00532 return vertices_.size() - 1;
00533 }
00534 else {
00535 return i - 1;
00536 }
00537 }
00538
00539 size_t Polygon::nextIndex(size_t i)
00540 {
00541 if (i == vertices_.size() - 1) {
00542 return 0;
00543 }
00544 else {
00545 return i + 1;
00546 }
00547 }
00548
00549 Polygon Polygon::fromROSMsg(const geometry_msgs::Polygon& polygon)
00550 {
00551 Vertices vertices;
00552 for (size_t i = 0; i < polygon.points.size(); i++) {
00553 Eigen::Vector3f v;
00554 pointFromXYZToVector<geometry_msgs::Point32, Eigen::Vector3f>(
00555 polygon.points[i], v);
00556 vertices.push_back(v);
00557 }
00558 return Polygon(vertices);
00559 }
00560
00561 Polygon::Ptr Polygon::fromROSMsgPtr(const geometry_msgs::Polygon& polygon)
00562 {
00563 Vertices vertices;
00564 for (size_t i = 0; i < polygon.points.size(); i++) {
00565 Eigen::Vector3f v;
00566 pointFromXYZToVector<geometry_msgs::Point32, Eigen::Vector3f>(
00567 polygon.points[i], v);
00568 vertices.push_back(v);
00569 }
00570 return Polygon::Ptr(new Polygon(vertices));
00571 }
00572
00573 std::vector<Polygon::Ptr> Polygon::fromROSMsg(const jsk_recognition_msgs::PolygonArray& msg,
00574 const Eigen::Affine3f& offset)
00575 {
00576 std::vector<Polygon::Ptr> ret;
00577 for (size_t i = 0; i < msg.polygons.size(); i++) {
00578 Polygon::Ptr polygon = Polygon::fromROSMsgPtr(msg.polygons[i].polygon);
00579 polygon->transformBy(offset);
00580 ret.push_back(polygon);
00581 }
00582 return ret;
00583 }
00584
00585 bool Polygon::isInside(const Eigen::Vector3f& p)
00586 {
00587 if (isTriangle()) {
00588 Eigen::Vector3f A = vertices_[0];
00589 Eigen::Vector3f B = vertices_[1];
00590 Eigen::Vector3f C = vertices_[2];
00591
00592
00593
00594
00595 Eigen::Vector3f cross0 = (B - A).cross(p - A);
00596 Eigen::Vector3f cross1 = (C - B).cross(p - B);
00597 Eigen::Vector3f cross2 = (A - C).cross(p - C);
00598 if (cross0.dot(cross1) >= 0 &&
00599 cross1.dot(cross2) >= 0) {
00600 return true;
00601 }
00602 else {
00603 return false;
00604 }
00605 }
00606 else {
00607 std::vector<Polygon::Ptr> triangles = decomposeToTriangles();
00608 for (size_t i = 0; i < triangles.size(); i++) {
00609 if (triangles[i]->isInside(p)) {
00610 return true;
00611 }
00612 }
00613 return false;
00614 }
00615 }
00616
00617
00618 }