36 #define BOOST_PARAMETER_MAX_ARITY 7
40 #include <jsk_topic_tools/log_utils.h>
48 const double thr = 0.01;
49 Polygon not_skipped_polygon(vertices);
51 for (
size_t i = 0;
i < vertices.size();
i++) {
52 size_t next_i = not_skipped_polygon.
nextIndex(
i);
53 Eigen::Vector3f v0 = vertices[
i];
54 Eigen::Vector3f v1 = vertices[next_i];
55 if ((v1 - v0).norm() > thr) {
56 skipped_vertices.push_back(vertices[
i]);
59 return Polygon(skipped_vertices);
64 Eigen::Vector3f c(0, 0, 0);
77 std::vector<pcl::ModelCoefficients::Ptr> coefficients)
79 std::vector<Plane::Ptr> ret;
80 for (
size_t i = 0;
i < coefficients.size();
i++) {
88 Plane((vertices[1] - vertices[0]).
cross(vertices[2] - vertices[0]).normalized(), vertices[0]),
95 const std::vector<float>& coefficients):
96 Plane(coefficients), vertices_(vertices)
108 double max_distance = - DBL_MAX;
109 size_t max_index = 0;
112 double d = (O - v).norm();
113 if (max_distance <
d) {
123 return boost::make_tuple<size_t, size_t>(
135 for (
size_t i = 0;
i < triangles.size();
i++) {
136 sum += triangles[
i]->area();
147 Eigen::Vector3f OA =
A - O;
148 Eigen::Vector3f OB = B - O;
149 Eigen::Vector3f n = (OA.normalized()).
cross(OB.normalized());
159 return n.normalized();
167 double& max_x,
double& max_y)
174 Eigen::Affine3f inv_coords =
coordinates().inverse();
177 Eigen::Vector3f local_point = inv_coords *
vertices_[
i];
178 min_x = ::fmin(local_point[0], min_x);
179 min_y = ::fmin(local_point[1], min_y);
180 max_x = ::fmax(local_point[0], max_x);
181 max_y = ::fmax(local_point[1], max_y);
188 double min_x, min_y, max_x, max_y;
194 Eigen::Vector3f local_v = Eigen::Vector3f(x, y, 0);
214 std::vector<Segment::Ptr> ret;
227 Eigen::Vector3f nearest_point;
232 Eigen::Vector3f& nearest_point)
242 Eigen::Vector3f projected_p;
249 std::vector<Segment::Ptr> boundary_edges =
edges();
250 double min_distnace = DBL_MAX;
251 Eigen::Vector3f nearest_point;
253 for (
size_t i = 0;
i < boundary_edges.size();
i++) {
255 Eigen::Vector3f foot;
256 double d = edge->distance(
p, foot);
257 if (min_distnace >
d) {
258 nearest_point = foot;
263 return nearest_point;
279 triangle_vertices.push_back(
vertices_[index]);
280 triangle_vertices.push_back(
vertices_[neighbor_index.get<1>()]);
281 triangle_vertices.push_back(
vertices_[neighbor_index.get<0>()]);
285 for (
size_t i = neighbor_index.get<1>();
i != index;) {
287 if (
i == neighbor_index.get<1>()) {
301 return boost::make_tuple<Polygon::Ptr, Polygon::Ptr>(
307 const Eigen::Vector3f& direction)
315 if (the_direction.norm() == 0.0) {
319 if (direction.dot(the_direction) < 0) {
320 #ifdef DEBUG_GEO_UTIL
321 ROS_INFO(
"triangle is not same direction");
322 ROS_INFO(
"direction: [%f, %f, %f]", direction[0], direction[1], direction[2]);
323 ROS_INFO(
"the_direction: [%f, %f, %f]",
329 ROS_INFO(
"the_direction[%lu]: [%f, %f, %f]",
330 i, v[0], v[1], v[2]);
339 for (
size_t i = 0;
i < rest_candidate->vertices_.size();
i++) {
340 if (
i == 0 ||
i == rest_candidate->vertices_.size() - 1) {
344 Eigen::Vector3f P = rest_candidate->getVertex(
i);
345 Eigen::Vector3f
A = triangle_candidate->getVertex(0);
346 Eigen::Vector3f B = triangle_candidate->getVertex(1);
347 Eigen::Vector3f C = triangle_candidate->getVertex(2);
348 Eigen::Vector3f CA =
A - C;
349 Eigen::Vector3f BC = C - B;
350 Eigen::Vector3f AB = B -
A;
351 Eigen::Vector3f AP = P -
A;
352 Eigen::Vector3f BP = P - B;
353 Eigen::Vector3f CP = P - C;
354 Eigen::Vector3f Across = CA.normalized().cross(AP.normalized()).normalized();
355 Eigen::Vector3f Bcross = AB.normalized().cross(BP.normalized()).normalized();
356 Eigen::Vector3f Ccross = BC.normalized().cross(CP.normalized()).normalized();
357 #ifdef DEBUG_GEO_UTIL
358 ROS_INFO(
"P: [%f, %f, %f]", P[0], P[1], P[2]);
360 ROS_INFO(
"B: [%f, %f, %f]", B[0], B[1], B[2]);
361 ROS_INFO(
"C: [%f, %f, %f]", C[0], C[1], C[2]);
362 ROS_INFO(
"Across: [%f, %f, %f]", Across[0], Across[1], Across[2]);
363 ROS_INFO(
"Bcross: [%f, %f, %f]", Bcross[0], Bcross[1], Bcross[2]);
364 ROS_INFO(
"Ccross: [%f, %f, %f]", Ccross[0], Ccross[1], Ccross[2]);
365 ROS_INFO(
"Across-Bcross: %f", Across.dot(Bcross));
366 ROS_INFO(
"Bcross-Ccross: %f", Bcross.dot(Ccross));
367 ROS_INFO(
"Ccross-Across: %f", Ccross.dot(Across));
369 if (((Across.dot(Bcross) > 0 &&
370 Bcross.dot(Ccross) > 0 &&
371 Ccross.dot(Across) > 0) ||
372 (Across.dot(Bcross) < 0 &&
373 Bcross.dot(Ccross) < 0 &&
374 Ccross.dot(Across) < 0))) {
391 Eigen::Affine3f float_affine;
413 cv::Mat& image)
const
415 std::vector<cv::Point> projected_vertices
417 bool all_outside =
true;
419 for (
size_t i = 0;
i < projected_vertices.size();
i++) {
420 if (model.
isInside(projected_vertices[
i])) {
424 image = model.
image(CV_8UC1);
431 const cv::Point* element_points[1] = {&projected_vertices[0]};
432 int number_of_points = (int)projected_vertices.size();
444 const cv::Scalar& color,
445 const int line_width)
const
447 std::vector<cv::Point> projected_vertices
450 for (
size_t i = 0;
i < projected_vertices.size() - 1;
i++) {
451 cv::Point from = projected_vertices[
i];
452 cv::Point to = projected_vertices[
i+1];
454 cv::line(image, from, to, color, line_width);
457 cv::Point from = projected_vertices[projected_vertices.size() - 1];
458 cv::Point to = projected_vertices[0];
460 cv::line(image, from, to, color, line_width);
466 #ifdef DEBUG_GEO_UTIL
469 ROS_INFO(
"n[%lu] [%f, %f, %f]",
i, n[0], n[1], n[2]);
487 std::vector<Polygon::Ptr> ret;
497 pcl::PolygonMesh::Ptr input_mesh (
new pcl::PolygonMesh);
498 pcl::PCLPointCloud2 mesh_cloud;
499 pcl::PointCloud<pcl::PointXYZ> mesh_pcl_cloud;
500 boundariesToPointCloud<pcl::PointXYZ>(mesh_pcl_cloud);
501 std::vector<pcl::Vertices> mesh_vertices(1);
503 mesh_vertices[0].vertices.push_back(
i);
506 mesh_pcl_cloud.height = 1;
507 mesh_pcl_cloud.width = mesh_pcl_cloud.points.size();
508 pcl::toPCLPointCloud2<pcl::PointXYZ>(mesh_pcl_cloud, mesh_cloud);
510 input_mesh->polygons = mesh_vertices;
511 input_mesh->cloud = mesh_cloud;
512 clip.setInputMesh(input_mesh);
513 pcl::PolygonMesh output;
514 clip.process(output);
515 assert(output.polygons.size() != 0);
517 for (
size_t i = 0;
i < output.polygons.size();
i++) {
519 Vertices vs(output_polygon_vertices.vertices.size());
520 for (
size_t j = 0; j < output_polygon_vertices.vertices.size(); j++) {
522 = mesh_pcl_cloud.points[output_polygon_vertices.vertices[j]];
524 pointFromXYZToVector<pcl::PointXYZ, Eigen::Vector3f>(
p, v);
539 ROS_ERROR(
"the number of vertices is not enough");
540 return Eigen::Vector3f(0, 0, 0);
567 for (
size_t i = 0;
i < polygon.points.size();
i++) {
569 pointFromXYZToVector<geometry_msgs::Point32, Eigen::Vector3f>(
570 polygon.points[
i], v);
571 vertices.push_back(v);
579 for (
size_t i = 0;
i < polygon.points.size();
i++) {
581 pointFromXYZToVector<geometry_msgs::Point32, Eigen::Vector3f>(
582 polygon.points[
i], v);
583 vertices.push_back(v);
589 const Eigen::Affine3f& offset)
591 std::vector<Polygon::Ptr> ret;
592 for (
size_t i = 0;
i <
msg.polygons.size();
i++) {
594 polygon->transformBy(offset);
595 ret.push_back(polygon);
610 Eigen::Vector3f cross0 = (B -
A).
cross(
p -
A);
611 Eigen::Vector3f cross1 = (C - B).
cross(
p - B);
612 Eigen::Vector3f cross2 = (
A - C).
cross(
p - C);
613 if (cross0.dot(cross1) >= 0 &&
614 cross1.dot(cross2) >= 0) {
623 for (
size_t i = 0;
i < triangles.size();
i++) {