Go to the documentation of this file.
   37 #define BOOST_TEST_MODULE COAL_GEOMETRIC_SHAPES 
   38 #include <boost/test/included/unit_test.hpp> 
   53   for (
size_t i = 0; i < 8; ++i) {
 
   54     BOOST_CHECK_EQUAL((*
box.neighbors)[i].count(), 3);
 
   56   BOOST_CHECK_EQUAL((*
box.neighbors)[0][0], 1);
 
   57   BOOST_CHECK_EQUAL((*
box.neighbors)[0][1], 2);
 
   58   BOOST_CHECK_EQUAL((*
box.neighbors)[0][2], 4);
 
   60   BOOST_CHECK_EQUAL((*
box.neighbors)[1][0], 0);
 
   61   BOOST_CHECK_EQUAL((*
box.neighbors)[1][1], 3);
 
   62   BOOST_CHECK_EQUAL((*
box.neighbors)[1][2], 5);
 
   64   BOOST_CHECK_EQUAL((*
box.neighbors)[2][0], 0);
 
   65   BOOST_CHECK_EQUAL((*
box.neighbors)[2][1], 3);
 
   66   BOOST_CHECK_EQUAL((*
box.neighbors)[2][2], 6);
 
   68   BOOST_CHECK_EQUAL((*
box.neighbors)[3][0], 1);
 
   69   BOOST_CHECK_EQUAL((*
box.neighbors)[3][1], 2);
 
   70   BOOST_CHECK_EQUAL((*
box.neighbors)[3][2], 7);
 
   72   BOOST_CHECK_EQUAL((*
box.neighbors)[4][0], 0);
 
   73   BOOST_CHECK_EQUAL((*
box.neighbors)[4][1], 5);
 
   74   BOOST_CHECK_EQUAL((*
box.neighbors)[4][2], 6);
 
   76   BOOST_CHECK_EQUAL((*
box.neighbors)[5][0], 1);
 
   77   BOOST_CHECK_EQUAL((*
box.neighbors)[5][1], 4);
 
   78   BOOST_CHECK_EQUAL((*
box.neighbors)[5][2], 7);
 
   80   BOOST_CHECK_EQUAL((*
box.neighbors)[6][0], 2);
 
   81   BOOST_CHECK_EQUAL((*
box.neighbors)[6][1], 4);
 
   82   BOOST_CHECK_EQUAL((*
box.neighbors)[6][2], 7);
 
   84   BOOST_CHECK_EQUAL((*
box.neighbors)[7][0], 3);
 
   85   BOOST_CHECK_EQUAL((*
box.neighbors)[7][1], 5);
 
   86   BOOST_CHECK_EQUAL((*
box.neighbors)[7][2], 6);
 
   89 template <
typename Sa, 
typename Sb>
 
  105     BOOST_TEST_MESSAGE(
tf1 << 
'\n' 
  109                            << cB.pos.format(
pyfmt) << 
'\n');
 
  111     BOOST_WARN_SMALL((cA.
pos - cB.pos).squaredNorm(), tol);
 
  112     BOOST_WARN_SMALL((cA.
normal - cB.normal).squaredNorm(), tol);
 
  119 template <
typename Sa, 
typename Sb>
 
  128   BOOST_TEST_MESSAGE(
tf1 << 
'\n' 
  144   BOOST_WARN_SMALL((resA.
normal - resA.
normal).squaredNorm(), tol);
 
  168   for (
int i = 0; i < 1000; ++i) {
 
  175 #ifdef COAL_HAS_QHULL 
  177   std::shared_ptr<std::vector<Vec3s>> points(
 
  178       new std::vector<Vec3s>({
Vec3s(1, 1, 1), 
Vec3s(0, 0, 0), 
Vec3s(1, 0, 0)}));
 
  181                     std::invalid_argument);
 
  183                     std::invalid_argument);
 
  185                     std::invalid_argument);
 
  187                     std::invalid_argument);
 
  191   std::shared_ptr<std::vector<Vec3s>> points(
new std::vector<Vec3s>({
 
  200   BOOST_REQUIRE_EQUAL(convexHull->
num_points, 4);
 
  201   BOOST_CHECK_EQUAL((*(convexHull->
neighbors))[0].count(), 3);
 
  202   BOOST_CHECK_EQUAL((*(convexHull->
neighbors))[1].count(), 3);
 
  203   BOOST_CHECK_EQUAL((*(convexHull->
neighbors))[2].count(), 3);
 
  208   std::shared_ptr<std::vector<Vec3s>> points(
new std::vector<Vec3s>({
 
  223   BOOST_REQUIRE_EQUAL(8, convexHull->
num_points);
 
  225     const std::vector<Vec3s>& cvxhull_points = *(convexHull->
points);
 
  226     for (
size_t i = 0; i < 8; ++i) {
 
  227       BOOST_CHECK(cvxhull_points[i].cwiseAbs() == 
Vec3s(1, 1, 1));
 
  228       BOOST_CHECK_EQUAL((*(convexHull->
neighbors))[i].count(), 3);
 
  235   BOOST_CHECK(convex_tri != NULL);
 
  237   BOOST_REQUIRE_EQUAL(8, convexHull->
num_points);
 
  239     const std::vector<Vec3s>& cvxhull_points = *(convexHull->
points);
 
  240     for (
size_t i = 0; i < 8; ++i) {
 
  241       BOOST_CHECK(cvxhull_points[i].cwiseAbs() == 
Vec3s(1, 1, 1));
 
  242       BOOST_CHECK((*(convexHull->
neighbors))[i].count() >= 3);
 
  243       BOOST_CHECK((*(convexHull->
neighbors))[i].count() <= 6);
 
  252     std::shared_ptr<std::vector<Vec3s>> points(
new std::vector<Vec3s>({
 
  267     BOOST_CHECK(*convexHullTri == *convexHullTriCopy);
 
  271   BOOST_CHECK(*convexHullTriCopyOfCopy == *convexHullTriCopy);
 
  275   std::shared_ptr<std::vector<Vec3s>> points(
new std::vector<Vec3s>({
 
  290   convexHullTriCopy = convexHullTri->
clone();
 
  291   BOOST_CHECK(*convexHullTri == *convexHullTriCopy);
 
  
Eigen::Matrix< CoalScalar, 3, 1 > Vec3s
void generateRandomTransform(CoalScalar extents[6], Transform3s &transform)
Generate one random transform whose translation is constrained by extents and rotation without constr...
std::shared_ptr< std::vector< Neighbors > > neighbors
Neighbors of each vertex. It is an array of size num_points. For each vertex, it contains the number ...
bool isCollision() const
return binary collision result
Convex< Quadrilateral > buildBox(CoalScalar l, CoalScalar w, CoalScalar d)
Constructs a box with halfsides (l, w, d), centered around 0. The box is 2*l wide on the x-axis,...
COAL_DLLAPI CoalScalar 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.
virtual Convex< PolygonT > * clone() const
Clone (deep copy)
CoalScalar distance_lower_bound
Center at zero point, axis aligned box.
CoalScalar min_distance
minimum distance between two objects. If two objects are in collision and DistanceRequest::enable_sig...
request to the distance computation
static ConvexBase * convexHull(std::shared_ptr< std::vector< Vec3s >> &points, unsigned int num_points, bool keepTriangles, const char *qhullCommand=NULL)
Build a convex hull based on Qhull library and store the vertices and optionally the triangles.
request to the collision algorithm
BOOST_AUTO_TEST_CASE(convex)
const Eigen::IOFormat pyfmt
void compareShapeDistance(const Sa &sa, const Sb &sb, const Transform3s &tf1, const Transform3s &tf2, CoalScalar tol=1e-9)
const Contact & getContact(size_t i) const
get the i-th contact calculated
COAL_DLLAPI std::size_t collide(const CollisionObject *o1, const CollisionObject *o2, const CollisionRequest &request, CollisionResult &result)
Main collision interface: given two collision objects, and the requirements for contacts,...
std::shared_ptr< std::vector< Vec3s > > points
An array of the points of the polygon.
void compareShapeIntersection(const Sa &sa, const Sb &sb, const Transform3s &tf1, const Transform3s &tf2, CoalScalar tol=1e-9)
std::array< Vec3s, 2 > nearest_points
nearest points. See CollisionResult::nearest_points.
Base for convex polytope.
size_t numContacts() const
number of contacts found
hpp-fcl
Author(s): 
autogenerated on Fri Feb 14 2025 03:45:50