Classes | Namespaces | Macros | Typedefs | Functions
utility.h File Reference
#include "coal/math/transform.h"
#include "coal/collision_data.h"
#include "coal/collision_object.h"
#include "coal/broadphase/default_broadphase_callbacks.h"
#include "coal/shape/convex.h"
#include <sys/time.h>
Include dependency graph for utility.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  coal::BenchTimer
 
struct  coal::DistanceRes
 
struct  coal::TStruct
 

Namespaces

 coal
 Main namespace.
 
 octomap
 

Macros

#define CoalScalar_IS_APPROX(Va, Vb, precision)
 
#define EIGEN_MATRIX_IS_APPROX(Va, Vb, precision)
 
#define EIGEN_VECTOR_IS_APPROX(Va, Vb, precision)
 

Typedefs

typedef Eigen::AngleAxis< CoalScalar > coal::AngleAxis
 

Functions

Convex< Quadrilateral > coal::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, 2*w wide on the y-axis and 2*d wide on the z-axis. More...
 
Convex< Triangle > coal::constructPolytopeFromEllipsoid (const Ellipsoid &ellipsoid)
 We give an ellipsoid as input. The output is a 20 faces polytope which vertices belong to the original ellipsoid surface. The procedure is simple: we construct a icosahedron, see https://sinestesia.co/blog/tutorials/python-icospheres/ . We then apply an ellipsoid tranformation to each vertex of the icosahedron. More...
 
bool coal::defaultCollisionFunction (CollisionObject *o1, CollisionObject *o2, void *data)
 Provides a simple callback for the collision query in the BroadPhaseCollisionManager. It assumes the data parameter is non-null and points to an instance of CollisionData. It simply invokes the collide() method on the culled pair of geometries and stores the results in the data's CollisionResult instance. More...
 
bool coal::defaultDistanceFunction (CollisionObject *o1, CollisionObject *o2, void *data, CoalScalar &dist)
 Collision data for use with the DefaultContinuousCollisionFunction. It stores the collision request and the result given by the collision algorithm (and stores the conclusion of whether further evaluation of the broadphase collision manager has been deemed unnecessary). More...
 
void coal::generateEnvironments (std::vector< CollisionObject * > &env, CoalScalar env_scale, std::size_t n)
 
void coal::generateEnvironmentsMesh (std::vector< CollisionObject * > &env, CoalScalar env_scale, std::size_t n)
 
void coal::generateRandomTransform (CoalScalar extents[6], Transform3s &transform)
 Generate one random transform whose translation is constrained by extents and rotation without constraints. The translation is (x, y, z), and extents[0] <= x <= extents[3], extents[1] <= y <= extents[4], extents[2] <= z <= extents[5]. More...
 
void coal::generateRandomTransforms (CoalScalar extents[6], CoalScalar delta_trans[3], CoalScalar delta_rot, std::vector< Transform3s > &transforms, std::vector< Transform3s > &transforms2, std::size_t n)
 Generate n random transforms whose translations are constrained by extents. Also generate another transforms2 which have additional random translation & rotation to the transforms generated. More...
 
void coal::generateRandomTransforms (CoalScalar extents[6], std::vector< Transform3s > &transforms, std::size_t n)
 Generate n random transforms whose translations are constrained by extents. More...
 
std::size_t coal::getNbRun (const int &argc, char const *const *argv, std::size_t defaultValue)
 Get the argument –nb-run from argv. More...
 
std::string coal::getNodeTypeName (NODE_TYPE node_type)
 
void coal::loadOBJFile (const char *filename, std::vector< Vec3s > &points, std::vector< Triangle > &triangles)
 Load an obj mesh file. More...
 
Quatf coal::makeQuat (CoalScalar w, CoalScalar x, CoalScalar y, CoalScalar z)
 
Box coal::makeRandomBox (CoalScalar min_size, CoalScalar max_size)
 
Capsule coal::makeRandomCapsule (std::array< CoalScalar, 2 > min_size, std::array< CoalScalar, 2 > max_size)
 
Cone coal::makeRandomCone (std::array< CoalScalar, 2 > min_size, std::array< CoalScalar, 2 > max_size)
 
Convex< Triangle > coal::makeRandomConvex (CoalScalar min_size, CoalScalar max_size)
 
Cylinder coal::makeRandomCylinder (std::array< CoalScalar, 2 > min_size, std::array< CoalScalar, 2 > max_size)
 
Ellipsoid coal::makeRandomEllipsoid (CoalScalar min_size, CoalScalar max_size)
 
std::shared_ptr< ShapeBase > coal::makeRandomGeometry (NODE_TYPE node_type)
 
Halfspace coal::makeRandomHalfspace (CoalScalar min_size, CoalScalar max_size)
 
Plane coal::makeRandomPlane (CoalScalar min_size, CoalScalar max_size)
 
Sphere coal::makeRandomSphere (CoalScalar min_size, CoalScalar max_size)
 
std::ostream & coal::operator<< (std::ostream &os, const Transform3s &tf)
 
void coal::saveOBJFile (const char *filename, std::vector< Vec3s > &points, std::vector< Triangle > &triangles)
 

Macro Definition Documentation

◆ CoalScalar_IS_APPROX

#define CoalScalar_IS_APPROX (   Va,
  Vb,
  precision 
)
Value:
BOOST_CHECK_MESSAGE(std::abs((Va) - (Vb)) < precision, \
"check " #Va ".isApprox(" #Vb ") failed at precision " \
<< precision << " [\n" \
<< Va << "\n!=\n" \
<< Vb << "\n]")

Definition at line 73 of file utility.h.

◆ EIGEN_MATRIX_IS_APPROX

#define EIGEN_MATRIX_IS_APPROX (   Va,
  Vb,
  precision 
)
Value:
BOOST_CHECK_MESSAGE(((Va) - (Vb)).isZero(precision), \
"check " #Va ".isApprox(" #Vb ") failed at precision " \
<< precision << " [\n" \
<< (Va) << "\n!=\n" \
<< (Vb) << "\n]")

Definition at line 66 of file utility.h.

◆ EIGEN_VECTOR_IS_APPROX

#define EIGEN_VECTOR_IS_APPROX (   Va,
  Vb,
  precision 
)
Value:
BOOST_CHECK_MESSAGE(((Va) - (Vb)).isZero(precision), \
"check " #Va ".isApprox(" #Vb ") failed at precision " \
<< precision << " [\n" \
<< (Va).transpose() << "\n!=\n" \
<< (Vb).transpose() << "\n]")
Author
Jia Pan

Definition at line 59 of file utility.h.



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