41 #include <console_bridge/console.h> 44 #ifdef GEOMETRIC_SHAPES_HAVE_QHULL_2011 45 #include <libqhull/libqhull.h> 46 #include <libqhull/mem.h> 47 #include <libqhull/qset.h> 48 #include <libqhull/geom.h> 49 #include <libqhull/merge.h> 50 #include <libqhull/poly.h> 51 #include <libqhull/io.h> 52 #include <libqhull/stat.h> 54 #include <qhull/qhull.h> 55 #include <qhull/mem.h> 56 #include <qhull/qset.h> 57 #include <qhull/geom.h> 58 #include <qhull/merge.h> 59 #include <qhull/poly.h> 61 #include <qhull/stat.h> 65 #include <boost/math/constants/constants.hpp> 70 #include <Eigen/Geometry> 71 #include <unordered_map> 78 static const double ZERO = 1e-9;
82 static inline double distanceSQR(
const Eigen::Vector3d& p,
const Eigen::Vector3d& origin,
const Eigen::Vector3d& dir)
84 Eigen::Vector3d a = p - origin;
85 double d = dir.normalized().dot(a);
86 return a.squaredNorm() - d * d;
92 intersc(
const Eigen::Vector3d& _pt,
const double _tm) :
pt(_pt),
time(_tm)
99 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
120 if (intersections ==
nullptr || ipts.empty())
124 const auto n = count > 0 ? std::min<size_t>(count, ipts.size()) : ipts.size();
126 for (
const auto& p : ipts)
128 if (intersections->size() == n)
130 if (!intersections->empty() && p.pt.isApprox(intersections->back(),
ZERO))
132 intersections->push_back(p.pt);
142 std::lock_guard<std::mutex> lock(g_triangle_for_plane_mutex);
143 auto it = g_triangle_for_plane_.find(mesh);
151 inline Eigen::Vector3d
normalize(
const Eigen::Vector3d& dir)
153 const double norm = dir.squaredNorm();
154 #if EIGEN_VERSION_AT_LEAST(3, 3, 0) 155 return ((norm - 1) > 1e-9) ? (dir / Eigen::numext::sqrt(norm)) : dir;
156 #else // used in kinetic 157 return ((norm - 1) > 1e-9) ? (Eigen::Vector3d)(dir / sqrt(norm)) : dir;
164 setDimensionsDirty(shape);
165 updateInternalData();
169 Eigen::Vector3d& result)
const 173 for (
unsigned int i = 0; i < max_attempts; ++i)
178 if (containsPoint(result))
186 return (center_ - p).squaredNorm() <= radius2_;
206 const auto tmpRadiusU = radius_ * scale_ + padding_;
208 throw std::runtime_error(
"Sphere radius must be non-negative.");
209 radiusU_ = tmpRadiusU;
210 radius2_ = radiusU_ * radiusU_;
211 center_ = pose_.translation();
216 auto s = std::allocate_shared<Sphere>(Eigen::aligned_allocator<Sphere>());
217 s->radius_ = radius_;
218 s->padding_ = padding;
221 s->updateInternalData();
227 return 4.0 * boost::math::constants::pi<double>() * radiusU_ * radiusU_ * radiusU_ / 3.0;
238 cylinder.
pose = pose_;
239 cylinder.
radius = radiusU_;
240 cylinder.
length = 2.0 * radiusU_;
248 Eigen::Isometry3d transform = Eigen::Isometry3d::Identity();
249 transform.translation() = getPose().translation();
257 Eigen::Isometry3d transform = Eigen::Isometry3d::Identity();
258 transform.translation() = getPose().translation();
260 bbox.
setPoseAndExtents(transform, 2 * Eigen::Vector3d(radiusU_, radiusU_, radiusU_));
264 Eigen::Vector3d& result)
const 266 for (
unsigned int i = 0; i < max_attempts; ++i)
268 const double minX = center_.x() - radiusU_;
269 const double maxX = center_.x() + radiusU_;
270 const double minY = center_.y() - radiusU_;
271 const double maxY = center_.y() + radiusU_;
272 const double minZ = center_.z() - radiusU_;
273 const double maxZ = center_.z() + radiusU_;
276 for (
int j = 0; j < 20; ++j)
279 if (containsPoint(result))
290 const Eigen::Vector3d dirNorm =
normalize(dir);
297 Eigen::Vector3d cp = origin - center_;
298 double dpcpv = cp.dot(dirNorm);
300 Eigen::Vector3d w = cp - dpcpv * dirNorm;
301 Eigen::Vector3d Q = center_ + w;
302 double x = radius2_ - w.squaredNorm();
307 double dpQv = w.dot(dirNorm);
311 intersections->push_back(Q);
319 Eigen::Vector3d A = Q - w;
320 Eigen::Vector3d B = Q + w;
322 double dpAv = w.dot(dirNorm);
324 double dpBv = w.dot(dirNorm);
331 intersections->push_back(A);
341 intersections->push_back(B);
349 Eigen::Vector3d v = p - center_;
350 double pH = v.dot(normalH_);
352 if (fabs(pH) > length2_)
355 double pB1 = v.dot(normalB1_);
356 double remaining = radius2_ - pB1 * pB1;
362 double pB2 = v.dot(normalB2_);
363 return pB2 * pB2 <= remaining;
375 return { radius_, length_ };
380 return { radiusU_, 2 * length2_ };
385 const auto tmpRadiusU = radius_ * scale_ + padding_;
387 throw std::runtime_error(
"Cylinder radius must be non-negative.");
388 const auto tmpLength2 = scale_ * length_ / 2.0 + padding_;
390 throw std::runtime_error(
"Cylinder length must be non-negative.");
391 radiusU_ = tmpRadiusU;
392 length2_ = tmpLength2;
393 radius2_ = radiusU_ * radiusU_;
394 center_ = pose_.translation();
395 radiusBSqr_ = length2_ * length2_ + radius2_;
396 radiusB_ = sqrt(radiusBSqr_);
399 Eigen::Matrix3d basis = pose_.linear();
400 normalB1_ = basis.col(0);
401 normalB2_ = basis.col(1);
402 normalH_ = basis.col(2);
404 double tmp = -normalH_.dot(center_);
405 d1_ = tmp + length2_;
406 d2_ = tmp - length2_;
410 Eigen::Vector3d& result)
const 413 double a = rng.
uniformReal(-boost::math::constants::pi<double>(), boost::math::constants::pi<double>());
415 double x = cos(a) * r;
416 double y = sin(a) * r;
421 result = pose_ * Eigen::Vector3d(x, y, z);
428 auto c = std::allocate_shared<Cylinder>(Eigen::aligned_allocator<Cylinder>());
429 c->length_ = length_;
430 c->radius_ = radius_;
431 c->padding_ = padding;
434 c->updateInternalData();
440 return 2.0 * boost::math::constants::pi<double>() * radius2_ * length2_;
451 cylinder.
pose = pose_;
452 cylinder.
radius = radiusU_;
453 cylinder.
length = 2 * length2_;
462 const auto a = normalH_;
463 const auto e = radiusU_ * (Eigen::Vector3d::Ones() - a.cwiseProduct(a) / a.dot(a)).cwiseSqrt();
464 const auto pa = center_ + length2_ * normalH_;
465 const auto pb = center_ - length2_ * normalH_;
475 bbox.
setPoseAndExtents(getPose(), 2 * Eigen::Vector3d(radiusU_, radiusU_, length2_));
482 const Eigen::Vector3d dirNorm =
normalize(dir);
487 std::vector<detail::intersc> ipts;
490 double tmp = normalH_.dot(dirNorm);
493 double tmp2 = -normalH_.dot(origin);
494 double t1 = (tmp2 - d1_) / tmp;
498 Eigen::Vector3d p1(origin + dirNorm * t1);
499 Eigen::Vector3d v1(p1 - center_);
500 v1 = v1 - normalH_.dot(v1) * normalH_;
503 if (intersections ==
nullptr)
511 double t2 = (tmp2 - d2_) / tmp;
514 Eigen::Vector3d p2(origin + dirNorm * t2);
515 Eigen::Vector3d v2(p2 - center_);
516 v2 = v2 - normalH_.dot(v2) * normalH_;
519 if (intersections ==
nullptr)
531 Eigen::Vector3d VD(normalH_.cross(dirNorm));
532 Eigen::Vector3d ROD(normalH_.cross(origin - center_));
533 double a = VD.squaredNorm();
534 double b = 2.0 * ROD.dot(VD);
535 double c = ROD.squaredNorm() - radius2_;
536 double d = b * b - 4.0 * a * c;
541 double t1 = (b + d) / e;
542 double t2 = (b - d) / e;
546 Eigen::Vector3d p1(origin + dirNorm * t1);
547 Eigen::Vector3d v1(center_ - p1);
551 if (intersections ==
nullptr)
561 Eigen::Vector3d p2(origin + dirNorm * t2);
562 Eigen::Vector3d v2(center_ - p2);
566 if (intersections ==
nullptr)
585 Eigen::Vector3d& result)
const 587 result = pose_ * Eigen::Vector3d(rng.
uniformReal(-length2_, length2_), rng.
uniformReal(-width2_, width2_),
594 const Eigen::Vector3d aligned = (pose_.linear().transpose() * (p - center_)).cwiseAbs();
595 return aligned[0] <= length2_ && aligned[1] <= width2_ && aligned[2] <= height2_;
600 const double* size =
static_cast<const shapes::Box*
>(shape)->size;
608 return { length_, width_, height_ };
613 return { 2 * length2_, 2 * width2_, 2 * height2_ };
618 double s2 = scale_ / 2.0;
619 const auto tmpLength2 = length_ * s2 + padding_;
620 const auto tmpWidth2 = width_ * s2 + padding_;
621 const auto tmpHeight2 = height_ * s2 + padding_;
623 if (tmpLength2 < 0 || tmpWidth2 < 0 || tmpHeight2 < 0)
624 throw std::runtime_error(
"Box dimensions must be non-negative.");
626 length2_ = tmpLength2;
628 height2_ = tmpHeight2;
630 center_ = pose_.translation();
632 radius2_ = length2_ * length2_ + width2_ * width2_ + height2_ * height2_;
633 radiusB_ = sqrt(radius2_);
636 Eigen::Matrix3d basis = pose_.linear();
637 normalL_ = basis.col(0);
638 normalW_ = basis.col(1);
639 normalH_ = basis.col(2);
642 const Eigen::Vector3d tmp(length2_, width2_, height2_);
643 corner1_ = center_ - tmp;
644 corner2_ = center_ + tmp;
647 std::shared_ptr<bodies::Body>
bodies::Box::cloneAt(
const Eigen::Isometry3d& pose,
double padding,
double scale)
const 649 auto b = std::allocate_shared<Box>(Eigen::aligned_allocator<Box>());
650 b->length_ = length_;
652 b->height_ = height_;
653 b->padding_ = padding;
656 b->updateInternalData();
662 return 8.0 * length2_ * width2_ * height2_;
675 if (length2_ > width2_ && length2_ > height2_)
677 cylinder.
length = length2_ * 2.0;
680 Eigen::Isometry3d rot(Eigen::AngleAxisd(90.0
f * (
M_PI / 180.0
f), Eigen::Vector3d::UnitY()));
681 cylinder.
pose = pose_ * rot;
683 else if (width2_ > height2_)
685 cylinder.
length = width2_ * 2.0;
688 cylinder.
radius = sqrt(height2_ * height2_ + length2_ * length2_);
689 Eigen::Isometry3d rot(Eigen::AngleAxisd(90.0
f * (
M_PI / 180.0
f), Eigen::Vector3d::UnitX()));
690 cylinder.
pose = pose_ * rot;
694 cylinder.
length = height2_ * 2.0;
697 cylinder.
pose = pose_;
699 cylinder.
radius = sqrt(a * a + b * b);
711 bbox.
setPoseAndExtents(getPose(), 2 * Eigen::Vector3d(length2_, width2_, height2_));
718 const Eigen::Vector3d dirNorm =
normalize(dir);
724 const Eigen::Matrix3d invRot = pose_.linear().transpose();
725 const Eigen::Vector3d o(invRot * (origin - center_) + center_);
726 const Eigen::Vector3d
d(invRot * dirNorm);
728 Eigen::Vector3d tmpTmin, tmpTmax;
729 tmpTmin = (corner1_ - o).cwiseQuotient(d);
730 tmpTmax = (corner2_ - o).cwiseQuotient(d);
734 for (
size_t i = 0; i < 3; ++i)
737 std::swap(tmpTmin[i], tmpTmax[i]);
747 tmin = std::fmax(tmpTmin.x(), std::fmax(tmpTmin.y(), tmpTmin.z()));
748 tmax = std::fmin(tmpTmax.x(), std::fmin(tmpTmax.y(), tmpTmax.z()));
767 intersections->push_back(tmin * dirNorm + origin);
768 if (count == 0 || count > 1)
769 intersections->push_back(tmax * dirNorm + origin);
775 intersections->push_back(tmax * dirNorm + origin);
781 intersections->push_back(tmax * dirNorm + origin);
792 if (bounding_box_.containsPoint(p))
795 Eigen::Vector3d ip(i_pose_ * p);
796 return isPointInsidePlanes(ip);
804 for (
unsigned int i = 0; i < mesh_data_->triangles_.size(); i += 3)
807 mesh_data_->vertices_[mesh_data_->triangles_[i]] - mesh_data_->vertices_[mesh_data_->triangles_[i + 1]];
809 mesh_data_->vertices_[mesh_data_->triangles_[i]] - mesh_data_->vertices_[mesh_data_->triangles_[i + 2]];
811 Eigen::Vector3d tri_normal = d1.cross(d2);
812 tri_normal.normalize();
814 Eigen::Vector3d normal(mesh_data_->planes_[mesh_data_->plane_for_triangle_[i / 3]].x(),
815 mesh_data_->planes_[mesh_data_->plane_for_triangle_[i / 3]].y(),
816 mesh_data_->planes_[mesh_data_->plane_for_triangle_[i / 3]].z());
817 bool same_dir = tri_normal.dot(normal) > 0;
820 std::swap(mesh_data_->triangles_[i], mesh_data_->triangles_[i + 1]);
827 mesh_data_ = std::allocate_shared<MeshData>(Eigen::aligned_allocator<MeshData>());
830 double maxX = -std::numeric_limits<double>::infinity(), maxY = -std::numeric_limits<double>::infinity(),
831 maxZ = -std::numeric_limits<double>::infinity();
832 double minX = std::numeric_limits<double>::infinity(), minY = std::numeric_limits<double>::infinity(),
833 minZ = std::numeric_limits<double>::infinity();
838 double vy = mesh->
vertices[3 * i + 1];
839 double vz = mesh->
vertices[3 * i + 2];
863 mesh_data_->box_size_ = Eigen::Vector3d(maxX - minX, maxY - minY, maxZ - minZ);
865 mesh_data_->box_offset_ = Eigen::Vector3d((minX + maxX) / 2.0, (minY + maxY) / 2.0, (minZ + maxZ) / 2.0);
867 mesh_data_->planes_.clear();
868 mesh_data_->triangles_.clear();
869 mesh_data_->vertices_.clear();
870 mesh_data_->mesh_radiusB_ = 0.0;
871 mesh_data_->mesh_center_ = Eigen::Vector3d();
873 double xdim = maxX - minX;
874 double ydim = maxY - minY;
875 double zdim = maxZ - minZ;
885 double maxdist = -std::numeric_limits<double>::infinity();
886 if (xdim > ydim && xdim > zdim)
890 pose1 = mesh_data_->box_offset_.y();
891 pose2 = mesh_data_->box_offset_.z();
894 else if (ydim > zdim)
898 pose1 = mesh_data_->box_offset_.x();
899 pose2 = mesh_data_->box_offset_.z();
906 pose1 = mesh_data_->box_offset_.x();
907 pose2 = mesh_data_->box_offset_.y();
912 coordT* points = (coordT*)calloc(mesh->
vertex_count * 3,
sizeof(coordT));
915 points[3 * i + 0] = (coordT)mesh->
vertices[3 * i + 0];
916 points[3 * i + 1] = (coordT)mesh->
vertices[3 * i + 1];
917 points[3 * i + 2] = (coordT)mesh->
vertices[3 * i + 2];
919 double dista = mesh->
vertices[3 * i + off1] - pose1;
920 double distb = mesh->
vertices[3 * i + off2] - pose2;
921 double dist = sqrt(((dista * dista) + (distb * distb)));
925 mesh_data_->bounding_cylinder_.radius = maxdist;
926 mesh_data_->bounding_cylinder_.length = cyl_length;
928 static FILE* null = fopen(
"/dev/null",
"w");
930 char flags[] =
"qhull Tv Qt";
931 int exitcode = qh_new_qhull(3, mesh->
vertex_count, points,
true, flags, null, null);
935 CONSOLE_BRIDGE_logWarn(
"Convex hull creation failed");
936 qh_freeqhull(!qh_ALL);
937 int curlong, totlong;
938 qh_memfreeshort(&curlong, &totlong);
942 int num_facets = qh num_facets;
944 int num_vertices = qh num_vertices;
945 mesh_data_->vertices_.reserve(num_vertices);
946 Eigen::Vector3d sum(0, 0, 0);
949 std::map<unsigned int, unsigned int> qhull_vertex_table;
953 Eigen::Vector3d vert(vertex->point[0], vertex->point[1], vertex->point[2]);
954 qhull_vertex_table[vertex->id] = mesh_data_->vertices_.size();
956 mesh_data_->vertices_.push_back(vert);
959 mesh_data_->mesh_center_ = sum / (double)(num_vertices);
960 for (
unsigned int j = 0; j < mesh_data_->vertices_.size(); ++j)
962 double dist = (mesh_data_->vertices_[j] - mesh_data_->mesh_center_).squaredNorm();
963 if (dist > mesh_data_->mesh_radiusB_)
964 mesh_data_->mesh_radiusB_ = dist;
967 mesh_data_->mesh_radiusB_ = sqrt(mesh_data_->mesh_radiusB_);
968 mesh_data_->triangles_.reserve(num_facets);
972 triangle_for_plane.clear();
978 Eigen::Vector4d planeEquation(facet->normal[0], facet->normal[1], facet->normal[2], facet->offset);
979 if (!mesh_data_->planes_.empty())
982 if ((planeEquation - mesh_data_->planes_.back()).cwiseAbs().maxCoeff() > 1e-6)
983 mesh_data_->planes_.push_back(planeEquation);
987 mesh_data_->planes_.push_back(planeEquation);
991 int vertex_n, vertex_i;
992 FOREACHvertex_i_((*facet).vertices)
994 mesh_data_->triangles_.push_back(qhull_vertex_table[vertex->id]);
997 mesh_data_->plane_for_triangle_[(mesh_data_->triangles_.size() - 1) / 3] = mesh_data_->planes_.size() - 1;
998 triangle_for_plane[mesh_data_->planes_.size() - 1] = (mesh_data_->triangles_.size() - 1) / 3;
1000 qh_freeqhull(!qh_ALL);
1001 int curlong, totlong;
1002 qh_memfreeshort(&curlong, &totlong);
1018 if (padding_ == 0.0 && scale_ == 1.0)
1020 scaled_vertices_ = &mesh_data_->vertices_;
1024 if (!scaled_vertices_storage_)
1026 scaled_vertices_ = scaled_vertices_storage_.get();
1027 scaled_vertices_storage_->resize(mesh_data_->vertices_.size());
1033 std::map<unsigned int, std::vector<unsigned int>> vertex_to_tris;
1034 for (
unsigned int i = 0; i < mesh_data_->triangles_.size() / 3; ++i)
1036 vertex_to_tris[mesh_data_->triangles_[3 * i + 0]].push_back(i);
1037 vertex_to_tris[mesh_data_->triangles_[3 * i + 1]].push_back(i);
1038 vertex_to_tris[mesh_data_->triangles_[3 * i + 2]].push_back(i);
1041 for (
unsigned int i = 0; i < mesh_data_->vertices_.size(); ++i)
1043 Eigen::Vector3d v(mesh_data_->vertices_[i] - mesh_data_->mesh_center_);
1045 for (
unsigned int t : vertex_to_tris[i])
1047 const Eigen::Vector4d& plane = mesh_data_->planes_[mesh_data_->plane_for_triangle_[t]];
1048 Eigen::Vector3d plane_normal(plane.x(), plane.y(), plane.z());
1049 double d_scaled_padded =
1050 scale_ * plane.w() - (1 - scale_) * mesh_data_->mesh_center_.dot(plane_normal) - padding_;
1053 double denom = v.dot(plane_normal);
1054 if (fabs(denom) < 1e-3)
1056 double lambda = (-mesh_data_->mesh_center_.dot(plane_normal) - d_scaled_padded) / denom;
1057 Eigen::Vector3d vert_on_plane = v * lambda + mesh_data_->mesh_center_;
1058 projected_vertices.push_back(vert_on_plane);
1060 if (projected_vertices.empty())
1062 double l = v.norm();
1063 scaled_vertices_storage_->at(i) =
1064 mesh_data_->mesh_center_ + v * (scale_ + (l >
detail::ZERO ? padding_ / l : 0.0));
1068 Eigen::Vector3d sum(0, 0, 0);
1069 for (
const Eigen::Vector3d& vertex : projected_vertices)
1073 sum /= projected_vertices.size();
1074 scaled_vertices_storage_->at(i) = sum;
1083 Eigen::Isometry3d pose = pose_;
1084 pose.translation() = Eigen::Vector3d(pose_ * mesh_data_->box_offset_);
1086 shapes::Box box_shape(mesh_data_->box_size_.x(), mesh_data_->box_size_.y(), mesh_data_->box_size_.z());
1087 bounding_box_.setPoseDirty(pose);
1090 bounding_box_.setPaddingDirty(padding_);
1091 bounding_box_.setScaleDirty(scale_);
1092 bounding_box_.setDimensionsDirty(&box_shape);
1093 bounding_box_.updateInternalData();
1095 i_pose_ = pose_.inverse();
1096 center_ = pose_ * mesh_data_->mesh_center_;
1097 radiusB_ = mesh_data_->mesh_radiusB_ * scale_ + padding_;
1098 radiusBSqr_ = radiusB_ * radiusB_;
1101 if (padding_ == 0.0 && scale_ == 1.0)
1102 scaled_vertices_ = &mesh_data_->vertices_;
1105 if (!scaled_vertices_storage_)
1107 scaled_vertices_ = scaled_vertices_storage_.get();
1108 scaled_vertices_storage_->resize(mesh_data_->vertices_.size());
1109 for (
unsigned int i = 0; i < mesh_data_->vertices_.size(); ++i)
1111 Eigen::Vector3d v(mesh_data_->vertices_[i] - mesh_data_->mesh_center_);
1112 double l = v.norm();
1113 scaled_vertices_storage_->at(i) =
1114 mesh_data_->mesh_center_ + v * (scale_ + (l >
detail::ZERO ? padding_ / l : 0.0));
1120 static const std::vector<unsigned int> empty;
1121 return mesh_data_ ? mesh_data_->triangles_ : empty;
1127 return mesh_data_ ? mesh_data_->vertices_ : empty;
1132 return scaled_vertices_ ? *scaled_vertices_ : getVertices();
1138 return mesh_data_ ? mesh_data_->planes_ : empty;
1144 auto m = std::allocate_shared<ConvexMesh>(Eigen::aligned_allocator<ConvexMesh>());
1145 m->mesh_data_ = mesh_data_;
1146 m->padding_ = padding;
1149 m->updateInternalData();
1156 sphere.
radius = radiusB_;
1162 cylinder.
length = mesh_data_ ? mesh_data_->bounding_cylinder_.length * scale_ + 2 * padding_ : 0.0;
1163 cylinder.
radius = mesh_data_ ? mesh_data_->bounding_cylinder_.radius * scale_ + padding_ : 0.0;
1166 bounding_box_.computeBoundingCylinder(cyl);
1174 bounding_box_.computeBoundingBox(bbox);
1179 bounding_box_.computeBoundingBox(bbox);
1184 unsigned int numplanes = mesh_data_->planes_.size();
1186 for (
unsigned int i = 0; i < numplanes; ++i)
1188 const Eigen::Vector4d& plane = mesh_data_->planes_[i];
1189 Eigen::Vector3d plane_vec(plane.x(), plane.y(), plane.z());
1193 const auto scaled_point_on_plane = scaled_vertices_->at(mesh_data_->triangles_[3 * triangle_for_plane.at(i)]);
1194 const double w_scaled_padded = -plane_vec.dot(scaled_point_on_plane);
1195 const double dist = plane_vec.dot(point) + w_scaled_padded -
detail::ZERO;
1204 unsigned int numvertices = mesh_data_->vertices_.size();
1205 unsigned int result = 0;
1206 for (
unsigned int i = 0; i < numvertices; ++i)
1208 Eigen::Vector3d plane_vec(planeNormal.x(), planeNormal.y(), planeNormal.z());
1209 double dist = plane_vec.dot(mesh_data_->vertices_[i]) + planeNormal.w() - 1e-6;
1218 double volume = 0.0;
1220 for (
unsigned int i = 0; i < mesh_data_->triangles_.size() / 3; ++i)
1222 const Eigen::Vector3d& v1 = mesh_data_->vertices_[mesh_data_->triangles_[3 * i + 0]];
1223 const Eigen::Vector3d& v2 = mesh_data_->vertices_[mesh_data_->triangles_[3 * i + 1]];
1224 const Eigen::Vector3d& v3 = mesh_data_->vertices_[mesh_data_->triangles_[3 * i + 2]];
1225 volume += v1.x() * v2.y() * v3.z() + v2.x() * v3.y() * v1.z() + v3.x() * v1.y() * v2.z() -
1226 v1.x() * v3.y() * v2.z() - v2.x() * v1.y() * v3.z() - v3.x() * v2.y() * v1.z();
1228 return fabs(volume) / 6.0;
1235 const Eigen::Vector3d dirNorm =
normalize(dir);
1241 if (!bounding_box_.intersectsRay(origin, dirNorm))
1245 Eigen::Vector3d orig(i_pose_ * origin);
1246 Eigen::Vector3d dr(i_pose_.linear() * dirNorm);
1248 std::vector<detail::intersc> ipts;
1250 bool result =
false;
1253 const auto nt = mesh_data_->triangles_.size() / 3;
1254 for (
size_t i = 0; i < nt; ++i)
1256 Eigen::Vector3d vec(mesh_data_->planes_[mesh_data_->plane_for_triangle_[i]].x(),
1257 mesh_data_->planes_[mesh_data_->plane_for_triangle_[i]].y(),
1258 mesh_data_->planes_[mesh_data_->plane_for_triangle_[i]].z());
1260 const double tmp = vec.dot(dr);
1264 const double w_scaled_padded = vec.dot(scaled_vertices_->at(mesh_data_->triangles_[3 * i]));
1265 const double t = -(vec.dot(orig) + w_scaled_padded) / tmp;
1268 const auto i3 = 3 * i;
1269 const auto v1 = mesh_data_->triangles_[i3 + 0];
1270 const auto v2 = mesh_data_->triangles_[i3 + 1];
1271 const auto v3 = mesh_data_->triangles_[i3 + 2];
1273 const Eigen::Vector3d& a = scaled_vertices_->at(v1);
1274 const Eigen::Vector3d& b = scaled_vertices_->at(v2);
1275 const Eigen::Vector3d& c = scaled_vertices_->at(v3);
1277 Eigen::Vector3d cb(c - b);
1278 Eigen::Vector3d ab(a - b);
1281 Eigen::Vector3d P(orig + dr * t);
1284 Eigen::Vector3d pb(P - b);
1285 Eigen::Vector3d c1(cb.cross(pb));
1286 Eigen::Vector3d c2(cb.cross(ab));
1287 if (c1.dot(c2) < 0.0)
1290 Eigen::Vector3d ca(c - a);
1291 Eigen::Vector3d pa(P - a);
1292 Eigen::Vector3d ba(-ab);
1296 if (c1.dot(c2) < 0.0)
1302 if (c1.dot(c2) < 0.0)
1317 if (result && intersections)
1343 for (
unsigned int i = 0; i < shapes.size(); i++)
1344 addBody(shapes[i], poses[i], padding);
1354 for (
auto& body : bodies_)
1361 bodies_.push_back(body);
1377 return bodies_.size();
1382 if (i >= bodies_.size())
1388 bodies_[i]->setPose(pose);
1393 if (i >= bodies_.size())
1404 for (std::size_t i = 0; i < bodies_.size(); ++i)
1405 if (bodies_[i]->containsPoint(p, verbose))
1416 return containsPoint(p, dummy, verbose);
1422 for (std::size_t i = 0; i < bodies_.size(); ++i)
1423 if (bodies_[i]->intersectsRay(origin, dir, intersections, count))
Definition of various shapes. No properties such as position are included. These are simply the descr...
bool containsPoint(const Eigen::Vector3d &p, bool verbose=false) const override
Check if a point is inside the body. Surface points are included.
bool containsPoint(const Eigen::Vector3d &p, bool verbose=false) const override
Check if a point is inside the body. Surface points are included.
BodyPtr cloneAt(const Eigen::Isometry3d &pose, double padding, double scale) const override
Get a clone of this body, but one that is located at the pose pose and has possibly different passing...
bool intersectsRay(const Eigen::Vector3d &origin, const Eigen::Vector3d &dir, EigenSTL::vector_Vector3d *intersections=nullptr, unsigned int count=0) const override
Check if a ray intersects the body, and find the set of intersections, in order, along the ray...
virtual bool samplePointInside(random_numbers::RandomNumberGenerator &rng, unsigned int max_attempts, Eigen::Vector3d &result) const
Sample a point that is included in the body using a given random number generator.
void updateInternalData() override
This function is called every time a change to the body is made, so that intermediate values stored f...
void computeBoundingSphere(const std::vector< const Body *> &bodies, BoundingSphere &mergedSphere)
Compute the bounding sphere for a set of bodies and store the resulting sphere in mergedSphere...
Definition of a cylinder Length is along z axis. Origin is at center of mass.
std::vector< double > getScaledDimensions() const override
Get the dimensions associated to this body (scaled and padded)
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > vector_Vector3d
void filterIntersections(std::vector< detail::intersc > &ipts, EigenSTL::vector_Vector3d *intersections, const size_t count)
Take intersections points in ipts and add them to intersections, filtering duplicates.
bool intersectsRay(const Eigen::Vector3d &origin, const Eigen::Vector3d &dir, EigenSTL::vector_Vector3d *intersections=nullptr, unsigned int count=0) const override
Check if a ray intersects the body, and find the set of intersections, in order, along the ray...
void computeBoundingBox(AABB &bbox) const override
Compute the axis-aligned bounding box for the body, in its current pose. Scaling and padding are acco...
void computeBoundingCylinder(BoundingCylinder &cylinder) const override
Compute the bounding cylinder for the body, in its current pose. Scaling and padding are accounted fo...
bool isPointInsidePlanes(const Eigen::Vector3d &point) const
Check if the point is inside all halfspaces this mesh consists of (mesh_data_->planes_).
void updateInternalData() override
This function is called every time a change to the body is made, so that intermediate values stored f...
static std::map< size_t, size_t > & getTriangleForPlane(const ConvexMesh *mesh)
BodyPtr cloneAt(const Eigen::Isometry3d &pose, double padding, double scale) const override
Get a clone of this body, but one that is located at the pose pose and has possibly different passing...
const Body * getBody(unsigned int i) const
Get the ith body in the vector.
static double distanceSQR(const Eigen::Vector3d &p, const Eigen::Vector3d &origin, const Eigen::Vector3d &dir)
Compute the square of the distance between a ray and a point Note: this requires 'dir' to be normaliz...
intersc(const Eigen::Vector3d &_pt, const double _tm)
void computeBoundingBox(AABB &bbox) const override
Compute the axis-aligned bounding box for the body, in its current pose. Scaling and padding are acco...
const EigenSTL::vector_Vector3d & getScaledVertices() const
double computeVolume() const override
Compute the volume of the body. This method includes changes induced by scaling and padding...
bool samplePointInside(random_numbers::RandomNumberGenerator &rng, unsigned int max_attempts, Eigen::Vector3d &result) const override
Sample a point that is included in the body using a given random number generator.
BodyPtr cloneAt(const Eigen::Isometry3d &pose, double padding, double scale) const override
Get a clone of this body, but one that is located at the pose pose and has possibly different passing...
const EigenSTL::vector_Vector4d & getPlanes() const
Get the planes that define the convex shape.
bool intersectsRay(const Eigen::Vector3d &origin, const Eigen::Vector3d &dir, std::size_t &index, EigenSTL::vector_Vector3d *intersections=nullptr, unsigned int count=0) const
Check if any of the bodies intersects the ray defined by origin and dir. When the first intersection ...
bool samplePointInside(random_numbers::RandomNumberGenerator &rng, unsigned int max_attempts, Eigen::Vector3d &result) const override
Sample a point that is included in the body using a given random number generator.
BodyPtr cloneAt(const Eigen::Isometry3d &pose, double padding, double scale) const override
Get a clone of this body, but one that is located at the pose pose and has possibly different passing...
Represents an oriented bounding box.
void useDimensions(const shapes::Shape *shape) override
Depending on the shape, this function copies the relevant data to the body.
std::vector< double > getDimensions() const override
Get the radius of the sphere.
Definition of a sphere that bounds another object.
void setPoseAndExtents(const Eigen::Isometry3d &pose, const Eigen::Vector3d &extents)
Set both the pose and extents of the OBB.
std::vector< double > getScaledDimensions() const override
Get the dimensions associated to this body (scaled and padded)
unsigned int countVerticesBehindPlane(const Eigen::Vector4f &planeNormal) const
(Used mainly for debugging) Count the number of vertices behind a plane
unsigned int vertex_count
The number of available vertices.
A basic definition of a shape. Shapes are considered centered at origin.
Definition of a convex mesh. Convex hull is computed for a given shape::Mesh.
virtual void updateInternalData()=0
This function is called every time a change to the body is made, so that intermediate values stored f...
void computeBoundingBox(AABB &bbox) const override
Compute the axis-aligned bounding box for the body, in its current pose. Scaling and padding are acco...
void computeBoundingSphere(BoundingSphere &sphere) const override
Compute the bounding radius for the body, in its current pose. Scaling and padding are accounted for...
Definition of a cylinder.
bool containsPoint(const Eigen::Vector3d &p, bool verbose=false) const
Check if any body in the vector contains the input point.
Body * createBodyFromShape(const shapes::Shape *shape)
Create a body from a given shape.
void setPose(unsigned int i, const Eigen::Isometry3d &pose)
Set the pose of a particular body in the vector of bodies.
#define ASSERT_ISOMETRY(transform)
Assert that the given transform is an isometry.
std::vector< double > getDimensions() const override
Returns an empty vector.
void computeBoundingSphere(BoundingSphere &sphere) const override
Compute the bounding radius for the body, in its current pose. Scaling and padding are accounted for...
void useDimensions(const shapes::Shape *shape) override
Depending on the shape, this function copies the relevant data to the body.
double * vertices
The position for each vertex vertex k has values at index (3k, 3k+1, 3k+2) = (x,y,z)
void computeBoundingCylinder(BoundingCylinder &cylinder) const override
Compute the bounding cylinder for the body, in its current pose. Scaling and padding are accounted fo...
void clear()
Clear all bodies from the vector.
std::size_t getCount() const
Get the number of bodies in this vector.
double uniformReal(double lower_bound, double upper_bound)
Eigen::Vector3d normalize(const Eigen::Vector3d &dir)
void updateInternalData() override
This function is called every time a change to the body is made, so that intermediate values stored f...
void computeBoundingSphere(BoundingSphere &sphere) const override
Compute the bounding radius for the body, in its current pose. Scaling and padding are accounted for...
std::unordered_map< const ConvexMesh *, std::map< size_t, size_t > > g_triangle_for_plane_
std::vector< Eigen::Vector4d, Eigen::aligned_allocator< Eigen::Vector4d > > vector_Vector4d
bool intersectsRay(const Eigen::Vector3d &origin, const Eigen::Vector3d &dir, EigenSTL::vector_Vector3d *intersections=nullptr, unsigned int count=0) const override
Check if a ray intersects the body, and find the set of intersections, in order, along the ray...
void useDimensions(const shapes::Shape *shape) override
Depending on the shape, this function copies the relevant data to the body.
void computeBoundingBox(AABB &bbox) const override
Compute the axis-aligned bounding box for the body, in its current pose. Scaling and padding are acco...
void setPaddingDirty(double padd)
If the dimension of the body should be padded, this method sets the pading.
double computeVolume() const override
Compute the volume of the body. This method includes changes induced by scaling and padding...
void computeBoundingSphere(BoundingSphere &sphere) const override
Compute the bounding radius for the body, in its current pose. Scaling and padding are accounted for...
void correctVertexOrderFromPlanes()
void computeBoundingCylinder(BoundingCylinder &cylinder) const override
Compute the bounding cylinder for the body, in its current pose. Scaling and padding are accounted fo...
void extendWithTransformedBox(const Eigen::Isometry3d &transform, const Eigen::Vector3d &box)
Extend with a box transformed by the given transform.
virtual void computeBoundingSphere(BoundingSphere &sphere) const =0
Compute the bounding radius for the body, in its current pose. Scaling and padding are accounted for...
Definition of a triangle mesh By convention the "center" of the shape is at the origin. For a mesh this implies that the AABB of the mesh is centered at the origin. Some methods may not work with arbitrary meshes whose AABB is not centered at the origin. Padding is not applied to vertices plainly coordinate-wise, but instead the padding value is added to the length of the direction vector between centroid and each vertex.
Definition of a box Aligned with the XYZ axes.
bool containsPoint(const Eigen::Vector3d &p, bool verbose=false) const override
Check if a point is inside the body. Surface points are included.
void setDimensions(const shapes::Shape *shape)
Set the dimensions of the body (from corresponding shape)
void computeBoundingCylinder(BoundingCylinder &cylinder) const override
Compute the bounding cylinder for the body, in its current pose. Scaling and padding are accounted fo...
void setPoseDirty(const Eigen::Isometry3d &pose)
Set the pose of the body.
std::vector< double > getScaledDimensions() const override
Returns an empty vector.
Represents an axis-aligned bounding box.
std::vector< Eigen::Isometry3d, Eigen::aligned_allocator< Eigen::Isometry3d > > vector_Isometry3d
bool samplePointInside(random_numbers::RandomNumberGenerator &rng, unsigned int max_attempts, Eigen::Vector3d &result) const override
Sample a point that is included in the body using a given random number generator.
std::mutex g_triangle_for_plane_mutex
Lock this mutex every time you work with g_triangle_for_plane_.
void addBody(Body *body)
Add a body.
void updateInternalData() override
This function is called every time a change to the body is made, so that intermediate values stored f...
bool intersectsRay(const Eigen::Vector3d &origin, const Eigen::Vector3d &dir, EigenSTL::vector_Vector3d *intersections=nullptr, unsigned int count=0) const override
Check if a ray intersects the body, and find the set of intersections, in order, along the ray...
double computeVolume() const override
Compute the volume of the body. This method includes changes induced by scaling and padding...
double computeVolume() const override
Compute the volume of the body. This method includes changes induced by scaling and padding...
const std::vector< unsigned int > & getTriangles() const
bool containsPoint(const Eigen::Vector3d &p, bool verbose=false) const override
Check if a point is inside the body. Surface points are included.
bool operator()(const intersc &a, const intersc &b) const
A body is a shape + its pose. Point inclusion, ray intersection can be tested, volumes and bounding s...
std::vector< double > getDimensions() const override
Get the radius & length of the cylinder.
std::vector< double > getDimensions() const override
Get the length & width & height (x, y, z) of the box.
void computeScaledVerticesFromPlaneProjections()
Project the original vertex to the scaled and padded planes and average.
void useDimensions(const shapes::Shape *shape) override
Depending on the shape, this function copies the relevant data to the body.
const EigenSTL::vector_Vector3d & getVertices() const
std::vector< double > getScaledDimensions() const override
Get the dimensions associated to this body (scaled and padded)
This set of classes allows quickly detecting whether a given point is inside an object or not...