coal/hfield.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2021-2024, INRIA
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Open Source Robotics Foundation nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
37 #ifndef COAL_HEIGHT_FIELD_H
38 #define COAL_HEIGHT_FIELD_H
39 
40 #include "coal/fwd.hh"
41 #include "coal/data_types.h"
42 #include "coal/collision_object.h"
43 #include "coal/BV/BV_node.h"
44 #include "coal/BVH/BVH_internal.h"
45 
46 #include <vector>
47 
48 namespace coal {
49 
52 
53 struct COAL_DLLAPI HFNodeBase {
54  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
55 
56  enum class FaceOrientation {
57  TOP = 1,
58  BOTTOM = 1,
59  NORTH = 2,
60  EAST = 4,
61  SOUTH = 8,
62  WEST = 16
63  };
64 
69  size_t first_child;
70 
71  Eigen::DenseIndex x_id, x_size;
72  Eigen::DenseIndex y_id, y_size;
73 
76 
79  : first_child(0),
80  x_id(-1),
81  x_size(0),
82  y_id(-1),
83  y_size(0),
84  max_height(std::numeric_limits<CoalScalar>::lowest()),
85  contact_active_faces(0) {}
86 
88  bool operator==(const HFNodeBase& other) const {
89  return first_child == other.first_child && x_id == other.x_id &&
90  x_size == other.x_size && y_id == other.y_id &&
91  y_size == other.y_size && max_height == other.max_height &&
92  contact_active_faces == other.contact_active_faces;
93  }
94 
96  bool operator!=(const HFNodeBase& other) const { return !(*this == other); }
97 
100  inline bool isLeaf() const { return x_size == 1 && y_size == 1; }
101 
104  inline size_t leftChild() const { return first_child; }
105 
108  inline size_t rightChild() const { return first_child + 1; }
109 
110  inline Eigen::Vector2i leftChildIndexes() const {
111  return Eigen::Vector2i(x_id, y_id);
112  }
113  inline Eigen::Vector2i rightChildIndexes() const {
114  return Eigen::Vector2i(x_id + x_size / 2, y_id + y_size / 2);
115  }
116 };
117 
120  return HFNodeBase::FaceOrientation(int(a) & int(b));
121 }
122 
124  return a & int(b);
125 }
126 
127 template <typename BV>
128 struct COAL_DLLAPI HFNode : public HFNodeBase {
129  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
130 
131  typedef HFNodeBase Base;
132 
134  BV bv;
135 
137  bool operator==(const HFNode& other) const {
138  return Base::operator==(other) && bv == other.bv;
139  }
140 
142  bool operator!=(const HFNode& other) const { return !(*this == other); }
143 
145  bool overlap(const HFNode& other) const { return bv.overlap(other.bv); }
147  bool overlap(const HFNode& other, const CollisionRequest& request,
148  CoalScalar& sqrDistLowerBound) const {
149  return bv.overlap(other.bv, request, sqrDistLowerBound);
150  }
151 
154  CoalScalar distance(const HFNode& other, Vec3s* P1 = NULL,
155  Vec3s* P2 = NULL) const {
156  return bv.distance(other.bv, P1, P2);
157  }
158 
160  Vec3s getCenter() const { return bv.center(); }
161 
163  coal::Matrix3s::IdentityReturnType getOrientation() const {
164  return Matrix3s::Identity();
165  }
166 
167  virtual ~HFNode() {}
168 };
169 
170 namespace details {
171 
172 template <typename BV>
174  static void run(const Vec3s& pointA, const Vec3s& pointB, BV& bv) {
175  AABB bv_aabb(pointA, pointB);
176  // AABB bv_aabb;
177  // bv_aabb.update(pointA,pointB);
178  convertBV(bv_aabb, bv);
179  }
180 };
181 
182 template <>
184  static void run(const Vec3s& pointA, const Vec3s& pointB, AABB& bv) {
185  AABB bv_aabb(pointA, pointB);
186  convertBV(bv_aabb, bv);
187  // bv.update(pointA,pointB);
188  }
189 };
190 
191 } // namespace details
192 
201 template <typename BV>
202 class COAL_DLLAPI HeightField : public CollisionGeometry {
203  public:
204  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
205 
207 
208  typedef HFNode<BV> Node;
209  typedef std::vector<Node, Eigen::aligned_allocator<Node>> BVS;
210 
213  : CollisionGeometry(),
214  min_height((std::numeric_limits<CoalScalar>::min)()),
215  max_height((std::numeric_limits<CoalScalar>::max)()) {}
216 
228  HeightField(const CoalScalar x_dim, const CoalScalar y_dim,
229  const MatrixXs& heights,
230  const CoalScalar min_height = (CoalScalar)0)
231  : CollisionGeometry() {
232  init(x_dim, y_dim, heights, min_height);
233  }
234 
239  HeightField(const HeightField& other)
240  : CollisionGeometry(other),
241  x_dim(other.x_dim),
242  y_dim(other.y_dim),
243  heights(other.heights),
244  min_height(other.min_height),
245  max_height(other.max_height),
246  x_grid(other.x_grid),
247  y_grid(other.y_grid),
248  bvs(other.bvs),
249  num_bvs(other.num_bvs) {}
250 
252  const VecXs& getXGrid() const { return x_grid; }
254  const VecXs& getYGrid() const { return y_grid; }
255 
257  const MatrixXs& getHeights() const { return heights; }
258 
260  CoalScalar getXDim() const { return x_dim; }
262  CoalScalar getYDim() const { return y_dim; }
263 
265  CoalScalar getMinHeight() const { return min_height; }
267  CoalScalar getMaxHeight() const { return max_height; }
268 
269  virtual HeightField<BV>* clone() const { return new HeightField(*this); }
270 
271  const BVS& getNodes() const { return bvs; }
272 
274  virtual ~HeightField() {}
275 
279  const Vec3s A(x_grid[0], y_grid[0], min_height);
280  const Vec3s B(x_grid[x_grid.size() - 1], y_grid[y_grid.size() - 1],
281  max_height);
282  const AABB aabb_(A, B);
283 
284  aabb_radius = (A - B).norm() / 2.;
285  aabb_local = aabb_;
286  aabb_center = aabb_.center();
287  }
288 
290  void updateHeights(const MatrixXs& new_heights) {
291  if (new_heights.rows() != heights.rows() ||
292  new_heights.cols() != heights.cols())
294  "The matrix containing the new heights values does not have the same "
295  "matrix size as the original one.\n"
296  "\tinput values - rows: "
297  << new_heights.rows() << " - cols: " << new_heights.cols() << "\n"
298  << "\texpected values - rows: " << heights.rows()
299  << " - cols: " << heights.cols() << "\n",
300  std::invalid_argument);
301 
302  heights = new_heights.cwiseMax(min_height);
303  this->max_height = recursiveUpdateHeight(0);
304  assert(this->max_height == heights.maxCoeff());
305  }
306 
307  protected:
308  void init(const CoalScalar x_dim, const CoalScalar y_dim,
309  const MatrixXs& heights, const CoalScalar min_height) {
310  this->x_dim = x_dim;
311  this->y_dim = y_dim;
312  this->heights = heights.cwiseMax(min_height);
313  this->min_height = min_height;
314  this->max_height = heights.maxCoeff();
315 
316  const Eigen::DenseIndex NX = heights.cols(), NY = heights.rows();
317  assert(NX >= 2 && "The number of columns is too small.");
318  assert(NY >= 2 && "The number of rows is too small.");
319 
320  x_grid = VecXs::LinSpaced(NX, -0.5 * x_dim, 0.5 * x_dim);
321  y_grid = VecXs::LinSpaced(NY, 0.5 * y_dim, -0.5 * y_dim);
322 
323  // Allocate BVS
324  const size_t num_tot_bvs =
325  (size_t)(NX * NY) - 1 + (size_t)((NX - 1) * (NY - 1));
326  bvs.resize(num_tot_bvs);
327  num_bvs = 0;
328 
329  // Build tree
330  buildTree();
331  }
332 
334  OBJECT_TYPE getObjectType() const { return OT_HFIELD; }
335 
336  Vec3s computeCOM() const { return Vec3s::Zero(); }
337 
338  CoalScalar computeVolume() const { return 0; }
339 
340  Matrix3s computeMomentofInertia() const { return Matrix3s::Zero(); }
341 
342  protected:
345 
348 
351  CoalScalar min_height, max_height;
352 
355  VecXs x_grid, y_grid;
356 
359  unsigned int num_bvs;
360 
362  int buildTree() {
363  num_bvs = 1;
364  const CoalScalar max_recursive_height =
365  recursiveBuildTree(0, 0, heights.cols() - 1, 0, heights.rows() - 1);
366  assert(max_recursive_height == max_height &&
367  "the maximal height is not correct");
368  COAL_UNUSED_VARIABLE(max_recursive_height);
369 
370  bvs.resize(num_bvs);
371  return BVH_OK;
372  }
373 
374  CoalScalar recursiveUpdateHeight(const size_t bv_id) {
375  HFNode<BV>& bv_node = bvs[bv_id];
376 
377  CoalScalar max_height;
378  if (bv_node.isLeaf()) {
379  max_height = heights.block<2, 2>(bv_node.y_id, bv_node.x_id).maxCoeff();
380  } else {
381  CoalScalar max_left_height = recursiveUpdateHeight(bv_node.leftChild()),
382  max_right_height = recursiveUpdateHeight(bv_node.rightChild());
383 
384  max_height = (std::max)(max_left_height, max_right_height);
385  }
386 
387  bv_node.max_height = max_height;
388 
389  const Vec3s pointA(x_grid[bv_node.x_id], y_grid[bv_node.y_id], min_height);
390  const Vec3s pointB(x_grid[bv_node.x_id + bv_node.x_size],
391  y_grid[bv_node.y_id + bv_node.y_size], max_height);
392 
393  details::UpdateBoundingVolume<BV>::run(pointA, pointB, bv_node.bv);
394 
395  return max_height;
396  }
397 
398  CoalScalar recursiveBuildTree(const size_t bv_id,
399  const Eigen::DenseIndex x_id,
400  const Eigen::DenseIndex x_size,
401  const Eigen::DenseIndex y_id,
402  const Eigen::DenseIndex y_size) {
403  assert(x_id < heights.cols() && "x_id is out of bounds");
404  assert(y_id < heights.rows() && "y_id is out of bounds");
405  assert(x_size >= 0 && y_size >= 0 &&
406  "x_size or y_size are not of correct value");
407  assert(bv_id < bvs.size() && "bv_id exceeds the vector dimension");
408 
409  HFNode<BV>& bv_node = bvs[bv_id];
410  CoalScalar max_height;
411  if (x_size == 1 &&
412  y_size == 1) // don't build any BV for the current child node
413  {
414  max_height = heights.block<2, 2>(y_id, x_id).maxCoeff();
415  } else {
416  bv_node.first_child = num_bvs;
417  num_bvs += 2;
418 
419  CoalScalar max_left_height = min_height, max_right_height = min_height;
420  if (x_size >= y_size) // splitting along the X axis
421  {
422  Eigen::DenseIndex x_size_half = x_size / 2;
423  if (x_size == 1) x_size_half = 1;
424  max_left_height = recursiveBuildTree(bv_node.leftChild(), x_id,
425  x_size_half, y_id, y_size);
426 
427  max_right_height =
428  recursiveBuildTree(bv_node.rightChild(), x_id + x_size_half,
429  x_size - x_size_half, y_id, y_size);
430  } else // splitting along the Y axis
431  {
432  Eigen::DenseIndex y_size_half = y_size / 2;
433  if (y_size == 1) y_size_half = 1;
434  max_left_height = recursiveBuildTree(bv_node.leftChild(), x_id, x_size,
435  y_id, y_size_half);
436 
437  max_right_height =
438  recursiveBuildTree(bv_node.rightChild(), x_id, x_size,
439  y_id + y_size_half, y_size - y_size_half);
440  }
441 
442  max_height = (std::max)(max_left_height, max_right_height);
443  }
444 
445  bv_node.max_height = max_height;
446  // max_height = std::max(max_height,min_height);
447 
448  const Vec3s pointA(x_grid[x_id], y_grid[y_id], min_height);
449  assert(x_id + x_size < x_grid.size());
450  assert(y_id + y_size < y_grid.size());
451  const Vec3s pointB(x_grid[x_id + x_size], y_grid[y_id + y_size],
452  max_height);
453 
454  details::UpdateBoundingVolume<BV>::run(pointA, pointB, bv_node.bv);
455  bv_node.x_id = x_id;
456  bv_node.y_id = y_id;
457  bv_node.x_size = x_size;
458  bv_node.y_size = y_size;
459 
460  if (bv_node.isLeaf()) {
461  int& contact_active_faces = bv_node.contact_active_faces;
462  contact_active_faces |= int(HFNodeBase::FaceOrientation::TOP);
463  contact_active_faces |= int(HFNodeBase::FaceOrientation::BOTTOM);
464 
465  if (bv_node.x_id == 0) // first col
466  contact_active_faces |= int(HFNodeBase::FaceOrientation::WEST);
467 
468  if (bv_node.y_id == 0) // first row (TOP)
469  contact_active_faces |= int(HFNodeBase::FaceOrientation::NORTH);
470 
471  if (bv_node.x_id + 1 == heights.cols() - 1) // last col
472  contact_active_faces |= int(HFNodeBase::FaceOrientation::EAST);
473 
474  if (bv_node.y_id + 1 == heights.rows() - 1) // last row (BOTTOM)
475  contact_active_faces |= int(HFNodeBase::FaceOrientation::SOUTH);
476  }
477 
478  return max_height;
479  }
480 
481  public:
483  const HFNode<BV>& getBV(unsigned int i) const {
484  if (i >= num_bvs)
485  COAL_THROW_PRETTY("Index out of bounds", std::invalid_argument);
486  return bvs[i];
487  }
488 
490  HFNode<BV>& getBV(unsigned int i) {
491  if (i >= num_bvs)
492  COAL_THROW_PRETTY("Index out of bounds", std::invalid_argument);
493  return bvs[i];
494  }
495 
497  NODE_TYPE getNodeType() const { return BV_UNKNOWN; }
498 
499  private:
500  virtual bool isEqual(const CollisionGeometry& _other) const {
501  const HeightField* other_ptr = dynamic_cast<const HeightField*>(&_other);
502  if (other_ptr == nullptr) return false;
503  const HeightField& other = *other_ptr;
504 
505  return x_dim == other.x_dim && y_dim == other.y_dim &&
506  heights == other.heights && min_height == other.min_height &&
507  max_height == other.max_height && x_grid == other.x_grid &&
508  y_grid == other.y_grid && bvs == other.bvs &&
509  num_bvs == other.num_bvs;
510  }
511 };
512 
515 template <>
517 
518 template <>
520 
521 template <>
523 
524 template <>
526 
527 template <>
529 
530 template <>
531 NODE_TYPE HeightField<KDOP<16>>::getNodeType() const;
532 
533 template <>
534 NODE_TYPE HeightField<KDOP<18>>::getNodeType() const;
535 
536 template <>
537 NODE_TYPE HeightField<KDOP<24>>::getNodeType() const;
538 
540 
541 } // namespace coal
542 
543 #endif
coal::BV_UNKNOWN
@ BV_UNKNOWN
Definition: coal/collision_object.h:65
coal::HeightField::getXGrid
const VecXs & getXGrid() const
Returns a const reference of the grid along the X direction.
Definition: coal/hfield.h:252
coal::HFNode::Base
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef HFNodeBase Base
Definition: coal/hfield.h:131
coal::HeightField::HeightField
HeightField(const CoalScalar x_dim, const CoalScalar y_dim, const MatrixXs &heights, const CoalScalar min_height=(CoalScalar) 0)
Constructing an HeightField from its base dimensions and the set of heights points....
Definition: coal/hfield.h:228
coal::HeightField::getHeights
const MatrixXs & getHeights() const
Returns a const reference of the heights.
Definition: coal/hfield.h:257
coal::HeightField::computeCOM
Vec3s computeCOM() const
compute center of mass
Definition: coal/hfield.h:336
coal::HFNodeBase
Definition: coal/hfield.h:53
coal::Vec3s
Eigen::Matrix< CoalScalar, 3, 1 > Vec3s
Definition: coal/data_types.h:77
coal::HFNodeBase::y_id
Eigen::DenseIndex y_id
Definition: coal/hfield.h:72
coal::HFNodeBase::FaceOrientation::WEST
@ WEST
coal::HeightField::HeightField
HeightField(const HeightField &other)
Copy contructor from another HeightField.
Definition: coal/hfield.h:239
coal::HeightField::~HeightField
virtual ~HeightField()
deconstruction, delete mesh data related.
Definition: coal/hfield.h:274
coal::HFNode::~HFNode
virtual ~HFNode()
Definition: coal/hfield.h:167
coal::HFNodeBase::leftChildIndexes
Eigen::Vector2i leftChildIndexes() const
Definition: coal/hfield.h:110
B
B
coal::HFNodeBase::HFNodeBase
HFNodeBase()
Default constructor.
Definition: coal/hfield.h:78
coal::HeightField::init
void init(const CoalScalar x_dim, const CoalScalar y_dim, const MatrixXs &heights, const CoalScalar min_height)
Definition: coal/hfield.h:308
coal::HeightField::getNodeType
NODE_TYPE getNodeType() const
Get the BV type: default is unknown.
Definition: coal/hfield.h:497
coal::HFNodeBase::rightChildIndexes
Eigen::Vector2i rightChildIndexes() const
Definition: coal/hfield.h:113
coal::NODE_TYPE
NODE_TYPE
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18,...
Definition: coal/collision_object.h:64
coal::HeightField::computeMomentofInertia
Matrix3s computeMomentofInertia() const
compute the inertia matrix, related to the origin
Definition: coal/hfield.h:340
gjk.P2
tuple P2
Definition: test/scripts/gjk.py:22
coal
Main namespace.
Definition: coal/broadphase/broadphase_bruteforce.h:44
coal::operator&
CollisionRequestFlag operator&(CollisionRequestFlag a, CollisionRequestFlag b)
Definition: coal/collision_data.h:1208
coal::HeightField::y_dim
CoalScalar y_dim
Definition: coal/hfield.h:344
coal::HeightField::recursiveUpdateHeight
CoalScalar recursiveUpdateHeight(const size_t bv_id)
Definition: coal/hfield.h:374
coal::HeightField::getYDim
CoalScalar getYDim() const
Returns the dimension of the Height Field along the Y direction.
Definition: coal/hfield.h:262
collision_object.h
coal::HFNodeBase::x_id
Eigen::DenseIndex x_id
Definition: coal/hfield.h:71
coal::HeightField::HeightField
HeightField()
Constructing an empty HeightField.
Definition: coal/hfield.h:212
coal::CollisionGeometry
The geometry for the object for collision or distance computation.
Definition: coal/collision_object.h:94
coal::HeightField::updateHeights
void updateHeights(const MatrixXs &new_heights)
Update Height Field height.
Definition: coal/hfield.h:290
coal::AABB
A class describing the AABB collision structure, which is a box in 3D space determined by two diagona...
Definition: coal/BV/AABB.h:55
coal::HeightField::computeLocalAABB
void computeLocalAABB()
Compute the AABB for the HeightField, used for broad-phase collision.
Definition: coal/hfield.h:278
a
list a
coal::HFNodeBase::FaceOrientation::SOUTH
@ SOUTH
coal::HFNodeBase::isLeaf
bool isLeaf() const
Whether current node is a leaf node (i.e. contains a primitive index)
Definition: coal/hfield.h:100
coal::HFNode::operator==
bool operator==(const HFNode &other) const
Equality operator.
Definition: coal/hfield.h:137
coal::HFNodeBase::operator!=
bool operator!=(const HFNodeBase &other) const
Difference operator.
Definition: coal/hfield.h:96
coal::HeightField::clone
virtual HeightField< BV > * clone() const
Clone *this into a new CollisionGeometry.
Definition: coal/hfield.h:269
COAL_UNUSED_VARIABLE
#define COAL_UNUSED_VARIABLE(var)
Definition: include/coal/fwd.hh:56
coal::HeightField::recursiveBuildTree
CoalScalar recursiveBuildTree(const size_t bv_id, const Eigen::DenseIndex x_id, const Eigen::DenseIndex x_size, const Eigen::DenseIndex y_id, const Eigen::DenseIndex y_size)
Definition: coal/hfield.h:398
gjk.P1
tuple P1
Definition: test/scripts/gjk.py:21
coal::VecXs
Eigen::Matrix< CoalScalar, Eigen::Dynamic, 1 > VecXs
Definition: coal/data_types.h:80
coal::HeightField::BVS
std::vector< Node, Eigen::aligned_allocator< Node > > BVS
Definition: coal/hfield.h:209
coal::HeightField::getMinHeight
CoalScalar getMinHeight() const
Returns the minimal height value of the Height Field.
Definition: coal/hfield.h:265
coal::HeightField::isEqual
virtual bool isEqual(const CollisionGeometry &_other) const
equal operator with another object of derived type.
Definition: coal/hfield.h:500
coal::HeightField::Node
HFNode< BV > Node
Definition: coal/hfield.h:208
fwd.hh
COAL_THROW_PRETTY
#define COAL_THROW_PRETTY(message, exception)
Definition: include/coal/fwd.hh:64
coal::HeightField::getNodes
const BVS & getNodes() const
Definition: coal/hfield.h:271
coal::HFNode::getOrientation
coal::Matrix3s::IdentityReturnType getOrientation() const
Access to the orientation of the BV.
Definition: coal/hfield.h:163
coal::HeightField::buildTree
int buildTree()
Build the bounding volume hierarchy.
Definition: coal/hfield.h:362
coal::details::UpdateBoundingVolume< AABB >::run
static void run(const Vec3s &pointA, const Vec3s &pointB, AABB &bv)
Definition: coal/hfield.h:184
coal::CollisionRequest
request to the collision algorithm
Definition: coal/collision_data.h:311
coal::HFNode::getCenter
Vec3s getCenter() const
Access to the center of the BV.
Definition: coal/hfield.h:160
coal::HFNodeBase::FaceOrientation::TOP
@ TOP
coal::details::UpdateBoundingVolume
Definition: coal/hfield.h:173
coal::BVH_OK
@ BVH_OK
Definition: coal/BVH/BVH_internal.h:64
coal::HeightField::getMaxHeight
CoalScalar getMaxHeight() const
Returns the maximal height value of the Height Field.
Definition: coal/hfield.h:267
coal::HeightField::computeVolume
CoalScalar computeVolume() const
compute the volume
Definition: coal/hfield.h:338
coal::HFNodeBase::first_child
size_t first_child
An index for first child node or primitive If the value is positive, it is the index of the first chi...
Definition: coal/hfield.h:69
coal::HeightField::getXDim
CoalScalar getXDim() const
Returns the dimension of the Height Field along the X direction.
Definition: coal/hfield.h:260
coal::OBJECT_TYPE
OBJECT_TYPE
object type: BVH (mesh, points), basic geometry, octree
Definition: coal/collision_object.h:52
coal::HeightField::getBV
const HFNode< BV > & getBV(unsigned int i) const
Access the bv giving the its index.
Definition: coal/hfield.h:483
coal::HeightField::bvs
BVS bvs
Bounding volume hierarchy.
Definition: coal/hfield.h:358
BVH_internal.h
coal::HFNodeBase::max_height
CoalScalar max_height
Definition: coal/hfield.h:74
coal::HeightField::getObjectType
OBJECT_TYPE getObjectType() const
Get the object type: it is a HFIELD.
Definition: coal/hfield.h:334
coal::HeightField
Data structure depicting a height field given by the base grid dimensions and the elevation along the...
Definition: coal/hfield.h:202
coal::AABB::center
Vec3s center() const
Center of the AABB.
Definition: coal/BV/AABB.h:164
coal::HFNodeBase::rightChild
size_t rightChild() const
Return the index of the second child. The index is referred to the bounding volume array (i....
Definition: coal/hfield.h:108
coal::HeightField::x_dim
CoalScalar x_dim
Dimensions in meters along X and Y directions.
Definition: coal/hfield.h:344
coal::HFNodeBase::FaceOrientation::BOTTOM
@ BOTTOM
coal::HFNodeBase::FaceOrientation::EAST
@ EAST
coal::MatrixXs
Eigen::Matrix< CoalScalar, Eigen::Dynamic, Eigen::Dynamic > MatrixXs
Definition: coal/data_types.h:86
A
A
coal::HFNode::operator!=
bool operator!=(const HFNode &other) const
Difference operator.
Definition: coal/hfield.h:142
generate_distance_plot.b
float b
Definition: generate_distance_plot.py:7
coal::HFNodeBase::FaceOrientation
FaceOrientation
Definition: coal/hfield.h:56
coal::HFNode::bv
BV bv
bounding volume storing the geometry
Definition: coal/hfield.h:134
coal::HeightField::getYGrid
const VecXs & getYGrid() const
Returns a const reference of the grid along the Y direction.
Definition: coal/hfield.h:254
coal::Matrix3s
Eigen::Matrix< CoalScalar, 3, 3 > Matrix3s
Definition: coal/data_types.h:81
coal::HeightField::y_grid
VecXs y_grid
Definition: coal/hfield.h:355
coal::HFNode::overlap
bool overlap(const HFNode &other, const CollisionRequest &request, CoalScalar &sqrDistLowerBound) const
Check whether two BVNode collide.
Definition: coal/hfield.h:147
coal::HFNodeBase::x_size
Eigen::DenseIndex x_size
Definition: coal/hfield.h:71
coal::HFNodeBase::y_size
Eigen::DenseIndex y_size
Definition: coal/hfield.h:72
coal::HFNodeBase::contact_active_faces
int contact_active_faces
Definition: coal/hfield.h:75
coal::HeightField::heights
MatrixXs heights
Elevation values in meters of the Height Field.
Definition: coal/hfield.h:347
coal::HFNode
Definition: coal/hfield.h:128
coal::HFNodeBase::operator==
bool operator==(const HFNodeBase &other) const
Comparison operator.
Definition: coal/hfield.h:88
coal::HeightField::getBV
HFNode< BV > & getBV(unsigned int i)
Access the bv giving the its index.
Definition: coal/hfield.h:490
coal::convertBV
static void convertBV(const BV1 &bv1, const Transform3s &tf1, BV2 &bv2)
Convert a bounding volume of type BV1 in configuration tf1 to bounding volume of type BV2 in identity...
Definition: coal/BV/BV.h:276
coal::HeightField::x_grid
VecXs x_grid
Grids along the X and Y directions. Useful for plotting or other related things.
Definition: coal/hfield.h:355
coal::details::UpdateBoundingVolume::run
static void run(const Vec3s &pointA, const Vec3s &pointB, BV &bv)
Definition: coal/hfield.h:174
coal::HFNode::distance
CoalScalar distance(const HFNode &other, Vec3s *P1=NULL, Vec3s *P2=NULL) const
Compute the distance between two BVNode. P1 and P2, if not NULL and the underlying BV supports distan...
Definition: coal/hfield.h:154
coal::HeightField::Base
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef CollisionGeometry Base
Definition: coal/hfield.h:206
coal::OT_HFIELD
@ OT_HFIELD
Definition: coal/collision_object.h:57
coal::HeightField::max_height
CoalScalar max_height
Definition: coal/hfield.h:351
data_types.h
coal::CoalScalar
double CoalScalar
Definition: coal/data_types.h:76
coal::HeightField::num_bvs
unsigned int num_bvs
Definition: coal/hfield.h:359
coal::HFNodeBase::leftChild
size_t leftChild() const
Return the index of the first child. The index is referred to the bounding volume array (i....
Definition: coal/hfield.h:104
coal::HFNode::overlap
bool overlap(const HFNode &other) const
Check whether two BVNode collide.
Definition: coal/hfield.h:145
coal::HeightField::min_height
CoalScalar min_height
Minimal height of the Height Field: all values bellow min_height will be discarded.
Definition: coal/hfield.h:351
BV_node.h
coal::HFNodeBase::FaceOrientation::NORTH
@ NORTH


hpp-fcl
Author(s):
autogenerated on Sat Nov 23 2024 03:44:58