37 #ifndef HPP_FCL_TRAVERSAL_NODE_HFIELD_SHAPE_H
38 #define HPP_FCL_TRAVERSAL_NODE_HFIELD_SHAPE_H
58 template <
typename BV>
59 Convex<Quadrilateral> buildConvexQuadrilateral(
const HFNode<BV>& node,
60 const HeightField<BV>& model) {
61 const MatrixXf& heights = model.getHeights();
62 const VecXf& x_grid = model.getXGrid();
63 const VecXf& y_grid = model.getYGrid();
65 const FCL_REAL min_height = model.getMinHeight();
67 const FCL_REAL x0 = x_grid[node.x_id], x1 = x_grid[node.x_id + 1],
68 y0 = y_grid[node.y_id], y1 = y_grid[node.y_id + 1];
69 const Eigen::Block<const MatrixXf, 2, 2> cell =
70 heights.block<2, 2>(node.y_id, node.x_id);
72 assert(cell.maxCoeff() > min_height &&
73 "max_height is lower than min_height");
77 pts[0] =
Vec3f(x0, y0, min_height);
78 pts[1] =
Vec3f(x0, y1, min_height);
79 pts[2] =
Vec3f(x1, y1, min_height);
80 pts[3] =
Vec3f(x1, y0, min_height);
81 pts[4] =
Vec3f(x0, y0, cell(0, 0));
82 pts[5] =
Vec3f(x0, y1, cell(1, 0));
83 pts[6] =
Vec3f(x1, y1, cell(1, 1));
84 pts[7] =
Vec3f(x1, y0, cell(0, 1));
86 Quadrilateral* polygons =
new Quadrilateral[6];
87 polygons[0].set(0, 3, 2, 1);
88 polygons[1].set(0, 1, 5, 4);
89 polygons[2].set(1, 2, 6, 5);
90 polygons[3].set(2, 3, 7, 6);
91 polygons[4].set(3, 0, 4, 7);
92 polygons[5].set(4, 5, 6, 7);
94 return Convex<Quadrilateral>(
true,
102 template <
typename BV>
103 void buildConvexTriangles(
const HFNode<BV>& node,
const HeightField<BV>& model,
104 Convex<Triangle>& convex1,
105 Convex<Triangle>& convex2) {
106 const MatrixXf& heights = model.getHeights();
107 const VecXf& x_grid = model.getXGrid();
108 const VecXf& y_grid = model.getYGrid();
110 const FCL_REAL min_height = model.getMinHeight();
112 const FCL_REAL x0 = x_grid[node.x_id], x1 = x_grid[node.x_id + 1],
113 y0 = y_grid[node.y_id], y1 = y_grid[node.y_id + 1];
114 const FCL_REAL max_height = node.max_height;
115 const Eigen::Block<const MatrixXf, 2, 2> cell =
116 heights.block<2, 2>(node.y_id, node.x_id);
118 assert(max_height > min_height &&
119 "max_height is lower than min_height");
125 pts[0] =
Vec3f(x0, y0, min_height);
126 pts[1] =
Vec3f(x0, y1, min_height);
127 pts[2] =
Vec3f(x1, y1, min_height);
128 pts[3] =
Vec3f(x1, y0, min_height);
129 pts[4] =
Vec3f(x0, y0, cell(0, 0));
130 pts[5] =
Vec3f(x0, y1, cell(1, 0));
131 pts[6] =
Vec3f(x1, y1, cell(1, 1));
132 pts[7] =
Vec3f(x1, y0, cell(0, 1));
134 Triangle* triangles =
new Triangle[8];
135 triangles[0].set(0, 1, 3);
136 triangles[1].set(4, 5, 7);
137 triangles[2].set(0, 1, 4);
138 triangles[3].set(4, 1, 5);
139 triangles[4].set(1, 7, 3);
140 triangles[5].set(1, 5, 7);
141 triangles[6].set(0, 3, 7);
142 triangles[7].set(7, 4, 0);
154 memcpy(pts, convex1.points, 8 *
sizeof(
Vec3f));
156 Triangle* triangles =
new Triangle[8];
157 triangles[0].set(3, 2, 1);
158 triangles[1].set(5, 6, 7);
159 triangles[2].set(1, 2, 5);
160 triangles[3].set(5, 2, 6);
161 triangles[4].set(1, 3, 7);
162 triangles[5].set(1, 7, 5);
163 triangles[6].set(2, 3, 7);
164 triangles[7].set(6, 2, 3);
177 template <
typename BV,
typename S,
178 int _Options = RelativeTransformationIsIdentity>
179 class HeightFieldShapeCollisionTraversalNode
180 :
public CollisionTraversalNodeBase {
182 typedef CollisionTraversalNodeBase
Base;
183 typedef Eigen::Array<FCL_REAL, 1, 2> Array2d;
187 RTIsIdentity = _Options & RelativeTransformationIsIdentity
190 HeightFieldShapeCollisionTraversalNode(
const CollisionRequest& request)
191 : CollisionTraversalNodeBase(request) {
197 query_time_seconds = 0.0;
200 shape_inflation.setZero();
204 bool isFirstNodeLeaf(
unsigned int b)
const {
205 return model1->getBV(
b).isLeaf();
209 int getFirstLeftChild(
unsigned int b)
const {
210 return static_cast<int>(model1->getBV(
b).leftChild());
214 int getFirstRightChild(
unsigned int b)
const {
215 return static_cast<int>(model1->getBV(
b).rightChild());
223 bool BVDisjoints(
unsigned int b1,
unsigned int ,
224 FCL_REAL& sqrDistLowerBound)
const {
225 if (this->enable_statistics) this->num_bv_tests++;
229 assert(
false &&
"must never happened");
230 disjoint = !this->model1->getBV(b1).bv.overlap(
231 this->model2_bv, this->request, sqrDistLowerBound);
233 disjoint = !
overlap(this->
tf1.getRotation(), this->tf1.getTranslation(),
234 this->model1->getBV(b1).bv, this->model2_bv,
235 this->request, sqrDistLowerBound);
242 assert(!disjoint || sqrDistLowerBound > 0);
246 template <
typename Polygone>
247 bool shapeDistance(
const Convex<Polygone>& convex1,
248 const Convex<Polygone>& convex2,
const Transform3f&
tf1,
251 const Transform3f Id;
252 Vec3f contact2_1, contact2_2, normal2;
254 bool collision1, collision2;
256 collision1 = !nsolver->shapeDistance(convex1, Id, shape,
tf2,
distance,
259 collision1 = !nsolver->shapeDistance(convex1,
tf1, shape,
tf2,
distance,
263 collision2 = !nsolver->shapeDistance(convex2, Id, shape,
tf2, distance2,
266 collision2 = !nsolver->shapeDistance(convex2,
tf1, shape,
tf2, distance2,
267 contact2_1, contact2_2, normal2);
269 if (collision1 && collision2) {
278 }
else if (collision1) {
280 }
else if (collision2) {
291 template <
typename Polygone>
292 bool shapeCollision(
const Convex<Polygone>& convex1,
293 const Convex<Polygone>& convex2,
const Transform3f&
tf1,
294 const S& shape,
const Transform3f&
tf2,
296 Vec3f& normal)
const {
297 const Transform3f Id;
298 Vec3f contact_point2, normal2;
300 bool collision1, collision2;
304 true, &contact_point, &normal);
306 collision1 = nsolver->shapeIntersect(convex1,
tf1, shape,
tf2,
308 &contact_point, &normal);
311 collision2 = nsolver->shapeIntersect(convex2, Id, shape,
tf2,
312 distance_lower_bound2,
true,
313 &contact_point2, &normal2);
315 collision2 = nsolver->shapeIntersect(convex2,
tf1, shape,
tf2,
316 distance_lower_bound2,
true,
317 &contact_point2, &normal2);
319 if (collision1 && collision2) {
323 distance_lower_bound2 != -(std::numeric_limits<FCL_REAL>::max)()) {
327 contact_point = contact_point2;
330 }
else if (distance_lower_bound2 !=
331 -(std::numeric_limits<FCL_REAL>::max)()) {
333 contact_point = contact_point2;
337 }
else if (collision1) {
339 }
else if (collision2) {
341 contact_point = contact_point2;
350 void leafCollides(
unsigned int b1,
unsigned int ,
351 FCL_REAL& sqrDistLowerBound)
const {
352 if (this->enable_statistics) this->num_leaf_tests++;
353 const HFNode<BV>& node = this->model1->getBV(b1);
362 typedef Convex<Triangle> ConvexTriangle;
363 ConvexTriangle convex1, convex2;
364 details::buildConvexTriangles(node, *this->model1, convex1, convex2);
371 this->shapeDistance(convex1, convex2, this->tf1, *(this->model2),
372 this->tf2,
distance, c1, c2, normal);
379 if (distToCollision <= this->request.collision_distance_threshold) {
380 sqrDistLowerBound = 0;
381 if (this->request.num_max_contacts > this->result->numContacts()) {
382 this->result->addContact(Contact(this->model1, this->model2, (
int)b1,
384 (c2 - c1).normalized(), -
distance));
386 }
else if (
collision && this->request.security_margin >= 0) {
387 sqrDistLowerBound = 0;
388 if (this->request.num_max_contacts > this->result->numContacts()) {
389 this->result->addContact(Contact(this->model1, this->model2, (
int)b1,
392 assert(this->result->isCollision());
395 sqrDistLowerBound = distToCollision * distToCollision;
400 distToCollision, c1, c2);
402 assert(this->result->isCollision() || sqrDistLowerBound > 0);
405 const GJKSolver* nsolver;
407 const HeightField<BV>* model1;
411 Array2d shape_inflation;
413 mutable int num_bv_tests;
414 mutable int num_leaf_tests;
415 mutable FCL_REAL query_time_seconds;
424 template <
typename BV,
typename S,
425 int _Options = RelativeTransformationIsIdentity>
426 class HeightFieldShapeDistanceTraversalNode :
public DistanceTraversalNodeBase {
428 typedef DistanceTraversalNodeBase
Base;
432 RTIsIdentity = _Options & RelativeTransformationIsIdentity
435 HeightFieldShapeDistanceTraversalNode() : DistanceTraversalNodeBase() {
440 query_time_seconds = 0.0;
448 bool isFirstNodeLeaf(
unsigned int b)
const {
449 return model1->getBV(
b).isLeaf();
453 int getFirstLeftChild(
unsigned int b)
const {
454 return model1->getBV(
b).leftChild();
458 int getFirstRightChild(
unsigned int b)
const {
459 return model1->getBV(
b).rightChild();
463 FCL_REAL BVDistanceLowerBound(
unsigned int b1,
unsigned int )
const {
464 return model1->getBV(b1).bv.distance(
469 void leafComputeDistance(
unsigned int b1,
unsigned int )
const {
470 if (this->enable_statistics) this->num_leaf_tests++;
472 const BVNode<BV>& node = this->model1->getBV(b1);
474 typedef Convex<Quadrilateral> ConvexQuadrilateral;
475 const ConvexQuadrilateral convex =
476 details::buildConvexQuadrilateral(node, *this->model1);
479 Vec3f closest_p1, closest_p2, normal;
481 nsolver->shapeDistance(convex, this->tf1, *(this->model2), this->tf2, d,
482 closest_p1, closest_p2, normal);
484 this->result->update(d, this->model1, this->model2, b1,
490 if ((c >= this->result->min_distance - abs_err) &&
491 (c * (1 + rel_err) >= this->result->min_distance))
499 const GJKSolver* nsolver;
501 const HeightField<BV>* model1;
505 mutable int num_bv_tests;
506 mutable int num_leaf_tests;
507 mutable FCL_REAL query_time_seconds;