48 static const double cosA = sqrt(3.0) / 2.0;
53 if (eigenS[0] > eigenS[1]) {
60 if (eigenS[2] < eigenS[min]) {
63 }
else if (eigenS[2] > eigenS[max]) {
70 axes.col(0) << eigenV[0][max], eigenV[1][max], eigenV[2][max];
71 axes.col(1) << eigenV[0][mid], eigenV[1][mid], eigenV[2][mid];
72 axes.col(2) << eigenV[1][max] * eigenV[2][mid] -
73 eigenV[1][mid] * eigenV[2][max],
74 eigenV[0][mid] * eigenV[2][max] - eigenV[0][max] * eigenV[2][mid],
75 eigenV[0][max] * eigenV[1][mid] - eigenV[0][mid] * eigenV[1][max];
78 namespace OBB_fit_functions {
81 bv.
To.noalias() = ps[0];
82 bv.
axes.setIdentity();
88 const Vec3f& p2 = ps[1];
93 bv.
axes.col(0).noalias() = p1p2;
96 bv.
extent << len_p1p2 * 0.5, 0, 0;
97 bv.
To.noalias() = (p1 + p2) / 2;
102 const Vec3f& p2 = ps[1];
103 const Vec3f& p3 = ps[2];
109 len[0] = e[0].squaredNorm();
110 len[1] = e[1].squaredNorm();
111 len[2] = e[2].squaredNorm();
114 if (len[1] > len[0]) imax = 1;
115 if (len[2] > len[imax]) imax = 2;
117 bv.
axes.col(2).noalias() = e[0].cross(e[1]).normalized();
118 bv.
axes.col(0).noalias() = e[imax].normalized();
119 bv.
axes.col(1).noalias() = bv.
axes.col(2).cross(bv.
axes.col(0));
134 Matrix3f::Scalar s[3] = {0, 0, 0};
146 namespace RSS_fit_functions {
148 bv.
Tr.noalias() = ps[0];
149 bv.
axes.setIdentity();
157 const Vec3f& p2 = ps[1];
158 bv.
axes.col(0).noalias() = p1 - p2;
160 bv.
axes.col(0) /= len_p1p2;
172 const Vec3f& p2 = ps[1];
173 const Vec3f& p3 = ps[2];
179 len[0] = e[0].squaredNorm();
180 len[1] = e[1].squaredNorm();
181 len[2] = e[2].squaredNorm();
184 if (len[1] > len[0]) imax = 1;
185 if (len[2] > len[imax]) imax = 2;
187 bv.
axes.col(2).noalias() = e[0].cross(e[1]).normalized();
188 bv.
axes.col(0).noalias() = e[imax].normalized();
189 bv.
axes.col(1).noalias() = bv.
axes.col(2).cross(bv.
axes.col(0));
205 Matrix3f::Scalar s[3] = {0, 0, 0};
218 namespace kIOS_fit_functions {
227 bv.
obb.
To.noalias() = ps[0];
234 const Vec3f& p2 = ps[1];
235 Vec3f p1p2 = p1 - p2;
240 axes.col(0).noalias() = p1p2;
245 bv.
obb.
To = (p1 + p2) * 0.5;
254 Vec3f delta = axes.col(1) * r1cosA;
260 delta = axes.col(2) * r1cosA;
269 const Vec3f& p2 = ps[1];
270 const Vec3f& p3 = ps[2];
276 len[0] = e[0].squaredNorm();
277 len[1] = e[1].squaredNorm();
278 len[2] = e[2].squaredNorm();
281 if (len[1] > len[0]) imax = 1;
282 if (len[2] > len[imax]) imax = 2;
284 bv.
obb.
axes.col(2).noalias() = e[0].cross(e[1]).normalized();
285 bv.
obb.
axes.col(0).noalias() = e[imax].normalized();
311 Matrix3f::Scalar s[3] = {0, 0, 0};
327 if (extent[0] > kIOS_RATIO * extent[2]) {
328 if (extent[0] > kIOS_RATIO * extent[1])
340 Vec3f delta = axes.col(2) * (r10 * cosA - extent[2]);
347 bv.
spheres[1].
o += axes.col(2) * (-r10 + r11);
348 bv.
spheres[2].
o += axes.col(2) * (r10 - r12);
358 (sqrt(r10 * r10 - extent[0] * extent[0] - extent[2] * extent[2]) -
367 bv.
spheres[3].
o += axes.col(1) * (-r10 + r21);
368 bv.
spheres[4].
o += axes.col(1) * (r10 - r22);
377 namespace OBBRSS_fit_functions {
475 for (
unsigned int i = 1; i < n; ++i) {
481 unsigned int num_primitives) {
486 Matrix3f::Scalar s[3];
488 getCovariance(vertices, prev_vertices, tri_indices, primitive_indices,
502 unsigned int num_primitives) {
506 Matrix3f::Scalar s[3];
508 getCovariance(vertices, prev_vertices, tri_indices, primitive_indices,
522 primitive_indices, num_primitives,
534 unsigned int num_primitives) {
539 Matrix3f::Scalar s[3];
540 getCovariance(vertices, prev_vertices, tri_indices, primitive_indices,
551 primitive_indices, num_primitives, bv.
axes,
563 unsigned int num_primitives) {
568 Matrix3f::Scalar s[3];
570 getCovariance(vertices, prev_vertices, tri_indices, primitive_indices,
584 primitive_indices, num_primitives, center);
587 if (extent[0] > kIOS_RATIO * extent[2]) {
588 if (extent[0] > kIOS_RATIO * extent[1])
600 Vec3f delta = axes.col(2) * (r10 * cosA - extent[2]);
605 maximumDistance(vertices, prev_vertices, tri_indices, primitive_indices,
608 maximumDistance(vertices, prev_vertices, tri_indices, primitive_indices,
611 bv.
spheres[1].
o += axes.col(2) * (-r10 + r11);
612 bv.
spheres[2].
o += axes.col(2) * (r10 - r12);
622 (sqrt(r10 * r10 - extent[0] * extent[0] - extent[2] * extent[2]) -
629 primitive_indices, num_primitives, bv.
spheres[3].
o);
631 primitive_indices, num_primitives, bv.
spheres[4].
o);
633 bv.
spheres[3].
o += axes.col(1) * (-r10 + r21);
634 bv.
spheres[4].
o += axes.col(1) * (r10 - r22);
644 unsigned int num_primitives) {
646 if (num_primitives == 0)
return bv;
650 Triangle t0 = tri_indices[primitive_indices[0]];
651 bv =
AABB(vertices[t0[0]]);
653 for (
unsigned int i = 0; i < num_primitives; ++i) {
654 Triangle t = tri_indices[primitive_indices[i]];
655 bv += vertices[t[0]];
656 bv += vertices[t[1]];
657 bv += vertices[t[2]];
661 bv += prev_vertices[t[0]];
662 bv += prev_vertices[t[1]];
663 bv += prev_vertices[t[2]];
669 bv =
AABB(vertices[primitive_indices[0]]);
670 for (
unsigned int i = 0; i < num_primitives; ++i) {
671 bv += vertices[primitive_indices[i]];
675 bv += prev_vertices[primitive_indices[i]];
kIOS_Sphere spheres[5]
The (at most) five spheres for intersection.
OBB obb
OBB member, for rotation.
void fitn(Vec3f *ps, unsigned int n, OBB &bv)
void generateCoordinateSystem(const Eigen::MatrixBase< Derived1 > &_w, const Eigen::MatrixBase< Derived2 > &_u, const Eigen::MatrixBase< Derived3 > &_v)
Matrix3f axes
Orientation of RSS. axis[i] is the ith column of the orientation matrix for the RSS; it is also the i...
BV fit(unsigned int *primitive_indices, unsigned int num_primitives)
Compute a bounding volume that fits a set of primitives (points or triangles). The primitive data was...
Eigen::Matrix< FCL_REAL, 3, 3 > Matrix3f
void eigen(const Eigen::MatrixBase< Derived > &m, typename Derived::Scalar dout[3], Vector *vout)
compute the eigen vector and eigen vector of a matrix. dout is the eigen values, vout is the eigen ve...
HPP_FCL_DLLAPI FCL_REAL maximumDistance(Vec3f *ps, Vec3f *ps2, Triangle *ts, unsigned int *indices, unsigned int n, const Vec3f &query)
Compute the maximum distance from a given center point to a point cloud.
void fit3(Vec3f *ps, OBB &bv)
static const double kIOS_RATIO
HPP_FCL_DLLAPI void circumCircleComputation(const Vec3f &a, const Vec3f &b, const Vec3f &c, Vec3f ¢er, FCL_REAL &radius)
Compute the center and radius for a triangle's circumcircle.
HPP_FCL_DLLAPI void getRadiusAndOriginAndRectangleSize(Vec3f *ps, Vec3f *ps2, Triangle *ts, unsigned int *indices, unsigned int n, const Matrix3f &axes, Vec3f &origin, FCL_REAL l[2], FCL_REAL &r)
Compute the RSS bounding volume parameters: radius, rectangle size and the origin, given the BV axises.
OBB obb
@ OBB related with kIOS
void fit6(Vec3f *ps, OBB &bv)
unsigned int num_spheres
The number of spheres, no larger than 5.
A class describing the kIOS collision structure, which is a set of spheres.
static void axisFromEigen(Vec3f eigenV[3], Matrix3f::Scalar eigenS[3], Matrix3f &axes)
void fitn(Vec3f *ps, unsigned int n, kIOS &bv)
void fit(Vec3f *ps, unsigned int n, BV &bv)
Compute a bounding volume that fits a set of n points.
HPP_FCL_DLLAPI void getCovariance(Vec3f *ps, Vec3f *ps2, Triangle *ts, unsigned int *indices, unsigned int n, Matrix3f &M)
Compute the covariance matrix for a set or subset of points. if ts = null, then indices refer to poin...
HPP_FCL_DLLAPI void getExtentAndCenter(Vec3f *ps, Vec3f *ps2, Triangle *ts, unsigned int *indices, unsigned int n, Matrix3f &axes, Vec3f ¢er, Vec3f &extent)
Compute the bounding volume extent and center for a set or subset of points, given the BV axises...
Vec3f Tr
Origin of the rectangle in RSS.
RSS rss
RSS member, for distance.
void fit2(Vec3f *ps, OBB &bv)
A class describing the AABB collision structure, which is a box in 3D space determined by two diagona...
void fit1(Vec3f *ps, kIOS &bv)
FCL_REAL radius
Radius of sphere summed with rectangle to form RSS.
Triangle with 3 indices for points.
void fit2(Vec3f *ps, kIOS &bv)
FCL_REAL length[2]
Side lengths of rectangle.
void fit1(Vec3f *ps, OBB &bv)
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
Matrix3f axes
Orientation of OBB. axis[i] is the ith column of the orientation matrix for the box; it is also the i...
static const double invSinA
void fit3(Vec3f *ps, kIOS &bv)
Vec3f extent
Half dimensions of OBB.
Oriented bounding box class.