37 #ifndef COAL_TRAVERSAL_NODE_HFIELD_SHAPE_H
38 #define COAL_TRAVERSAL_NODE_HFIELD_SHAPE_H
59 template <
typename BV>
60 Convex<Quadrilateral> buildConvexQuadrilateral(
const HFNode<BV>& node,
61 const HeightField<BV>& model) {
62 const MatrixXs& heights = model.getHeights();
63 const VecXs& x_grid = model.getXGrid();
64 const VecXs& y_grid = model.getYGrid();
66 const Scalar min_height = model.getMinHeight();
68 const Scalar x0 = x_grid[node.x_id], x1 = x_grid[node.x_id + 1],
69 y0 = y_grid[node.y_id], y1 = y_grid[node.y_id + 1];
70 const Eigen::Block<const MatrixXs, 2, 2> cell =
71 heights.block<2, 2>(node.y_id, node.x_id);
73 assert(cell.maxCoeff() > min_height &&
74 "max_height is lower than min_height");
77 std::shared_ptr<std::vector<Vec3s>> pts(
new std::vector<Vec3s>({
78 Vec3s(x0, y0, min_height),
79 Vec3s(x0, y1, min_height),
80 Vec3s(x1, y1, min_height),
81 Vec3s(x1, y0, min_height),
82 Vec3s(x0, y0, cell(0, 0)),
83 Vec3s(x0, y1, cell(1, 0)),
84 Vec3s(x1, y1, cell(1, 1)),
85 Vec3s(x1, y0, cell(0, 1)),
88 std::shared_ptr<std::vector<Quadrilateral>> polygons(
89 new std::vector<Quadrilateral>(6));
90 (*polygons)[0].set(0, 3, 2, 1);
91 (*polygons)[1].set(0, 1, 5, 4);
92 (*polygons)[2].set(1, 2, 6, 5);
93 (*polygons)[3].set(2, 3, 7, 6);
94 (*polygons)[4].set(3, 0, 4, 7);
95 (*polygons)[5].set(4, 5, 6, 7);
97 return Convex<Quadrilateral>(pts,
104 enum class FaceOrientationConvexPart1 {
112 enum class FaceOrientationConvexPart2 {
120 template <
typename BV>
121 void buildConvexTriangles(
const HFNode<BV>& node,
const HeightField<BV>& model,
122 Convex<Triangle>& convex1,
int& convex1_active_faces,
123 Convex<Triangle>& convex2,
124 int& convex2_active_faces) {
125 const MatrixXs& heights = model.getHeights();
126 const VecXs& x_grid = model.getXGrid();
127 const VecXs& y_grid = model.getYGrid();
129 const Scalar min_height = model.getMinHeight();
131 const Scalar x0 = x_grid[node.x_id], x1 = x_grid[node.x_id + 1],
132 y0 = y_grid[node.y_id], y1 = y_grid[node.y_id + 1];
133 const Scalar max_height = node.max_height;
134 const Eigen::Block<const MatrixXs, 2, 2> cell =
135 heights.block<2, 2>(node.y_id, node.x_id);
137 const int contact_active_faces = node.contact_active_faces;
138 convex1_active_faces = 0;
139 convex2_active_faces = 0;
143 if (contact_active_faces & FaceOrientation::TOP) {
144 convex1_active_faces |= int(details::FaceOrientationConvexPart1::TOP);
145 convex2_active_faces |= int(details::FaceOrientationConvexPart2::TOP);
148 if (contact_active_faces & FaceOrientation::BOTTOM) {
149 convex1_active_faces |= int(details::FaceOrientationConvexPart1::BOTTOM);
150 convex2_active_faces |= int(details::FaceOrientationConvexPart2::BOTTOM);
154 if (contact_active_faces & FaceOrientation::WEST) {
155 convex1_active_faces |= int(details::FaceOrientationConvexPart1::WEST);
158 if (contact_active_faces & FaceOrientation::NORTH) {
159 convex1_active_faces |= int(details::FaceOrientationConvexPart1::NORTH);
163 if (contact_active_faces & FaceOrientation::EAST) {
164 convex2_active_faces |= int(details::FaceOrientationConvexPart2::EAST);
167 if (contact_active_faces & FaceOrientation::SOUTH) {
168 convex2_active_faces |= int(details::FaceOrientationConvexPart2::SOUTH);
171 assert(max_height > min_height &&
172 "max_height is lower than min_height");
177 std::shared_ptr<std::vector<Vec3s>> pts(
new std::vector<Vec3s>({
178 Vec3s(x0, y0, min_height),
179 Vec3s(x0, y1, min_height),
180 Vec3s(x1, y0, min_height),
181 Vec3s(x0, y0, cell(0, 0)),
182 Vec3s(x0, y1, cell(1, 0)),
183 Vec3s(x1, y0, cell(0, 1)),
186 std::shared_ptr<std::vector<Triangle>> triangles(
187 new std::vector<Triangle>(8));
188 (*triangles)[0].set(0, 2, 1);
189 (*triangles)[1].set(3, 4, 5);
190 (*triangles)[2].set(0, 1, 3);
191 (*triangles)[3].set(3, 1, 4);
192 (*triangles)[4].set(1, 2, 5);
193 (*triangles)[5].set(1, 5, 4);
194 (*triangles)[6].set(0, 5, 2);
195 (*triangles)[7].set(5, 0, 3);
205 std::shared_ptr<std::vector<Vec3s>> pts(
new std::vector<Vec3s>({
206 Vec3s(x0, y1, min_height),
207 Vec3s(x1, y1, min_height),
208 Vec3s(x1, y0, min_height),
209 Vec3s(x0, y1, cell(1, 0)),
210 Vec3s(x1, y1, cell(1, 1)),
211 Vec3s(x1, y0, cell(0, 1)),
214 std::shared_ptr<std::vector<Triangle>> triangles(
215 new std::vector<Triangle>(8));
216 (*triangles)[0].set(2, 1, 0);
217 (*triangles)[1].set(3, 4, 5);
218 (*triangles)[2].set(0, 1, 3);
219 (*triangles)[3].set(3, 1, 4);
220 (*triangles)[4].set(0, 5, 2);
221 (*triangles)[5].set(0, 3, 5);
222 (*triangles)[6].set(1, 2, 5);
223 (*triangles)[7].set(4, 1, 2);
235 const Project<Scalar>::ProjectResult result =
236 Project<Scalar>::projectTriangle(pointA, pointB, pointC, point);
237 Vec3s res = result.parameterization[0] * pointA +
238 result.parameterization[1] * pointB +
239 result.parameterization[2] * pointC;
244 inline Vec3s projectTetrahedra(
const Vec3s& pointA,
const Vec3s& pointB,
246 const Vec3s& point) {
247 const Project<Scalar>::ProjectResult result =
248 Project<Scalar>::projectTetrahedra(pointA, pointB, pointC, pointD, point);
249 Vec3s res = result.parameterization[0] * pointA +
250 result.parameterization[1] * pointB +
251 result.parameterization[2] * pointC +
252 result.parameterization[3] * pointD;
257 inline Vec3s computeTriangleNormal(
const Triangle& triangle,
258 const std::vector<Vec3s>& points) {
259 const Vec3s pointA = points[triangle[0]];
260 const Vec3s pointB = points[triangle[1]];
261 const Vec3s pointC = points[triangle[2]];
263 const Vec3s normal = (pointB - pointA).cross(pointC - pointA).normalized();
264 assert(!normal.array().isNaN().any() &&
"normal is ill-defined");
269 inline Vec3s projectPointOnTriangle(
const Vec3s& contact_point,
270 const Triangle& triangle,
271 const std::vector<Vec3s>& points) {
272 const Vec3s pointA = points[triangle[0]];
273 const Vec3s pointB = points[triangle[1]];
274 const Vec3s pointC = points[triangle[2]];
276 const Vec3s contact_point_projected =
277 projectTriangle(pointA, pointB, pointC, contact_point);
279 return contact_point_projected;
282 inline Scalar distanceContactPointToTriangle(
const Vec3s& contact_point,
283 const Triangle& triangle,
284 const std::vector<Vec3s>& points) {
285 const Vec3s contact_point_projected =
286 projectPointOnTriangle(contact_point, triangle, points);
287 return (contact_point_projected - contact_point).norm();
290 inline Scalar distanceContactPointToFace(
const size_t face_id,
291 const Vec3s& contact_point,
292 const Convex<Triangle>& convex,
293 size_t& closest_face_id) {
294 assert((face_id >= 0 && face_id < 8) &&
"face_id should be in [0;7]");
296 const std::vector<Vec3s>& points = *(convex.points);
298 const Triangle& triangle = (*(convex.polygons))[face_id];
299 closest_face_id = face_id;
300 return distanceContactPointToTriangle(contact_point, triangle, points);
302 const Triangle& triangle1 = (*(convex.polygons))[face_id];
303 const Scalar distance_to_triangle1 =
304 distanceContactPointToTriangle(contact_point, triangle1, points);
306 const Triangle& triangle2 = (*(convex.polygons))[face_id + 1];
307 const Scalar distance_to_triangle2 =
308 distanceContactPointToTriangle(contact_point, triangle2, points);
310 if (distance_to_triangle1 > distance_to_triangle2) {
311 closest_face_id = face_id + 1;
312 return distance_to_triangle2;
314 closest_face_id = face_id;
315 return distance_to_triangle1;
320 template <
typename Polygone,
typename Shape>
321 bool binCorrection(
const Convex<Polygone>& convex,
322 const int convex_active_faces,
const Shape& shape,
325 Vec3s& face_normal,
const bool is_collision) {
327 const std::vector<Vec3s>& points = *(convex.points);
329 bool hfield_witness_is_on_bin_side =
true;
334 std::vector<size_t> active_faces;
335 active_faces.reserve(5);
336 active_faces.push_back(0);
337 active_faces.push_back(1);
339 if (convex_active_faces & 2) active_faces.push_back(2);
340 if (convex_active_faces & 4) active_faces.push_back(4);
341 if (convex_active_faces & 8) active_faces.push_back(6);
343 Triangle face_triangle;
344 Scalar shortest_distance_to_face = (std::numeric_limits<Scalar>::max)();
345 face_normal = normal;
346 for (
const size_t active_face : active_faces) {
347 size_t closest_face_id;
348 const Scalar distance_to_face = distanceContactPointToFace(
349 active_face, contact_1, convex, closest_face_id);
351 const bool contact_point_is_on_face = distance_to_face <= prec;
352 if (contact_point_is_on_face) {
353 hfield_witness_is_on_bin_side =
false;
354 face_triangle = (*(convex.polygons))[closest_face_id];
355 shortest_distance_to_face = distance_to_face;
357 }
else if (distance_to_face < shortest_distance_to_face) {
358 face_triangle = (*(convex.polygons))[closest_face_id];
359 shortest_distance_to_face = distance_to_face;
365 if (!face_triangle.isValid())
368 const Vec3s face_pointA = points[face_triangle[0]];
369 face_normal = computeTriangleNormal(face_triangle, points);
375 const Vec3s _support = getSupport<details::SupportOptions::WithSweptSphere>(
376 &shape, -shape_pose.rotation().transpose() * face_normal, hint);
377 const Vec3s support =
378 shape_pose.rotation() * _support + shape_pose.translation();
381 const Scalar offset_plane = face_normal.dot(face_pointA);
382 const Plane projection_plane(face_normal, offset_plane);
383 const Scalar distance_support_projection_plane =
384 projection_plane.signedDistance(support);
386 const Vec3s projected_support =
387 support - distance_support_projection_plane * face_normal;
391 projectPointOnTriangle(projected_support, face_triangle, points);
392 contact_2 = contact_1 + distance_support_projection_plane * face_normal;
393 normal = face_normal;
394 distance = -std::fabs(distance_support_projection_plane);
397 return hfield_witness_is_on_bin_side;
400 template <
typename Polygone,
typename Shape,
int Options>
401 bool shapeDistance(
const GJKSolver* nsolver,
const CollisionRequest& request,
402 const Convex<Polygone>& convex1,
403 const int convex1_active_faces,
404 const Convex<Polygone>& convex2,
405 const int convex2_active_faces,
const Transform3s& tf1,
408 bool& hfield_witness_is_on_bin_side) {
409 enum { RTIsIdentity = Options & RelativeTransformationIsIdentity };
411 const Transform3s Id;
417 const bool compute_penetration =
true;
418 Vec3s contact1_1, contact1_2, contact2_1, contact2_2;
419 Vec3s normal1, normal1_top, normal2, normal2_top;
420 Scalar distance1, distance2;
423 distance1 = internal::ShapeShapeDistance<Convex<Polygone>, Shape>(
424 &convex1, Id, &shape, tf2, nsolver, compute_penetration, contact1_1,
425 contact1_2, normal1);
427 distance1 = internal::ShapeShapeDistance<Convex<Polygone>, Shape>(
428 &convex1, tf1, &shape, tf2, nsolver, compute_penetration, contact1_1,
429 contact1_2, normal1);
431 bool collision1 = (distance1 - request.security_margin <=
432 request.collision_distance_threshold);
434 bool hfield_witness_is_on_bin_side1 =
435 binCorrection(convex1, convex1_active_faces, shape, tf2, distance1,
436 contact1_1, contact1_2, normal1, normal1_top, collision1);
439 distance2 = internal::ShapeShapeDistance<Convex<Polygone>, Shape>(
440 &convex2, Id, &shape, tf2, nsolver, compute_penetration, contact2_1,
441 contact2_2, normal2);
443 distance2 = internal::ShapeShapeDistance<Convex<Polygone>, Shape>(
444 &convex2, tf1, &shape, tf2, nsolver, compute_penetration, contact2_1,
445 contact2_2, normal2);
447 bool collision2 = (distance2 - request.security_margin <=
448 request.collision_distance_threshold);
450 bool hfield_witness_is_on_bin_side2 =
451 binCorrection(convex2, convex2_active_faces, shape, tf2, distance2,
452 contact2_1, contact2_2, normal2, normal2_top, collision2);
454 if (collision1 && collision2) {
455 if (distance1 > distance2)
461 normal_top = normal2_top;
462 hfield_witness_is_on_bin_side = hfield_witness_is_on_bin_side2;
468 normal_top = normal1_top;
469 hfield_witness_is_on_bin_side = hfield_witness_is_on_bin_side1;
472 }
else if (collision1) {
477 normal_top = normal1_top;
478 hfield_witness_is_on_bin_side = hfield_witness_is_on_bin_side1;
480 }
else if (collision2) {
485 normal_top = normal2_top;
486 hfield_witness_is_on_bin_side = hfield_witness_is_on_bin_side2;
490 if (distance1 > distance2)
496 normal_top = normal2_top;
497 hfield_witness_is_on_bin_side = hfield_witness_is_on_bin_side2;
503 normal_top = normal1_top;
504 hfield_witness_is_on_bin_side = hfield_witness_is_on_bin_side1;
512 template <
typename BV,
typename S,
513 int _Options = RelativeTransformationIsIdentity>
514 class HeightFieldShapeCollisionTraversalNode
515 :
public CollisionTraversalNodeBase {
517 typedef CollisionTraversalNodeBase Base;
521 RTIsIdentity = _Options & RelativeTransformationIsIdentity
524 HeightFieldShapeCollisionTraversalNode(
const CollisionRequest& request)
525 : CollisionTraversalNodeBase(request) {
531 query_time_seconds = 0.0;
538 bool isFirstNodeLeaf(
unsigned int b)
const {
539 return model1->getBV(b).isLeaf();
543 int getFirstLeftChild(
unsigned int b)
const {
544 return static_cast<int>(model1->getBV(b).leftChild());
548 int getFirstRightChild(
unsigned int b)
const {
549 return static_cast<int>(model1->getBV(b).rightChild());
557 bool BVDisjoints(
unsigned int b1,
unsigned int ,
558 Scalar& sqrDistLowerBound)
const {
559 if (this->enable_statistics) this->num_bv_tests++;
563 assert(
false &&
"must never happened");
564 disjoint = !this->model1->getBV(b1).bv.overlap(
565 this->model2_bv, this->request, sqrDistLowerBound);
567 disjoint = !
overlap(this->tf1.getRotation(), this->tf1.getTranslation(),
568 this->model1->getBV(b1).bv, this->model2_bv,
569 this->request, sqrDistLowerBound);
576 assert(!disjoint || sqrDistLowerBound > 0);
581 void leafCollides(
unsigned int b1,
unsigned int ,
582 Scalar& sqrDistLowerBound)
const {
584 if (this->enable_statistics) this->num_leaf_tests++;
585 const HFNode<BV>& node = this->model1->getBV(b1);
594 typedef Convex<Triangle> ConvexTriangle;
595 ConvexTriangle convex1, convex2;
596 int convex1_active_faces, convex2_active_faces;
598 details::buildConvexTriangles(node, *this->model1, convex1,
599 convex1_active_faces, convex2,
600 convex2_active_faces);
604 convex1.computeLocalAABB();
605 convex2.computeLocalAABB();
610 Vec3s c1, c2, normal, normal_face;
611 bool hfield_witness_is_on_bin_side;
613 bool collision = details::shapeDistance<Triangle, S, Options>(
614 nsolver, this->request, convex1, convex1_active_faces, convex2,
615 convex2_active_faces, this->tf1, *(this->model2), this->tf2,
distance,
616 c1, c2, normal, normal_face, hfield_witness_is_on_bin_side);
618 Scalar distToCollision =
distance - this->request.security_margin;
619 if (distToCollision <= this->request.collision_distance_threshold) {
620 sqrDistLowerBound = 0;
621 if (this->result->numContacts() < this->request.num_max_contacts) {
622 if (normal_face.isApprox(normal) &&
623 (collision || !hfield_witness_is_on_bin_side)) {
624 this->result->addContact(Contact(this->model1, this->model2, (
int)b1,
627 assert(this->result->isCollision());
631 sqrDistLowerBound = distToCollision * distToCollision;
636 distToCollision, c1, c2, normal);
638 assert(this->result->isCollision() || sqrDistLowerBound > 0);
641 const GJKSolver* nsolver;
643 const HeightField<BV>* model1;
647 mutable int num_bv_tests;
648 mutable int num_leaf_tests;
649 mutable Scalar query_time_seconds;
659 template <
typename BV,
typename S,
660 int _Options = RelativeTransformationIsIdentity>
661 class HeightFieldShapeDistanceTraversalNode :
public DistanceTraversalNodeBase {
663 typedef DistanceTraversalNodeBase Base;
667 RTIsIdentity = _Options & RelativeTransformationIsIdentity
670 HeightFieldShapeDistanceTraversalNode() : DistanceTraversalNodeBase() {
675 query_time_seconds = 0.0;
683 bool isFirstNodeLeaf(
unsigned int b)
const {
684 return model1->getBV(b).isLeaf();
688 int getFirstLeftChild(
unsigned int b)
const {
689 return model1->getBV(b).leftChild();
693 int getFirstRightChild(
unsigned int b)
const {
694 return model1->getBV(b).rightChild();
698 Scalar BVDistanceLowerBound(
unsigned int b1,
unsigned int )
const {
699 return model1->getBV(b1).bv.distance(
707 void leafComputeDistance(
unsigned int b1,
unsigned int )
const {
708 if (this->enable_statistics) this->num_leaf_tests++;
710 const BVNode<BV>& node = this->model1->getBV(b1);
712 typedef Convex<Quadrilateral> ConvexQuadrilateral;
713 const ConvexQuadrilateral convex =
714 details::buildConvexQuadrilateral(node, *this->model1);
716 Vec3s p1, p2, normal;
718 internal::ShapeShapeDistance<ConvexQuadrilateral, S>(
719 &convex, this->tf1, this->model2, this->tf2, this->nsolver,
720 this->request.enable_signed_distance, p1, p2, normal);
722 this->result->update(
distance, this->model1, this->model2, b1,
727 bool canStop(
Scalar c)
const {
728 if ((c >= this->result->min_distance - abs_err) &&
729 (c * (1 + rel_err) >= this->result->min_distance))
737 const GJKSolver* nsolver;
739 const HeightField<BV>* model1;
743 mutable int num_bv_tests;
744 mutable int num_leaf_tests;
745 mutable Scalar query_time_seconds;
#define COAL_UNUSED_VARIABLE(var)
Definition: fwd.hh:56
#define COAL_THROW_PRETTY(message, exception)
Definition: fwd.hh:64
Scalar distance(const Matrix3s &R0, const Vec3s &T0, const kIOS &b1, const kIOS &b2, Vec3s *P=NULL, Vec3s *Q=NULL)
Approximate distance between two kIOS bounding volumes.
bool overlap(const Matrix3s &R0, const Vec3s &T0, const AABB &b1, const AABB &b2)
Check collision between two aabbs, b1 is in configuration (R0, T0) and b2 is in identity.
void updateDistanceLowerBoundFromBV(const CollisionRequest &, CollisionResult &res, const Scalar sqrDistLowerBound)
Definition: collision_data.h:1171
void updateDistanceLowerBoundFromLeaf(const CollisionRequest &, CollisionResult &res, const Scalar &distance, const Vec3s &p0, const Vec3s &p1, const Vec3s &normal)
Definition: collision_data.h:1180
Main namespace.
Definition: broadphase_bruteforce.h:44
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > VecXs
Definition: data_types.h:73
Eigen::Matrix< Scalar, 3, 1 > Vec3s
Definition: data_types.h:70
double Scalar
Definition: data_types.h:68
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > MatrixXs
Definition: data_types.h:79
@ BoundingVolumeGuess
Definition: data_types.h:105
static const int NONE
invalid contact primitive information
Definition: collision_data.h:1085
FaceOrientation
Definition: hfield.h:56