Go to the documentation of this file.
   38 #ifndef TEST_COAL_UTILITY_H 
   39 #define TEST_COAL_UTILITY_H 
   47 #ifdef COAL_HAS_OCTOMAP 
   57 #define EIGEN_VECTOR_IS_APPROX(Va, Vb, precision)                            \ 
   58   BOOST_CHECK_MESSAGE(((Va) - (Vb)).isZero(precision),                       \ 
   59                       "check " #Va ".isApprox(" #Vb ") failed at precision " \ 
   60                           << precision << " [\n"                             \ 
   61                           << (Va).transpose() << "\n!=\n"                    \ 
   62                           << (Vb).transpose() << "\n]") 
   64 #define EIGEN_MATRIX_IS_APPROX(Va, Vb, precision)                            \ 
   65   BOOST_CHECK_MESSAGE(((Va) - (Vb)).isZero(precision),                       \ 
   66                       "check " #Va ".isApprox(" #Vb ") failed at precision " \ 
   67                           << precision << " [\n"                             \ 
   71 #define CoalScalar_IS_APPROX(Va, Vb, precision)                              \ 
   72   BOOST_CHECK_MESSAGE(std::abs((Va) - (Vb)) < precision,                     \ 
   73                       "check " #Va ".isApprox(" #Vb ") failed at precision " \ 
   74                           << precision << " [\n"                             \ 
   79 #ifdef COAL_HAS_OCTOMAP 
   80 typedef coal::shared_ptr<octomap::OcTree> 
OcTreePtr_t;
 
  103   LARGE_INTEGER frequency;  
 
  124 extern const Eigen::IOFormat 
vfmt;
 
  125 extern const Eigen::IOFormat 
pyfmt;
 
  133                  std::vector<Triangle>& triangles);
 
  136                  std::vector<Triangle>& triangles);
 
  138 #ifdef COAL_HAS_OCTOMAP 
  152                               std::vector<Transform3s>& transforms,
 
  160                               std::vector<Transform3s>& transforms,
 
  161                               std::vector<Transform3s>& transforms2,
 
  190 std::size_t 
getNbRun(
const int& argc, 
char const* 
const* argv,
 
  191                      std::size_t defaultValue);
 
  218                           std::array<CoalScalar, 2> max_size);
 
  221                     std::array<CoalScalar, 2> max_size);
 
  224                             std::array<CoalScalar, 2> max_size);
 
  
std::shared_ptr< ShapeBase > makeRandomGeometry(NODE_TYPE node_type)
const Eigen::IOFormat vfmt
std::vector< double > records
double getElapsedTime()
get elapsed time in milli-second
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...
Cone makeRandomCone(std::array< CoalScalar, 2 > min_size, std::array< CoalScalar, 2 > max_size)
double startTimeInMicroSec
starting time in micro-second
void stop()
stop the timer
Half Space: this is equivalent to the Plane in ODE. A Half space has a priviledged direction: the dir...
Convex< Triangle > makeRandomConvex(CoalScalar min_size, CoalScalar max_size)
void generateEnvironments(std::vector< CollisionObject * > &env, CoalScalar env_scale, std::size_t n)
void generateEnvironmentsMesh(std::vector< CollisionObject * > &env, CoalScalar env_scale, std::size_t n)
Halfspace makeRandomHalfspace(CoalScalar min_size, CoalScalar max_size)
NODE_TYPE
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18,...
Capsule It is  where  is the distance between the point x and the capsule segment AB,...
std::string getNodeTypeName(NODE_TYPE node_type)
Eigen::AngleAxis< CoalScalar > AngleAxis
Eigen::Quaternion< CoalScalar > Quatf
Sphere makeRandomSphere(CoalScalar min_size, CoalScalar max_size)
Box makeRandomBox(CoalScalar min_size, CoalScalar max_size)
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,...
Ellipsoid centered at point zero.
double getElapsedTimeInMilliSec()
get elapsed time in milli-second
double endTimeInMicroSec
ending time in micro-second
Infinite plane. A plane can be viewed as two half spaces; it has no priviledged direction....
Center at zero point, axis aligned box.
Convex< Triangle > constructPolytopeFromEllipsoid(const Ellipsoid &ellipsoid)
We give an ellipsoid as input. The output is a 20 faces polytope which vertices belong to the origina...
Center at zero point sphere.
static std::ostream & operator<<(std::ostream &o, const Quatf &q)
bool defaultCollisionFunction(CollisionObject *o1, CollisionObject *o2, void *data)
Provides a simple callback for the collision query in the BroadPhaseCollisionManager....
COAL_DLLAPI Halfspace transform(const Halfspace &a, const Transform3s &tf)
Plane makeRandomPlane(CoalScalar min_size, CoalScalar max_size)
the object for collision or distance computation, contains the geometry and the transform information
Cylinder along Z axis. The cylinder is defined at its centroid.
void generateRandomTransforms(CoalScalar extents[6], std::vector< Transform3s > &transforms, std::size_t n)
Generate n random transforms whose translations are constrained by extents.
shared_ptr< OcTree > OcTreePtr_t
bool defaultDistanceFunction(CollisionObject *o1, CollisionObject *o2, void *data, CoalScalar &dist)
Collision data for use with the DefaultContinuousCollisionFunction. It stores the collision request a...
Cone The base of the cone is at  and the top is at .
const Eigen::IOFormat pyfmt
Quatf makeQuat(CoalScalar w, CoalScalar x, CoalScalar y, CoalScalar z)
Octree is one type of collision geometry which can encode uncertainty information in the sensor data.
void saveOBJFile(const char *filename, std::vector< Vec3s > &points, std::vector< Triangle > &triangles)
double getElapsedTimeInSec()
Ellipsoid makeRandomEllipsoid(CoalScalar min_size, CoalScalar max_size)
std::size_t getNbRun(const int &argc, char const *const *argv, std::size_t defaultValue)
Get the argument –nb-run from argv.
double getElapsedTimeInMicroSec()
get elapsed time in micro-second
Cylinder makeRandomCylinder(std::array< CoalScalar, 2 > min_size, std::array< CoalScalar, 2 > max_size)
Capsule makeRandomCapsule(std::array< CoalScalar, 2 > min_size, std::array< CoalScalar, 2 > max_size)
void loadOBJFile(const char *filename, std::vector< Vec3s > &points, std::vector< Triangle > &triangles)
Load an obj mesh file.
hpp-fcl
Author(s): 
autogenerated on Fri Feb 14 2025 03:45:51