Main namespace. More...
Namespaces | |
detail | |
details | |
internal | |
kIOS_fit_functions | |
OBB_fit_functions | |
OBBRSS_fit_functions | |
python | |
RSS_fit_functions | |
serialization | |
viewer | |
windows_dll_manager | |
Classes | |
class | AABB |
A class describing the AABB collision structure, which is a box in 3D space determined by two diagonal points. More... | |
class | BenchTimer |
class | Box |
Center at zero point, axis aligned box. More... | |
class | BroadPhaseCollisionManager |
Base class for broad phase collision. It helps to accelerate the collision/distance between N objects. Also support self collision, self distance and collision/distance with another M objects. More... | |
struct | BroadPhaseCollisionManagerWrapper |
class | BroadPhaseContinuousCollisionManager |
Base class for broad phase continuous collision. It helps to accelerate the continuous collision/distance between N objects. Also support self collision, self distance and collision/distance with another M objects. More... | |
class | BVFitter |
The class for the default algorithm fitting a bounding volume to a set of points. More... | |
class | BVFitter< AABB > |
Specification of BVFitter for AABB bounding volume. More... | |
class | BVFitter< kIOS > |
Specification of BVFitter for kIOS bounding volume. More... | |
class | BVFitter< OBB > |
Specification of BVFitter for OBB bounding volume. More... | |
class | BVFitter< OBBRSS > |
Specification of BVFitter for OBBRSS bounding volume. More... | |
class | BVFitter< RSS > |
Specification of BVFitter for RSS bounding volume. More... | |
class | BVFitterTpl |
The class for the default algorithm fitting a bounding volume to a set of points. More... | |
struct | BVHComputeContactPatch |
struct | BVHFrontNode |
Front list acceleration for collision Front list is a set of internal and leaf nodes in the BVTT hierarchy, where the traversal terminates while performing a query during a given time instance. The front list reflects the subset of a BVTT that is traversed for that particular proximity query. More... | |
class | BVHModel |
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as a degraded version of mesh) More... | |
class | BVHModelBase |
A base class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as a degraded version of mesh) More... | |
struct | BVHShapeCollider |
struct | BVHShapeComputeContactPatch |
struct | BVHShapeDistancer |
struct | BVHShapeDistancer< kIOS, T_SH > |
struct | BVHShapeDistancer< OBBRSS, T_SH > |
struct | BVHShapeDistancer< RSS, T_SH > |
struct | BVNode |
A class describing a bounding volume node. It includes the tree structure providing in BVNodeBase and also the geometry data provided in BV template parameter. More... | |
struct | BVNodeBase |
BVNodeBase encodes the tree structure for BVH. More... | |
class | BVSplitter |
A class describing the split rule that splits each BV node. More... | |
struct | BVT |
Bounding volume test structure. More... | |
struct | BVT_Comparer |
Comparer between two BVT. More... | |
struct | BVTQ |
class | CachedMeshLoader |
class | Capsule |
Capsule It is where is the distance between the point x and the capsule segment AB, with . More... | |
struct | CollisionCallBackBase |
Base callback class for collision queries. This class can be supersed by child classes to provide desired behaviors according to the application (e.g, only listing the potential CollisionObjects in collision). More... | |
struct | CollisionCallBackBaseWrapper |
struct | CollisionCallBackCollect |
Collision callback to collect collision pairs potentially in contacts. More... | |
struct | CollisionCallBackDefault |
Default collision callback to check collision between collision objects. More... | |
struct | CollisionData |
Collision data stores the collision request and the result given by collision algorithm. More... | |
struct | CollisionFunctionMatrix |
collision matrix stores the functions for collision between different types of objects and provides a uniform call interface More... | |
class | CollisionGeometry |
The geometry for the object for collision or distance computation. More... | |
class | CollisionObject |
the object for collision or distance computation, contains the geometry and the transform information More... | |
struct | CollisionRequest |
request to the collision algorithm More... | |
struct | CollisionResult |
collision result More... | |
class | ComputeCollision |
This class reduces the cost of identifying the geometry pair. This is mostly useful for repeated shape-shape queries. More... | |
class | ComputeContactPatch |
This class reduces the cost of identifying the geometry pair. This is usefull for repeated shape-shape queries. More... | |
class | ComputeDistance |
struct | ComputeShapeShapeContactPatch |
Shape-shape contact patch computation. Assumes that csolver and the ContactPatchResult have already been set up by the ContactPatchRequest . More... | |
class | Cone |
Cone The base of the cone is at and the top is at . More... | |
struct | Contact |
Contact information returned by collision. More... | |
struct | ContactPatch |
This structure allows to encode contact patches. A contact patch is defined by a set of points belonging to a subset of a plane passing by p and supported by n , where n = Contact::normal and p = Contact::pos . If we denote by P this plane and by S1 and S2 the first and second shape of a collision pair, a contact patch is represented as a polytope which vertices all belong to P & S1 & S2 , where & denotes the set-intersection. Since a contact patch is a subset of a plane supported by n , it has a preferred direction. In Coal, the Contact::normal points from S1 to S2. In the same way, a contact patch points by default from S1 to S2. More... | |
struct | ContactPatchFunctionMatrix |
The contact patch matrix stores the functions for contact patches computation between different types of objects and provides a uniform call interface. More... | |
struct | ContactPatchRequest |
Request for a contact patch computation. More... | |
struct | ContactPatchResult |
Result for a contact patch computation. More... | |
struct | ContactPatchSolver |
Solver to compute contact patches, i.e. the intersection between two contact surfaces projected onto the shapes' separating plane. Otherwise said, a contact patch is simply the intersection between two support sets: the support set of shape S1 in direction n and the support set of shape S2 in direction -n , where n is the contact normal (satisfying the optimality conditions of GJK/EPA). More... | |
class | Convex |
Convex polytope. More... | |
class | ConvexBase |
Base for convex polytope. More... | |
struct | CPUTimes |
class | Cylinder |
Cylinder along Z axis. The cylinder is defined at its centroid. More... | |
struct | DistanceCallBackBase |
Base callback class for distance queries. This class can be supersed by child classes to provide desired behaviors according to the application (e.g, only listing the potential CollisionObjects in collision). More... | |
struct | DistanceCallBackBaseWrapper |
struct | DistanceCallBackDefault |
Default distance callback to check collision between collision objects. More... | |
struct | DistanceData |
Distance data stores the distance request and the result given by distance algorithm. More... | |
struct | DistanceFunctionMatrix |
distance matrix stores the functions for distance between different types of objects and provides a uniform call interface More... | |
struct | DistanceRequest |
request to the distance computation More... | |
struct | DistanceRes |
struct | DistanceResult |
distance result More... | |
class | DummyCollisionObject |
Dummy collision object with a point AABB. More... | |
class | DynamicAABBTreeArrayCollisionManager |
class | DynamicAABBTreeCollisionManager |
class | Ellipsoid |
Ellipsoid centered at point zero. More... | |
struct | GJKSolver |
collision and distance solver based on the GJK and EPA algorithms. Originally, GJK and EPA were implemented in fcl which itself took inspiration from the code of the GJK in bullet. Since then, both GJK and EPA have been largely modified to be faster and more robust to numerical accuracy and edge cases. More... | |
class | Halfspace |
Half Space: this is equivalent to the Plane in ODE. A Half space has a priviledged direction: the direction of the normal. The separation plane is defined as n * x = d; Points in the negative side of the separation plane (i.e. {x | n * x < d}) are inside the half space and points in the positive side of the separation plane (i.e. {x | n * x > d}) are outside the half space. Note: prefer using a Halfspace instead of a Plane if possible, it has better behavior w.r.t. collision detection algorithms. More... | |
class | HeightField |
Data structure depicting a height field given by the base grid dimensions and the elevation along the grid. More... | |
struct | HeightFieldShapeCollider |
Collider functor for HeightField data structure. More... | |
struct | HeightFieldShapeComputeContactPatch |
struct | HeightFieldShapeDistancer |
struct | HFNode |
struct | HFNodeBase |
class | IntervalTreeCollisionManager |
Collision manager based on interval tree. More... | |
class | KDOP |
KDOP class describes the KDOP collision structures. K is set as the template parameter, which should be 16, 18, or 24 The KDOP structure is defined by some pairs of parallel planes defined by some axes. For K = 16, the planes are 6 AABB planes and 10 diagonal planes that cut off some space of the edges: (-1,0,0) and (1,0,0) -> indices 0 and 8 (0,-1,0) and (0,1,0) -> indices 1 and 9 (0,0,-1) and (0,0,1) -> indices 2 and 10 (-1,-1,0) and (1,1,0) -> indices 3 and 11 (-1,0,-1) and (1,0,1) -> indices 4 and 12 (0,-1,-1) and (0,1,1) -> indices 5 and 13 (-1,1,0) and (1,-1,0) -> indices 6 and 14 (-1,0,1) and (1,0,-1) -> indices 7 and 15 For K = 18, the planes are 6 AABB planes and 12 diagonal planes that cut off some space of the edges: (-1,0,0) and (1,0,0) -> indices 0 and 9 (0,-1,0) and (0,1,0) -> indices 1 and 10 (0,0,-1) and (0,0,1) -> indices 2 and 11 (-1,-1,0) and (1,1,0) -> indices 3 and 12 (-1,0,-1) and (1,0,1) -> indices 4 and 13 (0,-1,-1) and (0,1,1) -> indices 5 and 14 (-1,1,0) and (1,-1,0) -> indices 6 and 15 (-1,0,1) and (1,0,-1) -> indices 7 and 16 (0,-1,1) and (0,1,-1) -> indices 8 and 17 For K = 18, the planes are 6 AABB planes and 18 diagonal planes that cut off some space of the edges: (-1,0,0) and (1,0,0) -> indices 0 and 12 (0,-1,0) and (0,1,0) -> indices 1 and 13 (0,0,-1) and (0,0,1) -> indices 2 and 14 (-1,-1,0) and (1,1,0) -> indices 3 and 15 (-1,0,-1) and (1,0,1) -> indices 4 and 16 (0,-1,-1) and (0,1,1) -> indices 5 and 17 (-1,1,0) and (1,-1,0) -> indices 6 and 18 (-1,0,1) and (1,0,-1) -> indices 7 and 19 (0,-1,1) and (0,1,-1) -> indices 8 and 20 (-1, -1, 1) and (1, 1, -1) --> indices 9 and 21 (-1, 1, -1) and (1, -1, 1) --> indices 10 and 22 (1, -1, -1) and (-1, 1, 1) --> indices 11 and 23. More... | |
class | kIOS |
A class describing the kIOS collision structure, which is a set of spheres. More... | |
class | MeshLoader |
class | NaiveCollisionManager |
Brute force N-body collision manager. More... | |
struct | OBB |
Oriented bounding box class. More... | |
struct | OBBRSS |
Class merging the OBB and RSS, can handle collision and distance simultaneously. More... | |
class | OcTree |
Octree is one type of collision geometry which can encode uncertainty information in the sensor data. More... | |
class | Plane |
Infinite plane. A plane can be viewed as two half spaces; it has no priviledged direction. Note: prefer using a Halfspace instead of a Plane if possible, it has better behavior w.r.t. collision detection algorithms. More... | |
struct | Quadrilateral |
Quadrilateral with 4 indices for points. More... | |
struct | QueryRequest |
base class for all query requests More... | |
struct | QueryResult |
base class for all query results More... | |
struct | RSS |
A class for rectangle sphere-swept bounding volume. More... | |
class | SaPCollisionManager |
Rigorous SAP collision manager. More... | |
struct | shape_traits |
struct | shape_traits< Box > |
struct | shape_traits< Capsule > |
struct | shape_traits< Cone > |
struct | shape_traits< ConvexBase > |
struct | shape_traits< Cylinder > |
struct | shape_traits< Ellipsoid > |
struct | shape_traits< Halfspace > |
struct | shape_traits< Sphere > |
struct | shape_traits< TriangleP > |
struct | shape_traits_base |
class | ShapeBase |
Base class for all basic geometric shapes. More... | |
struct | SortByXLow |
Functor sorting objects according to the AABB lower x bound. More... | |
struct | SortByYLow |
Functor sorting objects according to the AABB lower y bound. More... | |
struct | SortByZLow |
Functor sorting objects according to the AABB lower z bound. More... | |
class | SpatialHashingCollisionManager |
spatial hashing collision mananger More... | |
class | Sphere |
Center at zero point sphere. More... | |
class | SSaPCollisionManager |
Simple SAP collision manager. More... | |
struct | Timer |
This class mimics the way "boost/timer/timer.hpp" operates while using the modern std::chrono library. Importantly, this class will only have an effect for C++11 and more. More... | |
class | Transform3s |
Simple transform class used locally by InterpMotion. More... | |
struct | TraversalTraitsCollision |
struct | TraversalTraitsDistance |
class | Triangle |
Triangle with 3 indices for points. More... | |
class | TriangleP |
Triangle stores the points instead of only indices of points. More... | |
struct | TStruct |
Typedefs | |
typedef Eigen::AngleAxis< CoalScalar > | AngleAxis |
using | BroadPhaseContinuousCollisionManagerd = BroadPhaseContinuousCollisionManager< CoalScalar > |
using | BroadPhaseContinuousCollisionManagerf = BroadPhaseContinuousCollisionManager< float > |
typedef std::list< BVHFrontNode > | BVHFrontList |
BVH front list is a list of front nodes. More... | |
typedef shared_ptr< BVHModelBase > | BVHModelPtr_t |
typedef double | CoalScalar |
typedef shared_ptr< const CollisionGeometry > | CollisionGeometryConstPtr_t |
typedef shared_ptr< CollisionGeometry > | CollisionGeometryPtr_t |
typedef shared_ptr< const CollisionObject > | CollisionObjectConstPtr_t |
typedef shared_ptr< CollisionObject > | CollisionObjectPtr_t |
template<typename S > | |
using | ContinuousCollisionCallBack = bool(*)(ContinuousCollisionObject *o1, ContinuousCollisionObject *o2, void *cdata) |
Callback for continuous collision between two objects. Return value is whether can stop now. More... | |
template<typename S > | |
using | ContinuousDistanceCallBack = bool(*)(ContinuousCollisionObject *o1, ContinuousCollisionObject *o2, S &dist) |
Callback for continuous distance between two objects, Return value is whether can stop now, also return the minimum distance till now. More... | |
typedef Eigen::Matrix< CoalScalar, 3, 3 > | Matrix3s |
typedef Eigen::Matrix< CoalScalar, Eigen::Dynamic, 2, Eigen::RowMajor > | MatrixX2s |
typedef Eigen::Matrix< Eigen::DenseIndex, Eigen::Dynamic, 3, Eigen::RowMajor > | Matrixx3i |
typedef Eigen::Matrix< CoalScalar, Eigen::Dynamic, 3, Eigen::RowMajor > | MatrixX3s |
typedef Eigen::Matrix< CoalScalar, Eigen::Dynamic, Eigen::Dynamic > | MatrixXs |
typedef shared_ptr< const OcTree > | OcTreeConstPtr_t |
typedef shared_ptr< OcTree > | OcTreePtr_t |
typedef Eigen::Quaternion< CoalScalar > | Quatf |
typedef Eigen::Vector2i | support_func_guess_t |
using | SupportSet = ContactPatch |
Structure used for internal computations. A support set and a contact patch can be represented by the same structure. In fact, a contact patch is the intersection of two support sets, one with PatchDirection::DEFAULT and one with PatchDirection::INVERTED . More... | |
typedef Eigen::Matrix< CoalScalar, 2, 1 > | Vec2s |
typedef Eigen::Matrix< CoalScalar, 3, 1 > | Vec3s |
typedef Eigen::Matrix< CoalScalar, 6, 1 > | Vec6s |
typedef Eigen::Matrix< CoalScalar, Eigen::Dynamic, 1 > | VecXs |
Enumerations | |
enum | BVHBuildState { BVH_BUILD_STATE_EMPTY, BVH_BUILD_STATE_BEGUN, BVH_BUILD_STATE_PROCESSED, BVH_BUILD_STATE_UPDATE_BEGUN, BVH_BUILD_STATE_UPDATED, BVH_BUILD_STATE_REPLACE_BEGUN } |
States for BVH construction empty->begun->processed ->replace_begun->processed -> ...... | |-> update_begun -> updated -> ..... More... | |
enum | BVHModelType { BVH_MODEL_UNKNOWN, BVH_MODEL_TRIANGLES, BVH_MODEL_POINTCLOUD } |
BVH model type. More... | |
enum | BVHReturnCode { BVH_OK = 0, BVH_ERR_MODEL_OUT_OF_MEMORY, BVH_ERR_BUILD_OUT_OF_SEQUENCE, BVH_ERR_BUILD_EMPTY_MODEL = -3, BVH_ERR_BUILD_EMPTY_PREVIOUS_FRAME, BVH_ERR_UNSUPPORTED_FUNCTION = -5, BVH_ERR_UNUPDATED_MODEL = -6, BVH_ERR_INCORRECT_DATA = -7, BVH_ERR_UNKNOWN = -8 } |
Error code for BVH. More... | |
enum | CollisionRequestFlag { CONTACT = 0x00001, DISTANCE_LOWER_BOUND = 0x00002, NO_REQUEST = 0x01000 } |
flag declaration for specifying required params in CollisionResult More... | |
enum | GJKConvergenceCriterion { Default, DualityGap, Hybrid } |
Which convergence criterion is used to stop the algorithm (when the shapes are not in collision). (default) VDB: Van den Bergen (A Fast and Robust GJK Implementation, 1999) DG: duality-gap, as used in the Frank-Wolfe and the vanilla 1988 GJK algorithms Hybrid: a mix between VDB and DG. More... | |
enum | GJKConvergenceCriterionType { Relative, Absolute } |
Wether the convergence criterion is scaled on the norm of the solution or not. More... | |
enum | GJKInitialGuess { DefaultGuess, CachedGuess, BoundingVolumeGuess } |
Initial guess to use for the GJK algorithm DefaultGuess: Vec3s(1, 0, 0) CachedGuess: previous vector found by GJK or guess cached by the user BoundingVolumeGuess: guess using the centers of the shapes' AABB WARNING: to use BoundingVolumeGuess, computeLocalAABB must have been called on the two shapes. More... | |
enum | GJKVariant { DefaultGJK, PolyakAcceleration, NesterovAcceleration } |
Variant to use for the GJK algorithm. More... | |
enum | NODE_TYPE { BV_UNKNOWN, BV_AABB, BV_OBB, BV_RSS, BV_kIOS, BV_OBBRSS, BV_KDOP16, BV_KDOP18, BV_KDOP24, GEOM_BOX, GEOM_SPHERE, GEOM_CAPSULE, GEOM_CONE, GEOM_CYLINDER, GEOM_CONVEX, GEOM_PLANE, GEOM_HALFSPACE, GEOM_TRIANGLE, GEOM_OCTREE, GEOM_ELLIPSOID, HF_AABB, HF_OBBRSS, NODE_COUNT } |
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18, kDOP24), basic shape (box, sphere, ellipsoid, capsule, cone, cylinder, convex, plane, triangle), and octree More... | |
enum | OBJECT_TYPE { OT_UNKNOWN, OT_BVH, OT_GEOM, OT_OCTREE, OT_HFIELD, OT_COUNT } |
object type: BVH (mesh, points), basic geometry, octree More... | |
enum | SplitMethodType { SPLIT_METHOD_MEAN, SPLIT_METHOD_MEDIAN, SPLIT_METHOD_BV_CENTER } |
Three types of split algorithms are provided in FCL as default. More... | |
Functions | |
template<typename BV > | |
BVHModelPtr_t | _load (const std::string &filename, const Vec3s &scale) |
static void | axisFromEigen (Vec3s eigenV[3], CoalScalar eigenS[3], Matrix3s &axes) |
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, 2*w wide on the y-axis and 2*d wide on the z-axis. More... | |
template<typename T_BVH > | |
std::size_t | BVHCollide (const CollisionGeometry *o1, const Transform3s &tf1, const CollisionGeometry *o2, const Transform3s &tf2, const CollisionRequest &request, CollisionResult &result) |
template<typename T_BVH > | |
std::size_t | BVHCollide (const CollisionGeometry *o1, const Transform3s &tf1, const CollisionGeometry *o2, const Transform3s &tf2, const GJKSolver *, const CollisionRequest &request, CollisionResult &result) |
template<> | |
std::size_t | BVHCollide< kIOS > (const CollisionGeometry *o1, const Transform3s &tf1, const CollisionGeometry *o2, const Transform3s &tf2, const CollisionRequest &request, CollisionResult &result) |
template<> | |
std::size_t | BVHCollide< OBB > (const CollisionGeometry *o1, const Transform3s &tf1, const CollisionGeometry *o2, const Transform3s &tf2, const CollisionRequest &request, CollisionResult &result) |
template<> | |
std::size_t | BVHCollide< OBBRSS > (const CollisionGeometry *o1, const Transform3s &tf1, const CollisionGeometry *o2, const Transform3s &tf2, const CollisionRequest &request, CollisionResult &result) |
template<typename T_BVH > | |
CoalScalar | BVHDistance (const CollisionGeometry *o1, const Transform3s &tf1, const CollisionGeometry *o2, const Transform3s &tf2, const DistanceRequest &request, DistanceResult &result) |
template<typename T_BVH > | |
CoalScalar | BVHDistance (const CollisionGeometry *o1, const Transform3s &tf1, const CollisionGeometry *o2, const Transform3s &tf2, const GJKSolver *, const DistanceRequest &request, DistanceResult &result) |
template<> | |
CoalScalar | BVHDistance< kIOS > (const CollisionGeometry *o1, const Transform3s &tf1, const CollisionGeometry *o2, const Transform3s &tf2, const DistanceRequest &request, DistanceResult &result) |
template<> | |
CoalScalar | BVHDistance< OBBRSS > (const CollisionGeometry *o1, const Transform3s &tf1, const CollisionGeometry *o2, const Transform3s &tf2, const DistanceRequest &request, DistanceResult &result) |
template<> | |
CoalScalar | BVHDistance< RSS > (const CollisionGeometry *o1, const Transform3s &tf1, const CollisionGeometry *o2, const Transform3s &tf2, const DistanceRequest &request, DistanceResult &result) |
template<> | |
COAL_DLLAPI BVHModel< AABB > * | BVHExtract (const BVHModel< AABB > &model, const Transform3s &pose, const AABB &aabb) |
template<typename BV > | |
COAL_DLLAPI BVHModel< BV > * | BVHExtract (const BVHModel< BV > &model, const Transform3s &pose, const AABB &aabb) |
Extract the part of the BVHModel that is inside an AABB. A triangle in collision with the AABB is considered inside. More... | |
template<> | |
COAL_DLLAPI BVHModel< KDOP< 16 > > * | BVHExtract (const BVHModel< KDOP< 16 > > &model, const Transform3s &pose, const AABB &aabb) |
template<> | |
COAL_DLLAPI BVHModel< KDOP< 18 > > * | BVHExtract (const BVHModel< KDOP< 18 > > &model, const Transform3s &pose, const AABB &aabb) |
template<> | |
COAL_DLLAPI BVHModel< KDOP< 24 > > * | BVHExtract (const BVHModel< KDOP< 24 > > &model, const Transform3s &pose, const AABB &aabb) |
template<> | |
COAL_DLLAPI BVHModel< kIOS > * | BVHExtract (const BVHModel< kIOS > &model, const Transform3s &pose, const AABB &aabb) |
template<> | |
COAL_DLLAPI BVHModel< OBB > * | BVHExtract (const BVHModel< OBB > &model, const Transform3s &pose, const AABB &aabb) |
template<> | |
COAL_DLLAPI BVHModel< OBBRSS > * | BVHExtract (const BVHModel< OBBRSS > &model, const Transform3s &pose, const AABB &aabb) |
template<> | |
COAL_DLLAPI BVHModel< RSS > * | BVHExtract (const BVHModel< RSS > &model, const Transform3s &pose, const AABB &aabb) |
void | checkResultLowerBound (const CollisionResult &result, CoalScalar sqrDistLowerBound) |
COAL_DLLAPI void | circumCircleComputation (const Vec3s &a, const Vec3s &b, const Vec3s &c, Vec3s ¢er, CoalScalar &radius) |
Compute the center and radius for a triangle's circumcircle. More... | |
void | clipToRange (CoalScalar &val, CoalScalar a, CoalScalar b) |
Clip value between a and b. More... | |
void | collide (CollisionTraversalNodeBase *node, const CollisionRequest &request, CollisionResult &result, BVHFrontList *front_list, bool recursive) |
COAL_DLLAPI std::size_t | collide (const CollisionGeometry *o1, const Transform3s &tf1, const CollisionGeometry *o2, const Transform3s &tf2, const CollisionRequest &request, CollisionResult &result) |
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, including num of max contacts, whether perform exhaustive collision (i.e., returning returning all the contact points), whether return detailed contact information (i.e., normal, contact point, depth; otherwise only contact primitive id is returned), this function performs the collision between them. Return value is the number of contacts generated between the two objects. More... | |
void | collisionNonRecurse (CollisionTraversalNodeBase *node, BVHFrontList *front_list, CoalScalar &sqrDistLowerBound) |
void | collisionRecurse (CollisionTraversalNodeBase *node, unsigned int b1, unsigned int b2, BVHFrontList *front_list, CoalScalar &sqrDistLowerBound) |
template<typename BV , typename S > | |
void | computeBV (const S &s, const Transform3s &tf, BV &bv) |
calculate a bounding volume for a shape in a specific configuration More... | |
template<> | |
COAL_DLLAPI void | computeBV< AABB, Box > (const Box &s, const Transform3s &tf, AABB &bv) |
template<> | |
COAL_DLLAPI void | computeBV< AABB, Capsule > (const Capsule &s, const Transform3s &tf, AABB &bv) |
template<> | |
COAL_DLLAPI void | computeBV< AABB, Cone > (const Cone &s, const Transform3s &tf, AABB &bv) |
template<> | |
COAL_DLLAPI void | computeBV< AABB, ConvexBase > (const ConvexBase &s, const Transform3s &tf, AABB &bv) |
template<> | |
COAL_DLLAPI void | computeBV< AABB, Cylinder > (const Cylinder &s, const Transform3s &tf, AABB &bv) |
template<> | |
COAL_DLLAPI void | computeBV< AABB, Ellipsoid > (const Ellipsoid &e, const Transform3s &tf, AABB &bv) |
template<> | |
COAL_DLLAPI void | computeBV< AABB, Halfspace > (const Halfspace &s, const Transform3s &tf, AABB &bv) |
template<> | |
COAL_DLLAPI void | computeBV< AABB, Plane > (const Plane &s, const Transform3s &tf, AABB &bv) |
template<> | |
COAL_DLLAPI void | computeBV< AABB, Sphere > (const Sphere &s, const Transform3s &tf, AABB &bv) |
template<> | |
COAL_DLLAPI void | computeBV< AABB, TriangleP > (const TriangleP &s, const Transform3s &tf, AABB &bv) |
template<> | |
COAL_DLLAPI void | computeBV< KDOP< 16 >, Halfspace > (const Halfspace &s, const Transform3s &tf, KDOP< 16 > &bv) |
template<> | |
COAL_DLLAPI void | computeBV< KDOP< 16 >, Plane > (const Plane &s, const Transform3s &tf, KDOP< 16 > &bv) |
template<> | |
COAL_DLLAPI void | computeBV< KDOP< 18 >, Halfspace > (const Halfspace &s, const Transform3s &tf, KDOP< 18 > &bv) |
template<> | |
COAL_DLLAPI void | computeBV< KDOP< 18 >, Plane > (const Plane &s, const Transform3s &tf, KDOP< 18 > &bv) |
template<> | |
COAL_DLLAPI void | computeBV< KDOP< 24 >, Halfspace > (const Halfspace &s, const Transform3s &tf, KDOP< 24 > &bv) |
template<> | |
COAL_DLLAPI void | computeBV< KDOP< 24 >, Plane > (const Plane &s, const Transform3s &tf, KDOP< 24 > &bv) |
template<> | |
COAL_DLLAPI void | computeBV< kIOS, Halfspace > (const Halfspace &s, const Transform3s &tf, kIOS &bv) |
template<> | |
COAL_DLLAPI void | computeBV< kIOS, Plane > (const Plane &s, const Transform3s &tf, kIOS &bv) |
template<> | |
COAL_DLLAPI void | computeBV< OBB, Box > (const Box &s, const Transform3s &tf, OBB &bv) |
template<> | |
COAL_DLLAPI void | computeBV< OBB, Capsule > (const Capsule &s, const Transform3s &tf, OBB &bv) |
template<> | |
COAL_DLLAPI void | computeBV< OBB, Cone > (const Cone &s, const Transform3s &tf, OBB &bv) |
template<> | |
COAL_DLLAPI void | computeBV< OBB, ConvexBase > (const ConvexBase &s, const Transform3s &tf, OBB &bv) |
template<> | |
COAL_DLLAPI void | computeBV< OBB, Cylinder > (const Cylinder &s, const Transform3s &tf, OBB &bv) |
template<> | |
COAL_DLLAPI void | computeBV< OBB, Halfspace > (const Halfspace &s, const Transform3s &tf, OBB &bv) |
template<> | |
COAL_DLLAPI void | computeBV< OBB, Plane > (const Plane &s, const Transform3s &tf, OBB &bv) |
template<> | |
COAL_DLLAPI void | computeBV< OBB, Sphere > (const Sphere &s, const Transform3s &tf, OBB &bv) |
template<> | |
COAL_DLLAPI void | computeBV< OBBRSS, Halfspace > (const Halfspace &s, const Transform3s &tf, OBBRSS &bv) |
template<> | |
COAL_DLLAPI void | computeBV< OBBRSS, Plane > (const Plane &s, const Transform3s &tf, OBBRSS &bv) |
template<> | |
COAL_DLLAPI void | computeBV< RSS, Halfspace > (const Halfspace &s, const Transform3s &tf, RSS &bv) |
template<> | |
COAL_DLLAPI void | computeBV< RSS, Plane > (const Plane &s, const Transform3s &tf, RSS &bv) |
static void | computeChildBV (const AABB &root_bv, unsigned int i, AABB &child_bv) |
compute the bounding volume of an octree node's i-th child More... | |
COAL_DLLAPI void | computeContactPatch (const CollisionGeometry *o1, const Transform3s &tf1, const CollisionGeometry *o2, const Transform3s &tf2, const CollisionResult &collision_result, const ContactPatchRequest &request, ContactPatchResult &result) |
Main contact patch computation interface. More... | |
COAL_DLLAPI void | computeContactPatch (const CollisionObject *o1, const CollisionObject *o2, const CollisionResult &collision_result, const ContactPatchRequest &request, ContactPatchResult &result) |
template<typename T > | |
size_t | computeMemoryFootprint (const T &object) |
Returns the memory footpring of the input object. For POD objects, this function returns the result of sizeof(T) More... | |
template<bool InvertShapes, typename OtherShapeType , typename PlaneOrHalfspace > | |
void | computePatchPlaneOrHalfspace (const OtherShapeType &s1, const Transform3s &tf1, const PlaneOrHalfspace &s2, const Transform3s &tf2, const ContactPatchSolver *csolver, const Contact &contact, ContactPatch &contact_patch) |
Computes the contact patch between a Plane/Halfspace and another shape. More... | |
template<typename BV > | |
void | computeSplitValue_bvcenter (const BV &bv, CoalScalar &split_value) |
template<typename BV > | |
void | computeSplitValue_mean (const BV &, Vec3s *vertices, Triangle *triangles, unsigned int *primitive_indices, unsigned int num_primitives, BVHModelType type, const Vec3s &split_vector, CoalScalar &split_value) |
template<typename BV > | |
void | computeSplitValue_median (const BV &, Vec3s *vertices, Triangle *triangles, unsigned int *primitive_indices, unsigned int num_primitives, BVHModelType type, const Vec3s &split_vector, CoalScalar &split_value) |
template<typename BV > | |
void | computeSplitVector (const BV &bv, Vec3s &split_vector) |
template<> | |
void | computeSplitVector< kIOS > (const kIOS &bv, Vec3s &split_vector) |
template<> | |
void | computeSplitVector< OBBRSS > (const OBBRSS &bv, Vec3s &split_vector) |
void | computeVertices (const OBB &b, Vec3s vertices[8]) |
Compute the 8 vertices of a OBB. More... | |
COAL_DLLAPI void | constructBox (const AABB &bv, Box &box, Transform3s &tf) |
construct a box shape (with a configuration) from a given bounding volume More... | |
COAL_DLLAPI void | constructBox (const AABB &bv, const Transform3s &tf_bv, Box &box, Transform3s &tf) |
COAL_DLLAPI void | constructBox (const KDOP< 16 > &bv, Box &box, Transform3s &tf) |
COAL_DLLAPI void | constructBox (const KDOP< 16 > &bv, const Transform3s &tf_bv, Box &box, Transform3s &tf) |
COAL_DLLAPI void | constructBox (const KDOP< 18 > &bv, Box &box, Transform3s &tf) |
COAL_DLLAPI void | constructBox (const KDOP< 18 > &bv, const Transform3s &tf_bv, Box &box, Transform3s &tf) |
COAL_DLLAPI void | constructBox (const KDOP< 24 > &bv, Box &box, Transform3s &tf) |
COAL_DLLAPI void | constructBox (const KDOP< 24 > &bv, const Transform3s &tf_bv, Box &box, Transform3s &tf) |
COAL_DLLAPI void | constructBox (const kIOS &bv, Box &box, Transform3s &tf) |
COAL_DLLAPI void | constructBox (const kIOS &bv, const Transform3s &tf_bv, Box &box, Transform3s &tf) |
COAL_DLLAPI void | constructBox (const OBB &bv, Box &box, Transform3s &tf) |
COAL_DLLAPI void | constructBox (const OBB &bv, const Transform3s &tf_bv, Box &box, Transform3s &tf) |
COAL_DLLAPI void | constructBox (const OBBRSS &bv, Box &box, Transform3s &tf) |
COAL_DLLAPI void | constructBox (const OBBRSS &bv, const Transform3s &tf_bv, Box &box, Transform3s &tf) |
COAL_DLLAPI void | constructBox (const RSS &bv, Box &box, Transform3s &tf) |
COAL_DLLAPI void | constructBox (const RSS &bv, const Transform3s &tf_bv, Box &box, Transform3s &tf) |
void | constructContactPatchFrameFromContact (const Contact &contact, ContactPatch &contact_patch) |
Construct a frame from a Contact 's position and normal. Because both Contact 's position and normal are expressed in the world frame, this frame is also expressed w.r.t the world frame. The origin of the frame is contact.pos and the z-axis of the frame is contact.normal . More... | |
Matrix3s | constructOrthonormalBasisFromVector (const Vec3s &vec) |
Construct othonormal basis from vector. The z-axis is the normalized input vector. More... | |
Convex< Triangle > | 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... | |
COAL_LOCAL void | contact_patch_function_not_implemented (const CollisionGeometry *o1, const Transform3s &, const CollisionGeometry *o2, const Transform3s &, const CollisionResult &, const ContactPatchSolver *, const ContactPatchRequest &, ContactPatchResult &) |
template<typename BV1 , typename BV2 > | |
static void | convertBV (const BV1 &bv1, BV2 &bv2) |
Convert a bounding volume of type BV1 to bounding volume of type BV2 in identity configuration. More... | |
template<typename BV1 , typename BV2 > | |
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 configuration. More... | |
bool | 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 | 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... | |
COAL_DLLAPI CoalScalar | distance (const CollisionGeometry *o1, const Transform3s &tf1, const CollisionGeometry *o2, const Transform3s &tf2, const DistanceRequest &request, DistanceResult &result) |
COAL_DLLAPI CoalScalar | distance (const CollisionObject *o1, const CollisionObject *o2, const DistanceRequest &request, DistanceResult &result) |
Main distance interface: given two collision objects, and the requirements for contacts, including whether return the nearest points, this function performs the distance between them. Return value is the minimum distance generated between the two objects. More... | |
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. More... | |
CoalScalar | distance (const Matrix3s &R0, const Vec3s &T0, const OBBRSS &b1, const OBBRSS &b2, Vec3s *P=NULL, Vec3s *Q=NULL) |
Computate distance between two OBBRSS, b1 is in configuation (R0, T0) and b2 is in indentity; P and Q, is not NULL, returns the nearest points. More... | |
COAL_DLLAPI CoalScalar | distance (const Matrix3s &R0, const Vec3s &T0, const RSS &b1, const RSS &b2, Vec3s *P=NULL, Vec3s *Q=NULL) |
distance between two RSS bounding volumes P and Q (optional return values) are the closest points in the rectangles, not the RSS. But the direction P - Q is the correct direction for cloest points Notice that P and Q are both in the local frame of the first RSS (not global frame and not even the local frame of object 1) More... | |
void | distance (DistanceTraversalNodeBase *node, BVHFrontList *front_list, unsigned int qsize) |
COAL_LOCAL CoalScalar | distance_function_not_implemented (const CollisionGeometry *o1, const Transform3s &, const CollisionGeometry *o2, const Transform3s &, const GJKSolver *, const DistanceRequest &, DistanceResult &) |
void | distanceQueueRecurse (DistanceTraversalNodeBase *node, unsigned int b1, unsigned int b2, BVHFrontList *front_list, unsigned int qsize) |
void | distanceRecurse (DistanceTraversalNodeBase *node, unsigned int b1, unsigned int b2, BVHFrontList *front_list) |
template<typename Derived , typename Vector > | |
void | eigen (const Eigen::MatrixBase< Derived > &m, typename Derived::Scalar dout[3], Vector *vout) |
compute the eigen vector and eigen vector of a matrix. dout is the eigen values, vout is the eigen vectors More... | |
void | eulerToMatrix (CoalScalar a, CoalScalar b, CoalScalar c, Matrix3s &R) |
COAL_DLLAPI CollisionGeometry * | extract (const CollisionGeometry *model, const Transform3s &pose, const AABB &aabb) |
template<> | |
void | fit (Vec3s *ps, unsigned int n, AABB &bv) |
template<typename BV > | |
void | fit (Vec3s *ps, unsigned int n, BV &bv) |
Compute a bounding volume that fits a set of n points. More... | |
template<> | |
void | fit (Vec3s *ps, unsigned int n, kIOS &bv) |
template<> | |
void | fit (Vec3s *ps, unsigned int n, OBB &bv) |
template<> | |
void | fit (Vec3s *ps, unsigned int n, OBBRSS &bv) |
template<> | |
void | fit (Vec3s *ps, unsigned int n, RSS &bv) |
template<> | |
void | fit< AABB > (Vec3s *ps, unsigned int n, AABB &bv) |
template<> | |
void | fit< kIOS > (Vec3s *ps, unsigned int n, kIOS &bv) |
template<> | |
void | fit< OBB > (Vec3s *ps, unsigned int n, OBB &bv) |
template<> | |
void | fit< OBBRSS > (Vec3s *ps, unsigned int n, OBBRSS &bv) |
template<> | |
void | fit< RSS > (Vec3s *ps, unsigned int n, RSS &bv) |
template<typename Derived > | |
Quatf | fromAxisAngle (const Eigen::MatrixBase< Derived > &axis, CoalScalar angle) |
template<typename BV > | |
void | generateBVHModel (BVHModel< BV > &model, const Box &shape, const Transform3s &pose) |
Generate BVH model from box. More... | |
template<typename BV > | |
void | generateBVHModel (BVHModel< BV > &model, const Cone &shape, const Transform3s &pose, unsigned int tot, unsigned int h_num) |
Generate BVH model from cone, given the number of segments along circle and the number of segments along axis. More... | |
template<typename BV > | |
void | generateBVHModel (BVHModel< BV > &model, const Cone &shape, const Transform3s &pose, unsigned int tot_for_unit_cone) |
Generate BVH model from cone Difference from generateBVHModel: is that it gives the circle split number tot for a cylinder with unit radius. For cone with larger radius, the number of circle split number is r * tot. More... | |
template<typename BV > | |
void | generateBVHModel (BVHModel< BV > &model, const Cylinder &shape, const Transform3s &pose, unsigned int tot, unsigned int h_num) |
Generate BVH model from cylinder, given the number of segments along circle and the number of segments along axis. More... | |
template<typename BV > | |
void | generateBVHModel (BVHModel< BV > &model, const Cylinder &shape, const Transform3s &pose, unsigned int tot_for_unit_cylinder) |
Generate BVH model from cylinder Difference from generateBVHModel: is that it gives the circle split number tot for a cylinder with unit radius. For cylinder with larger radius, the number of circle split number is r * tot. More... | |
template<typename BV > | |
void | generateBVHModel (BVHModel< BV > &model, const Sphere &shape, const Transform3s &pose, unsigned int n_faces_for_unit_sphere) |
Generate BVH model from sphere The difference between generateBVHModel is that it gives the number of triangles faces N for a sphere with unit radius. For sphere of radius r, then the number of triangles is r * r * N so that the area represented by a single triangle is approximately the same.s. More... | |
template<typename BV > | |
void | generateBVHModel (BVHModel< BV > &model, const Sphere &shape, const Transform3s &pose, unsigned int seg, unsigned int ring) |
Generate BVH model from sphere, given the number of segments along longitude and number of rings along latitude. More... | |
template<typename Derived1 , typename Derived2 , typename Derived3 > | |
void | generateCoordinateSystem (const Eigen::MatrixBase< Derived1 > &_w, const Eigen::MatrixBase< Derived2 > &_u, const Eigen::MatrixBase< Derived3 > &_v) |
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) |
void | 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 | 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 | generateRandomTransforms (CoalScalar extents[6], std::vector< Transform3s > &transforms, std::size_t n) |
Generate n random transforms whose translations are constrained by extents. More... | |
const char * | get_node_type_name (NODE_TYPE node_type) |
Returns the name associated to a NODE_TYPE. More... | |
const char * | get_object_type_name (OBJECT_TYPE object_type) |
Returns the name associated to a OBJECT_TYPE. More... | |
CollisionFunctionMatrix & | getCollisionFunctionLookTable () |
ContactPatchFunctionMatrix & | getContactPatchFunctionLookTable () |
COAL_DLLAPI void | getCovariance (Vec3s *ps, Vec3s *ps2, Triangle *ts, unsigned int *indices, unsigned int n, Matrix3s &M) |
Compute the covariance matrix for a set or subset of points. if ts = null, then indices refer to points directly; otherwise refer to triangles. More... | |
DistanceFunctionMatrix & | getDistanceFunctionLookTable () |
template<short N> | |
void | getDistances (const Vec3s &, CoalScalar *) |
Compute the distances to planes with normals from KDOP vectors except those of AABB face planes. More... | |
template<> | |
void | getDistances< 5 > (const Vec3s &p, CoalScalar *d) |
Specification of getDistances. More... | |
template<> | |
void | getDistances< 6 > (const Vec3s &p, CoalScalar *d) |
template<> | |
void | getDistances< 9 > (const Vec3s &p, CoalScalar *d) |
COAL_DLLAPI void | getExtentAndCenter (Vec3s *ps, Vec3s *ps2, Triangle *ts, unsigned int *indices, unsigned int n, Matrix3s &axes, Vec3s ¢er, Vec3s &extent) |
Compute the bounding volume extent and center for a set or subset of points, given the BV axises. More... | |
static void | getExtentAndCenter_mesh (Vec3s *ps, Vec3s *ps2, Triangle *ts, unsigned int *indices, unsigned int n, Matrix3s &axes, Vec3s ¢er, Vec3s &extent) |
Compute the bounding volume extent and center for a set or subset of points. The bounding volume axes are known. More... | |
static void | getExtentAndCenter_pointcloud (Vec3s *ps, Vec3s *ps2, unsigned int *indices, unsigned int n, Matrix3s &axes, Vec3s ¢er, Vec3s &extent) |
Compute the bounding volume extent and center for a set or subset of points. The bounding volume axes are known. More... | |
std::size_t | getNbRun (const int &argc, char const *const *argv, std::size_t defaultValue) |
Get the argument –nb-run from argv. More... | |
std::string | getNodeTypeName (NODE_TYPE node_type) |
COAL_DLLAPI void | getRadiusAndOriginAndRectangleSize (Vec3s *ps, Vec3s *ps2, Triangle *ts, unsigned int *indices, unsigned int n, const Matrix3s &axes, Vec3s &origin, CoalScalar l[2], CoalScalar &r) |
Compute the RSS bounding volume parameters: radius, rectangle size and the origin, given the BV axises. More... | |
bool | inVoronoi (CoalScalar a, CoalScalar b, CoalScalar Anorm_dot_B, CoalScalar Anorm_dot_T, CoalScalar A_dot_B, CoalScalar A_dot_T, CoalScalar B_dot_T) |
Returns whether the nearest point on rectangle edge Pb + B*u, 0 <= u <= b, to the rectangle edge, Pa + A*t, 0 <= t <= a, is within the half space determined by the point Pa and the direction Anorm. A,B, and Anorm are unit vectors. T is the vector between Pa and Pb. More... | |
template<typename Derived , typename OtherDerived > | |
bool | isEqual (const Eigen::MatrixBase< Derived > &lhs, const Eigen::MatrixBase< OtherDerived > &rhs, const CoalScalar tol=std::numeric_limits< CoalScalar >::epsilon() *100) |
void | loadOBJFile (const char *filename, std::vector< Vec3s > &points, std::vector< Triangle > &triangles) |
Load an obj mesh file. More... | |
template<class BoundingVolume > | |
void | loadPolyhedronFromResource (const std::string &resource_path, const coal::Vec3s &scale, const shared_ptr< BVHModel< BoundingVolume > > &polyhedron) |
Read a mesh file and convert it to a polyhedral mesh. More... | |
COAL_DLLAPI OcTreePtr_t | makeOctree (const Eigen::Matrix< CoalScalar, Eigen::Dynamic, 3 > &point_cloud, const CoalScalar resolution) |
Build an OcTree from a point cloud and a given resolution. More... | |
Quatf | makeQuat (CoalScalar w, CoalScalar x, CoalScalar y, CoalScalar z) |
Box | makeRandomBox (CoalScalar min_size, CoalScalar max_size) |
Capsule | makeRandomCapsule (std::array< CoalScalar, 2 > min_size, std::array< CoalScalar, 2 > max_size) |
Cone | makeRandomCone (std::array< CoalScalar, 2 > min_size, std::array< CoalScalar, 2 > max_size) |
Convex< Triangle > | makeRandomConvex (CoalScalar min_size, CoalScalar max_size) |
Cylinder | makeRandomCylinder (std::array< CoalScalar, 2 > min_size, std::array< CoalScalar, 2 > max_size) |
Ellipsoid | makeRandomEllipsoid (CoalScalar min_size, CoalScalar max_size) |
std::shared_ptr< ShapeBase > | makeRandomGeometry (NODE_TYPE node_type) |
Halfspace | makeRandomHalfspace (CoalScalar min_size, CoalScalar max_size) |
Plane | makeRandomPlane (CoalScalar min_size, CoalScalar max_size) |
Sphere | makeRandomSphere (CoalScalar min_size, CoalScalar max_size) |
COAL_DLLAPI CoalScalar | maximumDistance (Vec3s *ps, Vec3s *ps2, Triangle *ts, unsigned int *indices, unsigned int n, const Vec3s &query) |
Compute the maximum distance from a given center point to a point cloud. More... | |
static CoalScalar | maximumDistance_mesh (Vec3s *ps, Vec3s *ps2, Triangle *ts, unsigned int *indices, unsigned int n, const Vec3s &query) |
static CoalScalar | maximumDistance_pointcloud (Vec3s *ps, Vec3s *ps2, unsigned int *indices, unsigned int n, const Vec3s &query) |
OBB | merge_largedist (const OBB &b1, const OBB &b2) |
OBB merge method when the centers of two smaller OBB are far away. More... | |
OBB | merge_smalldist (const OBB &b1, const OBB &b2) |
OBB merge method when the centers of two smaller OBB are close. More... | |
void | minmax (CoalScalar a, CoalScalar b, CoalScalar &minv, CoalScalar &maxv) |
Find the smaller and larger one of two values. More... | |
void | minmax (CoalScalar p, CoalScalar &minv, CoalScalar &maxv) |
Merge the interval [minv, maxv] and value p/. More... | |
COAL_DLLAPI bool | obbDisjoint (const Matrix3s &B, const Vec3s &T, const Vec3s &a, const Vec3s &b) |
bool | obbDisjointAndLowerBoundDistance (const Matrix3s &B, const Vec3s &T, const Vec3s &a_, const Vec3s &b_, const CollisionRequest &request, CoalScalar &squaredLowerBoundDistance) |
CollisionRequestFlag | operator& (CollisionRequestFlag a, CollisionRequestFlag b) |
HFNodeBase::FaceOrientation | operator& (HFNodeBase::FaceOrientation a, HFNodeBase::FaceOrientation b) |
int | operator& (int a, HFNodeBase::FaceOrientation b) |
CollisionRequestFlag & | operator&= (CollisionRequestFlag &a, CollisionRequestFlag b) |
static std::ostream & | operator<< (std::ostream &o, const Quatf &q) |
std::ostream & | operator<< (std::ostream &os, const Box &b) |
std::ostream & | operator<< (std::ostream &os, const ShapeBase &) |
std::ostream & | operator<< (std::ostream &os, const Transform3s &tf) |
CollisionRequestFlag | operator^ (CollisionRequestFlag a, CollisionRequestFlag b) |
CollisionRequestFlag & | operator^= (CollisionRequestFlag &a, CollisionRequestFlag b) |
CollisionRequestFlag | operator| (CollisionRequestFlag a, CollisionRequestFlag b) |
CollisionRequestFlag & | operator|= (CollisionRequestFlag &a, CollisionRequestFlag b) |
CollisionRequestFlag | operator~ (CollisionRequestFlag a) |
template<short N> | |
bool | overlap (const Matrix3s &, const Vec3s &, const KDOP< N > &, const KDOP< N > &) |
template<short N> | |
bool | overlap (const Matrix3s &, const Vec3s &, const KDOP< N > &, const KDOP< N > &, const CollisionRequest &, CoalScalar &) |
COAL_DLLAPI bool | overlap (const Matrix3s &R0, const Vec3s &T0, const AABB &b1, const AABB &b2) |
Check collision between two aabbs, b1 is in configuration (R0, T0) and b2 is in identity. More... | |
COAL_DLLAPI bool | overlap (const Matrix3s &R0, const Vec3s &T0, const AABB &b1, const AABB &b2, const CollisionRequest &request, CoalScalar &sqrDistLowerBound) |
Check collision between two aabbs, b1 is in configuration (R0, T0) and b2 is in identity. More... | |
COAL_DLLAPI bool | overlap (const Matrix3s &R0, const Vec3s &T0, const kIOS &b1, const kIOS &b2) |
Check collision between two kIOSs, b1 is in configuration (R0, T0) and b2 is in identity. More... | |
COAL_DLLAPI bool | overlap (const Matrix3s &R0, const Vec3s &T0, const kIOS &b1, const kIOS &b2, const CollisionRequest &request, CoalScalar &sqrDistLowerBound) |
Check collision between two kIOSs, b1 is in configuration (R0, T0) and b2 is in identity. More... | |
COAL_DLLAPI bool | overlap (const Matrix3s &R0, const Vec3s &T0, const OBB &b1, const OBB &b2) |
Check collision between two obbs, b1 is in configuration (R0, T0) and b2 is in identity. More... | |
COAL_DLLAPI bool | overlap (const Matrix3s &R0, const Vec3s &T0, const OBB &b1, const OBB &b2, const CollisionRequest &request, CoalScalar &sqrDistLowerBound) |
Check collision between two obbs, b1 is in configuration (R0, T0) and b2 is in identity. More... | |
bool | overlap (const Matrix3s &R0, const Vec3s &T0, const OBBRSS &b1, const OBBRSS &b2) |
Check collision between two OBBRSS, b1 is in configuration (R0, T0) and b2 is in indentity. More... | |
bool | overlap (const Matrix3s &R0, const Vec3s &T0, const OBBRSS &b1, const OBBRSS &b2, const CollisionRequest &request, CoalScalar &sqrDistLowerBound) |
COAL_DLLAPI bool | overlap (const Matrix3s &R0, const Vec3s &T0, const RSS &b1, const RSS &b2) |
Check collision between two RSSs, b1 is in configuration (R0, T0) and b2 is in identity. More... | |
COAL_DLLAPI bool | overlap (const Matrix3s &R0, const Vec3s &T0, const RSS &b1, const RSS &b2, const CollisionRequest &request, CoalScalar &sqrDistLowerBound) |
Check collision between two RSSs, b1 is in configuration (R0, T0) and b2 is in identity. More... | |
void | propagateBVHFrontListCollisionRecurse (CollisionTraversalNodeBase *node, const CollisionRequest &, CollisionResult &result, BVHFrontList *front_list) |
CoalScalar | rand_interval (CoalScalar rmin, CoalScalar rmax) |
CoalScalar | rectDistance (const Matrix3s &Rab, Vec3s const &Tab, const CoalScalar a[2], const CoalScalar b[2], Vec3s *P=NULL, Vec3s *Q=NULL) |
Distance between two oriented rectangles; P and Q (optional return values) are the closest points in the rectangles, both are in the local frame of the first rectangle. More... | |
template<typename Derived , typename OtherDerived > | |
void | relativeTransform (const Eigen::MatrixBase< Derived > &R1, const Eigen::MatrixBase< OtherDerived > &t1, const Eigen::MatrixBase< Derived > &R2, const Eigen::MatrixBase< OtherDerived > &t2, const Eigen::MatrixBase< Derived > &R, const Eigen::MatrixBase< OtherDerived > &t) |
void | relativeTransform (const Transform3s &tf1, const Transform3s &tf2, Transform3s &tf) |
void | relativeTransform2 (const Transform3s &tf1, const Transform3s &tf2, Transform3s &tf) |
void | reorderTriangle (const Convex< Triangle > *convex_tri, Triangle &tri) |
static AABB | rotate (const AABB &aabb, const Matrix3s &R) |
void | saveOBJFile (const char *filename, std::vector< Vec3s > &points, std::vector< Triangle > &triangles) |
void | segCoords (CoalScalar &t, CoalScalar &u, CoalScalar a, CoalScalar b, CoalScalar A_dot_B, CoalScalar A_dot_T, CoalScalar B_dot_T) |
Finds the parameters t & u corresponding to the two closest points on a pair of line segments. The first segment is defined as Pa + A*t, 0 <= t <= a, where "Pa" is one endpoint of the segment, "A" is a unit vector pointing to the other endpoint, and t is a scalar that produces all the points between the two endpoints. Since "A" is a unit vector, "a" is the segment's length. The second segment is defined as Pb + B*u, 0 <= u <= b. Many of the terms needed by the algorithm are already computed for other purposes,so we just pass these terms into the function instead of complete specifications of each segment. "T" in the dot products is the vector betweeen Pa and Pb. Reference: "On fast computation of distance between line segments." Vladimir J. Lumelsky, in Information Processing Letters, no. 21, pages 55-61, 1985. More... | |
template<typename ShapeType1 , typename ShapeType2 > | |
void | ShapeShapeContactPatch (const CollisionGeometry *o1, const Transform3s &tf1, const CollisionGeometry *o2, const Transform3s &tf2, const CollisionResult &collision_result, const ContactPatchSolver *csolver, const ContactPatchRequest &request, ContactPatchResult &result) |
void | toEllipsoid (Vec3s &point, const Ellipsoid &ellipsoid) |
void | toSphere (Vec3s &point) |
Takes a point and projects it onto the surface of the unit sphere. More... | |
COAL_DLLAPI Halfspace | transform (const Halfspace &a, const Transform3s &tf) |
COAL_DLLAPI Plane | transform (const Plane &a, const Transform3s &tf) |
COAL_DLLAPI std::array< Halfspace, 2 > | transformToHalfspaces (const Plane &a, const Transform3s &tf) |
static AABB | translate (const AABB &aabb, const Vec3s &t) |
translate the center of AABB by t More... | |
template<short N> | |
COAL_DLLAPI KDOP< N > | translate (const KDOP< N > &bv, const Vec3s &t) |
translate the KDOP BV More... | |
template<short N> | |
KDOP< N > | translate (const KDOP< N > &bv, const Vec3s &t) |
translate the KDOP BV More... | |
COAL_DLLAPI kIOS | translate (const kIOS &bv, const Vec3s &t) |
Translate the kIOS BV. More... | |
COAL_DLLAPI OBB | translate (const OBB &bv, const Vec3s &t) |
Translate the OBB bv. More... | |
OBBRSS | translate (const OBBRSS &bv, const Vec3s &t) |
RSS | translate (const RSS &bv, const Vec3s &t) |
template KDOP< 16 > | translate< 16 > (const KDOP< 16 > &, const Vec3s &) |
template KDOP< 18 > | translate< 18 > (const KDOP< 18 > &, const Vec3s &) |
template KDOP< 24 > | translate< 24 > (const KDOP< 24 > &, const Vec3s &) |
template<typename Derived > | |
static Derived::Scalar | triple (const Eigen::MatrixBase< Derived > &x, const Eigen::MatrixBase< Derived > &y, const Eigen::MatrixBase< Derived > &z) |
Quatf | uniformRandomQuaternion () |
Uniformly random quaternion sphere. Code taken from Pinocchio (https://github.com/stack-of-tasks/pinocchio). More... | |
void | updateFrontList (BVHFrontList *front_list, unsigned int b1, unsigned int b2) |
Add new front node into the front list. More... | |
Variables | |
static const double | cosA = sqrt(3.0) / 2.0 |
constexpr size_t | EPA_DEFAULT_MAX_ITERATIONS = 64 |
constexpr CoalScalar | EPA_DEFAULT_TOLERANCE = 1e-6 |
constexpr CoalScalar | EPA_MINIMUM_TOLERANCE = 1e-6 |
constexpr size_t | GJK_DEFAULT_MAX_ITERATIONS = 128 |
GJK. More... | |
constexpr CoalScalar | GJK_DEFAULT_TOLERANCE = 1e-6 |
constexpr CoalScalar | GJK_MINIMUM_TOLERANCE = 1e-6 |
static const double | invSinA = 2 |
static const double | kIOS_RATIO = 1.5 |
const Eigen::IOFormat | pyfmt |
COAL_DEPRECATED typedef Eigen::Quaternion< CoalScalar > | Quaternion3f |
const Vec3s | UnitX = Vec3s(1, 0, 0) |
const Vec3s | UnitY = Vec3s(0, 1, 0) |
const Vec3s | UnitZ = Vec3s(0, 0, 1) |
const Eigen::IOFormat | vfmt |
Main namespace.
This file defines different macros used to characterize the default behavior of the narrowphase algorithms GJK and EPA.
typedef Eigen::AngleAxis<CoalScalar> coal::AngleAxis |
using coal::BroadPhaseContinuousCollisionManagerd = typedef BroadPhaseContinuousCollisionManager<CoalScalar> |
Definition at line 137 of file coal/broadphase/broadphase_continuous_collision_manager.h.
using coal::BroadPhaseContinuousCollisionManagerf = typedef BroadPhaseContinuousCollisionManager<float> |
Definition at line 135 of file coal/broadphase/broadphase_continuous_collision_manager.h.
typedef std::list<BVHFrontNode> coal::BVHFrontList |
BVH front list is a list of front nodes.
Definition at line 66 of file coal/BVH/BVH_front.h.
typedef shared_ptr<BVHModelBase> coal::BVHModelPtr_t |
Definition at line 141 of file include/coal/fwd.hh.
typedef double coal::CoalScalar |
Definition at line 76 of file coal/data_types.h.
typedef shared_ptr<const CollisionGeometry> coal::CollisionGeometryConstPtr_t |
Definition at line 136 of file include/coal/fwd.hh.
typedef shared_ptr<CollisionGeometry> coal::CollisionGeometryPtr_t |
Definition at line 134 of file include/coal/fwd.hh.
typedef shared_ptr<const CollisionObject> coal::CollisionObjectConstPtr_t |
Definition at line 133 of file include/coal/fwd.hh.
typedef shared_ptr<CollisionObject> coal::CollisionObjectPtr_t |
Definition at line 131 of file include/coal/fwd.hh.
using coal::ContinuousCollisionCallBack = typedef bool (*)(ContinuousCollisionObject* o1, ContinuousCollisionObject* o2, void* cdata) |
Callback for continuous collision between two objects. Return value is whether can stop now.
Definition at line 52 of file coal/broadphase/broadphase_continuous_collision_manager.h.
using coal::ContinuousDistanceCallBack = typedef bool (*)(ContinuousCollisionObject* o1, ContinuousCollisionObject* o2, S& dist) |
Callback for continuous distance between two objects, Return value is whether can stop now, also return the minimum distance till now.
Definition at line 59 of file coal/broadphase/broadphase_continuous_collision_manager.h.
typedef Eigen::Matrix<CoalScalar, 3, 3> coal::Matrix3s |
Definition at line 81 of file coal/data_types.h.
typedef Eigen::Matrix<CoalScalar, Eigen::Dynamic, 2, Eigen::RowMajor> coal::MatrixX2s |
Definition at line 83 of file coal/data_types.h.
typedef Eigen::Matrix<Eigen::DenseIndex, Eigen::Dynamic, 3, Eigen::RowMajor> coal::Matrixx3i |
Definition at line 85 of file coal/data_types.h.
typedef Eigen::Matrix<CoalScalar, Eigen::Dynamic, 3, Eigen::RowMajor> coal::MatrixX3s |
Definition at line 82 of file coal/data_types.h.
typedef Eigen::Matrix<CoalScalar, Eigen::Dynamic, Eigen::Dynamic> coal::MatrixXs |
Definition at line 86 of file coal/data_types.h.
typedef shared_ptr<const OcTree> coal::OcTreeConstPtr_t |
Definition at line 146 of file include/coal/fwd.hh.
typedef shared_ptr<OcTree> coal::OcTreePtr_t |
Definition at line 144 of file include/coal/fwd.hh.
typedef Eigen::Quaternion<CoalScalar> coal::Quatf |
Definition at line 47 of file coal/math/transform.h.
typedef Eigen::Vector2i coal::support_func_guess_t |
Definition at line 87 of file coal/data_types.h.
using coal::SupportSet = typedef ContactPatch |
Structure used for internal computations. A support set and a contact patch can be represented by the same structure. In fact, a contact patch is the intersection of two support sets, one with PatchDirection::DEFAULT
and one with PatchDirection::INVERTED
.
DEFAULT
direction is the support set of a shape in the direction given by +n
, where n
is the z-axis of the frame's patch rotation. An INVERTED
support set is the support set of a shape in the direction -n
. Definition at line 721 of file coal/collision_data.h.
typedef Eigen::Matrix<CoalScalar, 2, 1> coal::Vec2s |
Definition at line 78 of file coal/data_types.h.
typedef Eigen::Matrix<CoalScalar, 3, 1> coal::Vec3s |
Definition at line 77 of file coal/data_types.h.
typedef Eigen::Matrix<CoalScalar, 6, 1> coal::Vec6s |
Definition at line 79 of file coal/data_types.h.
typedef Eigen::Matrix<CoalScalar, Eigen::Dynamic, 1> coal::VecXs |
Definition at line 80 of file coal/data_types.h.
enum coal::BVHBuildState |
States for BVH construction empty->begun->processed ->replace_begun->processed -> ...... | |-> update_begun -> updated -> .....
Definition at line 49 of file coal/BVH/BVH_internal.h.
enum coal::BVHModelType |
BVH model type.
Enumerator | |
---|---|
BVH_MODEL_UNKNOWN | |
BVH_MODEL_TRIANGLES | unknown model type |
BVH_MODEL_POINTCLOUD | triangle model point cloud model |
Definition at line 79 of file coal/BVH/BVH_internal.h.
enum coal::BVHReturnCode |
Error code for BVH.
Definition at line 63 of file coal/BVH/BVH_internal.h.
flag declaration for specifying required params in CollisionResult
Enumerator | |
---|---|
CONTACT | |
DISTANCE_LOWER_BOUND | |
NO_REQUEST |
Definition at line 304 of file coal/collision_data.h.
Which convergence criterion is used to stop the algorithm (when the shapes are not in collision). (default) VDB: Van den Bergen (A Fast and Robust GJK Implementation, 1999) DG: duality-gap, as used in the Frank-Wolfe and the vanilla 1988 GJK algorithms Hybrid: a mix between VDB and DG.
Enumerator | |
---|---|
Default | |
DualityGap | |
Hybrid |
Definition at line 104 of file coal/data_types.h.
Wether the convergence criterion is scaled on the norm of the solution or not.
Enumerator | |
---|---|
Relative | |
Absolute |
Definition at line 108 of file coal/data_types.h.
Initial guess to use for the GJK algorithm DefaultGuess: Vec3s(1, 0, 0) CachedGuess: previous vector found by GJK or guess cached by the user BoundingVolumeGuess: guess using the centers of the shapes' AABB WARNING: to use BoundingVolumeGuess, computeLocalAABB must have been called on the two shapes.
Enumerator | |
---|---|
DefaultGuess | |
CachedGuess | |
BoundingVolumeGuess |
Definition at line 95 of file coal/data_types.h.
enum coal::GJKVariant |
Variant to use for the GJK algorithm.
Enumerator | |
---|---|
DefaultGJK | |
PolyakAcceleration | |
NesterovAcceleration |
Definition at line 98 of file coal/data_types.h.
enum coal::NODE_TYPE |
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18, kDOP24), basic shape (box, sphere, ellipsoid, capsule, cone, cylinder, convex, plane, triangle), and octree
Definition at line 64 of file coal/collision_object.h.
enum coal::OBJECT_TYPE |
object type: BVH (mesh, points), basic geometry, octree
Enumerator | |
---|---|
OT_UNKNOWN | |
OT_BVH | |
OT_GEOM | |
OT_OCTREE | |
OT_HFIELD | |
OT_COUNT |
Definition at line 52 of file coal/collision_object.h.
Three types of split algorithms are provided in FCL as default.
Enumerator | |
---|---|
SPLIT_METHOD_MEAN | |
SPLIT_METHOD_MEDIAN | |
SPLIT_METHOD_BV_CENTER |
Definition at line 50 of file coal/internal/BV_splitter.h.
BVHModelPtr_t coal::_load | ( | const std::string & | filename, |
const Vec3s & | scale | ||
) |
Definition at line 61 of file loader.cpp.
|
inlinestatic |
Definition at line 50 of file BV_fitter.cpp.
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.
Definition at line 460 of file utility.cpp.
std::size_t coal::BVHCollide | ( | const CollisionGeometry * | o1, |
const Transform3s & | tf1, | ||
const CollisionGeometry * | o2, | ||
const Transform3s & | tf2, | ||
const CollisionRequest & | request, | ||
CollisionResult & | result | ||
) |
Definition at line 207 of file collision_func_matrix.cpp.
std::size_t coal::BVHCollide | ( | const CollisionGeometry * | o1, |
const Transform3s & | tf1, | ||
const CollisionGeometry * | o2, | ||
const Transform3s & | tf2, | ||
const GJKSolver * | , | ||
const CollisionRequest & | request, | ||
CollisionResult & | result | ||
) |
Definition at line 269 of file collision_func_matrix.cpp.
std::size_t coal::BVHCollide< kIOS > | ( | const CollisionGeometry * | o1, |
const Transform3s & | tf1, | ||
const CollisionGeometry * | o2, | ||
const Transform3s & | tf2, | ||
const CollisionRequest & | request, | ||
CollisionResult & | result | ||
) |
Definition at line 258 of file collision_func_matrix.cpp.
std::size_t coal::BVHCollide< OBB > | ( | const CollisionGeometry * | o1, |
const Transform3s & | tf1, | ||
const CollisionGeometry * | o2, | ||
const Transform3s & | tf2, | ||
const CollisionRequest & | request, | ||
CollisionResult & | result | ||
) |
Definition at line 238 of file collision_func_matrix.cpp.
std::size_t coal::BVHCollide< OBBRSS > | ( | const CollisionGeometry * | o1, |
const Transform3s & | tf1, | ||
const CollisionGeometry * | o2, | ||
const Transform3s & | tf2, | ||
const CollisionRequest & | request, | ||
CollisionResult & | result | ||
) |
Definition at line 247 of file collision_func_matrix.cpp.
CoalScalar coal::BVHDistance | ( | const CollisionGeometry * | o1, |
const Transform3s & | tf1, | ||
const CollisionGeometry * | o2, | ||
const Transform3s & | tf2, | ||
const DistanceRequest & | request, | ||
DistanceResult & | result | ||
) |
Definition at line 203 of file distance_func_matrix.cpp.
CoalScalar coal::BVHDistance | ( | const CollisionGeometry * | o1, |
const Transform3s & | tf1, | ||
const CollisionGeometry * | o2, | ||
const Transform3s & | tf2, | ||
const GJKSolver * | , | ||
const DistanceRequest & | request, | ||
DistanceResult & | result | ||
) |
Definition at line 276 of file distance_func_matrix.cpp.
CoalScalar coal::BVHDistance< kIOS > | ( | const CollisionGeometry * | o1, |
const Transform3s & | tf1, | ||
const CollisionGeometry * | o2, | ||
const Transform3s & | tf2, | ||
const DistanceRequest & | request, | ||
DistanceResult & | result | ||
) |
Definition at line 254 of file distance_func_matrix.cpp.
CoalScalar coal::BVHDistance< OBBRSS > | ( | const CollisionGeometry * | o1, |
const Transform3s & | tf1, | ||
const CollisionGeometry * | o2, | ||
const Transform3s & | tf2, | ||
const DistanceRequest & | request, | ||
DistanceResult & | result | ||
) |
Definition at line 265 of file distance_func_matrix.cpp.
CoalScalar coal::BVHDistance< RSS > | ( | const CollisionGeometry * | o1, |
const Transform3s & | tf1, | ||
const CollisionGeometry * | o2, | ||
const Transform3s & | tf2, | ||
const DistanceRequest & | request, | ||
DistanceResult & | result | ||
) |
Definition at line 245 of file distance_func_matrix.cpp.
BVHModel< AABB > * coal::BVHExtract | ( | const BVHModel< AABB > & | model, |
const Transform3s & | pose, | ||
const AABB & | aabb | ||
) |
Definition at line 147 of file BVH_utility.cpp.
COAL_DLLAPI BVHModel<BV>* coal::BVHExtract | ( | const BVHModel< BV > & | model, |
const Transform3s & | pose, | ||
const AABB & | aabb | ||
) |
Extract the part of the BVHModel that is inside an AABB. A triangle in collision with the AABB is considered inside.
Definition at line 47 of file BVH_utility.cpp.
BVHModel< KDOP< 16 > > * coal::BVHExtract | ( | const BVHModel< KDOP< 16 > > & | model, |
const Transform3s & | pose, | ||
const AABB & | aabb | ||
) |
Definition at line 167 of file BVH_utility.cpp.
BVHModel< KDOP< 18 > > * coal::BVHExtract | ( | const BVHModel< KDOP< 18 > > & | model, |
const Transform3s & | pose, | ||
const AABB & | aabb | ||
) |
Definition at line 172 of file BVH_utility.cpp.
BVHModel< KDOP< 24 > > * coal::BVHExtract | ( | const BVHModel< KDOP< 24 > > & | model, |
const Transform3s & | pose, | ||
const AABB & | aabb | ||
) |
Definition at line 177 of file BVH_utility.cpp.
BVHModel< kIOS > * coal::BVHExtract | ( | const BVHModel< kIOS > & | model, |
const Transform3s & | pose, | ||
const AABB & | aabb | ||
) |
Definition at line 157 of file BVH_utility.cpp.
BVHModel< OBB > * coal::BVHExtract | ( | const BVHModel< OBB > & | model, |
const Transform3s & | pose, | ||
const AABB & | aabb | ||
) |
Definition at line 142 of file BVH_utility.cpp.
BVHModel< OBBRSS > * coal::BVHExtract | ( | const BVHModel< OBBRSS > & | model, |
const Transform3s & | pose, | ||
const AABB & | aabb | ||
) |
Definition at line 162 of file BVH_utility.cpp.
BVHModel< RSS > * coal::BVHExtract | ( | const BVHModel< RSS > & | model, |
const Transform3s & | pose, | ||
const AABB & | aabb | ||
) |
Definition at line 152 of file BVH_utility.cpp.
void coal::checkResultLowerBound | ( | const CollisionResult & | result, |
CoalScalar | sqrDistLowerBound | ||
) |
Definition at line 43 of file collision_node.cpp.
void coal::circumCircleComputation | ( | const Vec3s & | a, |
const Vec3s & | b, | ||
const Vec3s & | c, | ||
Vec3s & | center, | ||
CoalScalar & | radius | ||
) |
Compute the center and radius for a triangle's circumcircle.
Definition at line 585 of file BVH_utility.cpp.
void coal::clipToRange | ( | CoalScalar & | val, |
CoalScalar | a, | ||
CoalScalar | b | ||
) |
void coal::collide | ( | CollisionTraversalNodeBase * | node, |
const CollisionRequest & | request, | ||
CollisionResult & | result, | ||
BVHFrontList * | front_list, | ||
bool | recursive | ||
) |
Definition at line 62 of file collision_node.cpp.
std::size_t coal::collide | ( | const CollisionGeometry * | o1, |
const Transform3s & | tf1, | ||
const CollisionGeometry * | o2, | ||
const Transform3s & | tf2, | ||
const CollisionRequest & | request, | ||
CollisionResult & | result | ||
) |
Definition at line 68 of file src/collision.cpp.
std::size_t coal::collide | ( | const CollisionObject * | o1, |
const CollisionObject * | o2, | ||
const CollisionRequest & | request, | ||
CollisionResult & | result | ||
) |
Main collision interface: given two collision objects, and the requirements for contacts, including num of max contacts, whether perform exhaustive collision (i.e., returning returning all the contact points), whether return detailed contact information (i.e., normal, contact point, depth; otherwise only contact primitive id is returned), this function performs the collision between them. Return value is the number of contacts generated between the two objects.
Definition at line 61 of file src/collision.cpp.
void coal::collisionNonRecurse | ( | CollisionTraversalNodeBase * | node, |
BVHFrontList * | front_list, | ||
CoalScalar & | sqrDistLowerBound | ||
) |
Definition at line 86 of file traversal_recurse.cpp.
void coal::collisionRecurse | ( | CollisionTraversalNodeBase * | node, |
unsigned int | b1, | ||
unsigned int | b2, | ||
BVHFrontList * | front_list, | ||
CoalScalar & | sqrDistLowerBound | ||
) |
Definition at line 43 of file traversal_recurse.cpp.
|
inline |
calculate a bounding volume for a shape in a specific configuration
Definition at line 73 of file coal/shape/geometric_shapes_utility.h.
void coal::computeBV< AABB, Box > | ( | const Box & | s, |
const Transform3s & | tf, | ||
AABB & | bv | ||
) |
Definition at line 292 of file geometric_shapes_utility.cpp.
void coal::computeBV< AABB, Capsule > | ( | const Capsule & | s, |
const Transform3s & | tf, | ||
AABB & | bv | ||
) |
Definition at line 322 of file geometric_shapes_utility.cpp.
void coal::computeBV< AABB, Cone > | ( | const Cone & | s, |
const Transform3s & | tf, | ||
AABB & | bv | ||
) |
Definition at line 333 of file geometric_shapes_utility.cpp.
void coal::computeBV< AABB, ConvexBase > | ( | const ConvexBase & | s, |
const Transform3s & | tf, | ||
AABB & | bv | ||
) |
Definition at line 368 of file geometric_shapes_utility.cpp.
void coal::computeBV< AABB, Cylinder > | ( | const Cylinder & | s, |
const Transform3s & | tf, | ||
AABB & | bv | ||
) |
Definition at line 350 of file geometric_shapes_utility.cpp.
void coal::computeBV< AABB, Ellipsoid > | ( | const Ellipsoid & | e, |
const Transform3s & | tf, | ||
AABB & | bv | ||
) |
Definition at line 311 of file geometric_shapes_utility.cpp.
void coal::computeBV< AABB, Halfspace > | ( | const Halfspace & | s, |
const Transform3s & | tf, | ||
AABB & | bv | ||
) |
Definition at line 390 of file geometric_shapes_utility.cpp.
void coal::computeBV< AABB, Plane > | ( | const Plane & | s, |
const Transform3s & | tf, | ||
AABB & | bv | ||
) |
Definition at line 423 of file geometric_shapes_utility.cpp.
void coal::computeBV< AABB, Sphere > | ( | const Sphere & | s, |
const Transform3s & | tf, | ||
AABB & | bv | ||
) |
Definition at line 302 of file geometric_shapes_utility.cpp.
void coal::computeBV< AABB, TriangleP > | ( | const TriangleP & | s, |
const Transform3s & | tf, | ||
AABB & | bv | ||
) |
Definition at line 384 of file geometric_shapes_utility.cpp.
void coal::computeBV< KDOP< 16 >, Halfspace > | ( | const Halfspace & | s, |
const Transform3s & | tf, | ||
KDOP< 16 > & | bv | ||
) |
Definition at line 596 of file geometric_shapes_utility.cpp.
void coal::computeBV< KDOP< 16 >, Plane > | ( | const Plane & | s, |
const Transform3s & | tf, | ||
KDOP< 16 > & | bv | ||
) |
Definition at line 864 of file geometric_shapes_utility.cpp.
void coal::computeBV< KDOP< 18 >, Halfspace > | ( | const Halfspace & | s, |
const Transform3s & | tf, | ||
KDOP< 18 > & | bv | ||
) |
Definition at line 656 of file geometric_shapes_utility.cpp.
void coal::computeBV< KDOP< 18 >, Plane > | ( | const Plane & | s, |
const Transform3s & | tf, | ||
KDOP< 18 > & | bv | ||
) |
Definition at line 910 of file geometric_shapes_utility.cpp.
void coal::computeBV< KDOP< 24 >, Halfspace > | ( | const Halfspace & | s, |
const Transform3s & | tf, | ||
KDOP< 24 > & | bv | ||
) |
Definition at line 722 of file geometric_shapes_utility.cpp.
void coal::computeBV< KDOP< 24 >, Plane > | ( | const Plane & | s, |
const Transform3s & | tf, | ||
KDOP< 24 > & | bv | ||
) |
Definition at line 958 of file geometric_shapes_utility.cpp.
void coal::computeBV< kIOS, Halfspace > | ( | const Halfspace & | s, |
const Transform3s & | tf, | ||
kIOS & | bv | ||
) |
Definition at line 583 of file geometric_shapes_utility.cpp.
void coal::computeBV< kIOS, Plane > | ( | const Plane & | s, |
const Transform3s & | tf, | ||
kIOS & | bv | ||
) |
Definition at line 852 of file geometric_shapes_utility.cpp.
void coal::computeBV< OBB, Box > | ( | const Box & | s, |
const Transform3s & | tf, | ||
OBB & | bv | ||
) |
Definition at line 458 of file geometric_shapes_utility.cpp.
void coal::computeBV< OBB, Capsule > | ( | const Capsule & | s, |
const Transform3s & | tf, | ||
OBB & | bv | ||
) |
Definition at line 485 of file geometric_shapes_utility.cpp.
void coal::computeBV< OBB, Cone > | ( | const Cone & | s, |
const Transform3s & | tf, | ||
OBB & | bv | ||
) |
Definition at line 499 of file geometric_shapes_utility.cpp.
void coal::computeBV< OBB, ConvexBase > | ( | const ConvexBase & | s, |
const Transform3s & | tf, | ||
OBB & | bv | ||
) |
Definition at line 528 of file geometric_shapes_utility.cpp.
void coal::computeBV< OBB, Cylinder > | ( | const Cylinder & | s, |
const Transform3s & | tf, | ||
OBB & | bv | ||
) |
Definition at line 513 of file geometric_shapes_utility.cpp.
void coal::computeBV< OBB, Halfspace > | ( | const Halfspace & | s, |
const Transform3s & | tf, | ||
OBB & | bv | ||
) |
Half space can only have very rough OBB
Half space can only have very rough OBB
Definition at line 545 of file geometric_shapes_utility.cpp.
void coal::computeBV< OBB, Plane > | ( | const Plane & | s, |
const Transform3s & | tf, | ||
OBB & | bv | ||
) |
n'd' = R * n * (d + (R * n) * T) = R * (n * d) + T
n'd' = R * n * (d + (R * n) * T) = R * (n * d) + T
Definition at line 803 of file geometric_shapes_utility.cpp.
void coal::computeBV< OBB, Sphere > | ( | const Sphere & | s, |
const Transform3s & | tf, | ||
OBB & | bv | ||
) |
Definition at line 472 of file geometric_shapes_utility.cpp.
void coal::computeBV< OBBRSS, Halfspace > | ( | const Halfspace & | s, |
const Transform3s & | tf, | ||
OBBRSS & | bv | ||
) |
Definition at line 572 of file geometric_shapes_utility.cpp.
void coal::computeBV< OBBRSS, Plane > | ( | const Plane & | s, |
const Transform3s & | tf, | ||
OBBRSS & | bv | ||
) |
Definition at line 841 of file geometric_shapes_utility.cpp.
void coal::computeBV< RSS, Halfspace > | ( | const Halfspace & | s, |
const Transform3s & | tf, | ||
RSS & | bv | ||
) |
Half space can only have very rough RSS
Half space can only have very rough RSS
Definition at line 558 of file geometric_shapes_utility.cpp.
void coal::computeBV< RSS, Plane > | ( | const Plane & | s, |
const Transform3s & | tf, | ||
RSS & | bv | ||
) |
Definition at line 821 of file geometric_shapes_utility.cpp.
|
inlinestatic |
compute the bounding volume of an octree node's i-th child
Definition at line 299 of file coal/octree.h.
void coal::computeContactPatch | ( | const CollisionGeometry * | o1, |
const Transform3s & | tf1, | ||
const CollisionGeometry * | o2, | ||
const Transform3s & | tf2, | ||
const CollisionResult & | collision_result, | ||
const ContactPatchRequest & | request, | ||
ContactPatchResult & | result | ||
) |
Main contact patch computation interface.
Definition at line 47 of file src/contact_patch.cpp.
void coal::computeContactPatch | ( | const CollisionObject * | o1, |
const CollisionObject * | o2, | ||
const CollisionResult & | collision_result, | ||
const ContactPatchRequest & | request, | ||
ContactPatchResult & | result | ||
) |
Definition at line 98 of file src/contact_patch.cpp.
size_t coal::computeMemoryFootprint | ( | const T & | object | ) |
Returns the memory footpring of the input object. For POD objects, this function returns the result of sizeof(T)
[in] | object | whose memory footprint needs to be evaluated. |
Definition at line 24 of file coal/serialization/memory.h.
void coal::computePatchPlaneOrHalfspace | ( | const OtherShapeType & | s1, |
const Transform3s & | tf1, | ||
const PlaneOrHalfspace & | s2, | ||
const Transform3s & | tf2, | ||
const ContactPatchSolver * | csolver, | ||
const Contact & | contact, | ||
ContactPatch & | contact_patch | ||
) |
Computes the contact patch between a Plane/Halfspace and another shape.
InvertShapes | set to true if the first shape of the collision pair is s2 and not s1 (if you had to invert (s1, tf1) and (s2, tf2) when calling this function). |
Definition at line 90 of file coal/internal/shape_shape_contact_patch_func.h.
void coal::computeSplitValue_bvcenter | ( | const BV & | bv, |
CoalScalar & | split_value | ||
) |
Definition at line 86 of file BV_splitter.cpp.
void coal::computeSplitValue_mean | ( | const BV & | , |
Vec3s * | vertices, | ||
Triangle * | triangles, | ||
unsigned int * | primitive_indices, | ||
unsigned int | num_primitives, | ||
BVHModelType | type, | ||
const Vec3s & | split_vector, | ||
CoalScalar & | split_value | ||
) |
Definition at line 92 of file BV_splitter.cpp.
void coal::computeSplitValue_median | ( | const BV & | , |
Vec3s * | vertices, | ||
Triangle * | triangles, | ||
unsigned int * | primitive_indices, | ||
unsigned int | num_primitives, | ||
BVHModelType | type, | ||
const Vec3s & | split_vector, | ||
CoalScalar & | split_value | ||
) |
Definition at line 121 of file BV_splitter.cpp.
void coal::computeSplitVector | ( | const BV & | bv, |
Vec3s & | split_vector | ||
) |
Definition at line 43 of file BV_splitter.cpp.
void coal::computeSplitVector< kIOS > | ( | const kIOS & | bv, |
Vec3s & | split_vector | ||
) |
Definition at line 48 of file BV_splitter.cpp.
void coal::computeSplitVector< OBBRSS > | ( | const OBBRSS & | bv, |
Vec3s & | split_vector | ||
) |
Definition at line 81 of file BV_splitter.cpp.
void coal::constructBox | ( | const AABB & | bv, |
Box & | box, | ||
Transform3s & | tf | ||
) |
construct a box shape (with a configuration) from a given bounding volume
Definition at line 1011 of file geometric_shapes_utility.cpp.
void coal::constructBox | ( | const AABB & | bv, |
const Transform3s & | tf_bv, | ||
Box & | box, | ||
Transform3s & | tf | ||
) |
Definition at line 1051 of file geometric_shapes_utility.cpp.
void coal::constructBox | ( | const KDOP< 16 > & | bv, |
Box & | box, | ||
Transform3s & | tf | ||
) |
Definition at line 1036 of file geometric_shapes_utility.cpp.
void coal::constructBox | ( | const KDOP< 16 > & | bv, |
const Transform3s & | tf_bv, | ||
Box & | box, | ||
Transform3s & | tf | ||
) |
Definition at line 1081 of file geometric_shapes_utility.cpp.
void coal::constructBox | ( | const KDOP< 18 > & | bv, |
Box & | box, | ||
Transform3s & | tf | ||
) |
Definition at line 1041 of file geometric_shapes_utility.cpp.
void coal::constructBox | ( | const KDOP< 18 > & | bv, |
const Transform3s & | tf_bv, | ||
Box & | box, | ||
Transform3s & | tf | ||
) |
Definition at line 1087 of file geometric_shapes_utility.cpp.
void coal::constructBox | ( | const KDOP< 24 > & | bv, |
Box & | box, | ||
Transform3s & | tf | ||
) |
Definition at line 1046 of file geometric_shapes_utility.cpp.
void coal::constructBox | ( | const KDOP< 24 > & | bv, |
const Transform3s & | tf_bv, | ||
Box & | box, | ||
Transform3s & | tf | ||
) |
Definition at line 1093 of file geometric_shapes_utility.cpp.
void coal::constructBox | ( | const kIOS & | bv, |
Box & | box, | ||
Transform3s & | tf | ||
) |
Definition at line 1026 of file geometric_shapes_utility.cpp.
void coal::constructBox | ( | const kIOS & | bv, |
const Transform3s & | tf_bv, | ||
Box & | box, | ||
Transform3s & | tf | ||
) |
Definition at line 1069 of file geometric_shapes_utility.cpp.
void coal::constructBox | ( | const OBB & | bv, |
Box & | box, | ||
Transform3s & | tf | ||
) |
Definition at line 1016 of file geometric_shapes_utility.cpp.
void coal::constructBox | ( | const OBB & | bv, |
const Transform3s & | tf_bv, | ||
Box & | box, | ||
Transform3s & | tf | ||
) |
Definition at line 1057 of file geometric_shapes_utility.cpp.
void coal::constructBox | ( | const OBBRSS & | bv, |
Box & | box, | ||
Transform3s & | tf | ||
) |
Definition at line 1021 of file geometric_shapes_utility.cpp.
void coal::constructBox | ( | const OBBRSS & | bv, |
const Transform3s & | tf_bv, | ||
Box & | box, | ||
Transform3s & | tf | ||
) |
Definition at line 1063 of file geometric_shapes_utility.cpp.
void coal::constructBox | ( | const RSS & | bv, |
Box & | box, | ||
Transform3s & | tf | ||
) |
Definition at line 1031 of file geometric_shapes_utility.cpp.
void coal::constructBox | ( | const RSS & | bv, |
const Transform3s & | tf_bv, | ||
Box & | box, | ||
Transform3s & | tf | ||
) |
Definition at line 1075 of file geometric_shapes_utility.cpp.
|
inline |
Construct a frame from a Contact
's position and normal. Because both Contact
's position and normal are expressed in the world frame, this frame is also expressed w.r.t the world frame. The origin of the frame is contact.pos
and the z-axis of the frame is contact.normal
.
Definition at line 704 of file coal/collision_data.h.
Construct othonormal basis from vector. The z-axis is the normalized input vector.
Definition at line 262 of file coal/math/transform.h.
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.
Definition at line 501 of file utility.cpp.
COAL_LOCAL void coal::contact_patch_function_not_implemented | ( | const CollisionGeometry * | o1, |
const Transform3s & | , | ||
const CollisionGeometry * | o2, | ||
const Transform3s & | , | ||
const CollisionResult & | , | ||
const ContactPatchSolver * | , | ||
const ContactPatchRequest & | , | ||
ContactPatchResult & | |||
) |
Definition at line 119 of file contact_patch_func_matrix.cpp.
|
inlinestatic |
Convert a bounding volume of type BV1 to bounding volume of type BV2 in identity configuration.
Definition at line 283 of file coal/BV/BV.h.
|
inlinestatic |
Convert a bounding volume of type BV1 in configuration tf1 to bounding volume of type BV2 in identity configuration.
Definition at line 276 of file coal/BV/BV.h.
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.
Default collision callback for two objects o1 and o2 in broad phase. return value means whether the broad phase can stop now.
This callback will cause the broadphase evaluation to stop if:
For a given instance of CollisionData, if broadphase evaluation has already terminated (i.e., defaultCollisionFunction() returned true
), subsequent invocations with the same instance of CollisionData will return immediately, requesting termination of broadphase evaluation (i.e., return true
).
o1 | The first object in the culled pair. |
o2 | The second object in the culled pair. |
data | A non-null pointer to a CollisionData instance. |
true
if the broadphase evaluation should stop. S | The scalar type with which the computation will be performed. |
Definition at line 42 of file default_broadphase_callbacks.cpp.
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).
Default distance callback for two objects o1 and o2 in broad phase. return value means whether the broad phase can stop now. also return dist, i.e. the bmin distance till now.
Provides a simple callback for the continuous collision query in the BroadPhaseCollisionManager. It assumes the data
parameter is non-null and points to an instance of DefaultContinuousCollisionData. It simply invokes the collide()
method on the culled pair of geometries and stores the results in the data's ContinuousCollisionResult instance.
This callback will never cause the broadphase evaluation to terminate early. However, if the done
member of the DefaultContinuousCollisionData is set to true, this method will simply return without doing any computation.
For a given instance of DefaultContinuousCollisionData, if broadphase evaluation has already terminated (i.e., DefaultContinuousCollisionFunction() returned true
), subsequent invocations with the same instance of CollisionData will return immediately, requesting termination of broadphase evaluation (i.e., return true
).
o1 | The first object in the culled pair. |
o2 | The second object in the culled pair. |
data | A non-null pointer to a CollisionData instance. |
S | The scalar type with which the computation will be performed. |
Provides a simple callback for the distance query in the BroadPhaseCollisionManager. It assumes the data
parameter is non-null and points to an instance of DistanceData. It simply invokes the distance()
method on the culled pair of geometries and stores the results in the data's DistanceResult instance.
This callback will cause the broadphase evaluation to stop if:
For a given instance of DistanceData, if broadphase evaluation has already terminated (i.e., defaultDistanceFunction() returned true
), subsequent invocations with the same instance of DistanceData will simply report the previously reported minimum distance and request termination of broadphase evaluation (i.e., return true
).
o1 | The first object in the culled pair. |
o2 | The second object in the culled pair. |
data | A non-null pointer to a DistanceData instance. |
dist | The distance computed by distance(). |
true
if the broadphase evaluation should stop. S | The scalar type with which the computation will be performed. |
Definition at line 66 of file default_broadphase_callbacks.cpp.
CoalScalar coal::distance | ( | const CollisionGeometry * | o1, |
const Transform3s & | tf1, | ||
const CollisionGeometry * | o2, | ||
const Transform3s & | tf2, | ||
const DistanceRequest & | request, | ||
DistanceResult & | result | ||
) |
Definition at line 59 of file src/distance.cpp.
CoalScalar coal::distance | ( | const CollisionObject * | o1, |
const CollisionObject * | o2, | ||
const DistanceRequest & | request, | ||
DistanceResult & | result | ||
) |
Main distance interface: given two collision objects, and the requirements for contacts, including whether return the nearest points, this function performs the distance between them. Return value is the minimum distance generated between the two objects.
Definition at line 52 of file src/distance.cpp.
void coal::distance | ( | DistanceTraversalNodeBase * | node, |
BVHFrontList * | front_list, | ||
unsigned int | qsize | ||
) |
Definition at line 79 of file collision_node.cpp.
COAL_LOCAL CoalScalar coal::distance_function_not_implemented | ( | const CollisionGeometry * | o1, |
const Transform3s & | , | ||
const CollisionGeometry * | o2, | ||
const Transform3s & | , | ||
const GJKSolver * | , | ||
const DistanceRequest & | , | ||
DistanceResult & | |||
) |
Definition at line 69 of file distance_func_matrix.cpp.
void coal::distanceQueueRecurse | ( | DistanceTraversalNodeBase * | node, |
unsigned int | b1, | ||
unsigned int | b2, | ||
BVHFrontList * | front_list, | ||
unsigned int | qsize | ||
) |
Definition at line 241 of file traversal_recurse.cpp.
void coal::distanceRecurse | ( | DistanceTraversalNodeBase * | node, |
unsigned int | b1, | ||
unsigned int | b2, | ||
BVHFrontList * | front_list | ||
) |
Recurse function for self collision Make sure node is set correctly so that the first and second tree are the same
Definition at line 152 of file traversal_recurse.cpp.
void coal::eigen | ( | const Eigen::MatrixBase< Derived > & | m, |
typename Derived::Scalar | dout[3], | ||
Vector * | vout | ||
) |
compute the eigen vector and eigen vector of a matrix. dout is the eigen values, vout is the eigen vectors
Definition at line 103 of file coal/internal/tools.h.
void coal::eulerToMatrix | ( | CoalScalar | a, |
CoalScalar | b, | ||
CoalScalar | c, | ||
Matrix3s & | R | ||
) |
Definition at line 198 of file utility.cpp.
CollisionGeometry * coal::extract | ( | const CollisionGeometry * | model, |
const Transform3s & | pose, | ||
const AABB & | aabb | ||
) |
Definition at line 66 of file collision_utility.cpp.
Definition at line 472 of file BV_fitter.cpp.
void coal::fit | ( | Vec3s * | ps, |
unsigned int | n, | ||
BV & | bv | ||
) |
Compute a bounding volume that fits a set of n points.
Definition at line 51 of file coal/internal/BV_fitter.h.
Definition at line 438 of file BV_fitter.cpp.
Definition at line 401 of file BV_fitter.cpp.
Definition at line 455 of file BV_fitter.cpp.
Definition at line 421 of file BV_fitter.cpp.
|
inline |
Definition at line 224 of file coal/math/transform.h.
void coal::generateBVHModel | ( | BVHModel< BV > & | model, |
const Box & | shape, | ||
const Transform3s & | pose | ||
) |
Generate BVH model from box.
Definition at line 49 of file coal/shape/geometric_shape_to_BVH_model.h.
void coal::generateBVHModel | ( | BVHModel< BV > & | model, |
const Cone & | shape, | ||
const Transform3s & | pose, | ||
unsigned int | tot, | ||
unsigned int | h_num | ||
) |
Generate BVH model from cone, given the number of segments along circle and the number of segments along axis.
Definition at line 264 of file coal/shape/geometric_shape_to_BVH_model.h.
void coal::generateBVHModel | ( | BVHModel< BV > & | model, |
const Cone & | shape, | ||
const Transform3s & | pose, | ||
unsigned int | tot_for_unit_cone | ||
) |
Generate BVH model from cone Difference from generateBVHModel: is that it gives the circle split number tot for a cylinder with unit radius. For cone with larger radius, the number of circle split number is r * tot.
Definition at line 337 of file coal/shape/geometric_shape_to_BVH_model.h.
void coal::generateBVHModel | ( | BVHModel< BV > & | model, |
const Cylinder & | shape, | ||
const Transform3s & | pose, | ||
unsigned int | tot, | ||
unsigned int | h_num | ||
) |
Generate BVH model from cylinder, given the number of segments along circle and the number of segments along axis.
Definition at line 172 of file coal/shape/geometric_shape_to_BVH_model.h.
void coal::generateBVHModel | ( | BVHModel< BV > & | model, |
const Cylinder & | shape, | ||
const Transform3s & | pose, | ||
unsigned int | tot_for_unit_cylinder | ||
) |
Generate BVH model from cylinder Difference from generateBVHModel: is that it gives the circle split number tot for a cylinder with unit radius. For cylinder with larger radius, the number of circle split number is r * tot.
Definition at line 245 of file coal/shape/geometric_shape_to_BVH_model.h.
void coal::generateBVHModel | ( | BVHModel< BV > & | model, |
const Sphere & | shape, | ||
const Transform3s & | pose, | ||
unsigned int | n_faces_for_unit_sphere | ||
) |
Generate BVH model from sphere The difference between generateBVHModel is that it gives the number of triangles faces N for a sphere with unit radius. For sphere of radius r, then the number of triangles is r * r * N so that the area represented by a single triangle is approximately the same.s.
Definition at line 157 of file coal/shape/geometric_shape_to_BVH_model.h.
void coal::generateBVHModel | ( | BVHModel< BV > & | model, |
const Sphere & | shape, | ||
const Transform3s & | pose, | ||
unsigned int | seg, | ||
unsigned int | ring | ||
) |
Generate BVH model from sphere, given the number of segments along longitude and number of rings along latitude.
Definition at line 91 of file coal/shape/geometric_shape_to_BVH_model.h.
void coal::generateCoordinateSystem | ( | const Eigen::MatrixBase< Derived1 > & | _w, |
const Eigen::MatrixBase< Derived2 > & | _u, | ||
const Eigen::MatrixBase< Derived3 > & | _v | ||
) |
Definition at line 59 of file coal/internal/tools.h.
void coal::generateEnvironments | ( | std::vector< CollisionObject * > & | env, |
CoalScalar | env_scale, | ||
std::size_t | n | ||
) |
Definition at line 392 of file utility.cpp.
void coal::generateEnvironmentsMesh | ( | std::vector< CollisionObject * > & | env, |
CoalScalar | env_scale, | ||
std::size_t | n | ||
) |
Definition at line 423 of file utility.cpp.
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].
Definition at line 210 of file utility.cpp.
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.
Definition at line 249 of file utility.cpp.
void coal::generateRandomTransforms | ( | CoalScalar | extents[6], |
std::vector< Transform3s > & | transforms, | ||
std::size_t | n | ||
) |
Generate n random transforms whose translations are constrained by extents.
Definition at line 226 of file utility.cpp.
|
inline |
Returns the name associated to a NODE_TYPE.
Definition at line 32 of file coal/collision_utility.h.
|
inline |
Returns the name associated to a OBJECT_TYPE.
Definition at line 47 of file coal/collision_utility.h.
CollisionFunctionMatrix& coal::getCollisionFunctionLookTable | ( | ) |
Definition at line 45 of file src/collision.cpp.
ContactPatchFunctionMatrix& coal::getContactPatchFunctionLookTable | ( | ) |
Definition at line 42 of file src/contact_patch.cpp.
void coal::getCovariance | ( | Vec3s * | ps, |
Vec3s * | ps2, | ||
Triangle * | ts, | ||
unsigned int * | indices, | ||
unsigned int | n, | ||
Matrix3s & | M | ||
) |
Compute the covariance matrix for a set or subset of points. if ts = null, then indices refer to points directly; otherwise refer to triangles.
Definition at line 182 of file BVH_utility.cpp.
DistanceFunctionMatrix& coal::getDistanceFunctionLookTable | ( | ) |
Definition at line 47 of file src/distance.cpp.
void coal::getDistances | ( | const Vec3s & | , |
CoalScalar * | |||
) |
|
inline |
|
inline |
|
inline |
void coal::getExtentAndCenter | ( | Vec3s * | ps, |
Vec3s * | ps2, | ||
Triangle * | ts, | ||
unsigned int * | indices, | ||
unsigned int | n, | ||
Matrix3s & | axes, | ||
Vec3s & | center, | ||
Vec3s & | extent | ||
) |
Compute the bounding volume extent and center for a set or subset of points, given the BV axises.
Definition at line 576 of file BVH_utility.cpp.
|
inlinestatic |
Compute the bounding volume extent and center for a set or subset of points. The bounding volume axes are known.
Definition at line 528 of file BVH_utility.cpp.
|
inlinestatic |
Compute the bounding volume extent and center for a set or subset of points. The bounding volume axes are known.
Definition at line 486 of file BVH_utility.cpp.
std::size_t coal::getNbRun | ( | const int & | argc, |
char const *const * | argv, | ||
std::size_t | defaultValue | ||
) |
Get the argument –nb-run from argv.
Definition at line 384 of file utility.cpp.
std::string coal::getNodeTypeName | ( | NODE_TYPE | node_type | ) |
Definition at line 327 of file utility.cpp.
void coal::getRadiusAndOriginAndRectangleSize | ( | Vec3s * | ps, |
Vec3s * | ps2, | ||
Triangle * | ts, | ||
unsigned int * | indices, | ||
unsigned int | n, | ||
const Matrix3s & | axes, | ||
Vec3s & | origin, | ||
CoalScalar | l[2], | ||
CoalScalar & | r | ||
) |
Compute the RSS bounding volume parameters: radius, rectangle size and the origin, given the BV axises.
Compute the RSS bounding volume parameters: radius, rectangle size and the origin. The bounding volume axes are known.
Definition at line 263 of file BVH_utility.cpp.
bool coal::inVoronoi | ( | CoalScalar | a, |
CoalScalar | b, | ||
CoalScalar | Anorm_dot_B, | ||
CoalScalar | Anorm_dot_T, | ||
CoalScalar | A_dot_B, | ||
CoalScalar | A_dot_T, | ||
CoalScalar | B_dot_T | ||
) |
Returns whether the nearest point on rectangle edge Pb + B*u, 0 <= u <= b, to the rectangle edge, Pa + A*t, 0 <= t <= a, is within the half space determined by the point Pa and the direction Anorm. A,B, and Anorm are unit vectors. T is the vector between Pa and Pb.
bool coal::isEqual | ( | const Eigen::MatrixBase< Derived > & | lhs, |
const Eigen::MatrixBase< OtherDerived > & | rhs, | ||
const CoalScalar | tol = std::numeric_limits<CoalScalar>::epsilon() * 100 |
||
) |
Definition at line 204 of file coal/internal/tools.h.
void coal::loadOBJFile | ( | const char * | filename, |
std::vector< Vec3s > & | points, | ||
std::vector< Triangle > & | triangles | ||
) |
Load an obj mesh file.
Definition at line 97 of file utility.cpp.
|
inline |
Read a mesh file and convert it to a polyhedral mesh.
[in] | resource_path | Path to the ressource mesh file to be read |
[in] | scale | Scale to apply when reading the ressource |
[out] | polyhedron | The resulted polyhedron |
Definition at line 116 of file coal/mesh_loader/assimp.h.
OcTreePtr_t coal::makeOctree | ( | const Eigen::Matrix< CoalScalar, Eigen::Dynamic, 3 > & | point_cloud, |
const CoalScalar | resolution | ||
) |
Build an OcTree from a point cloud and a given resolution.
[in] | point_cloud | The input points to insert in the OcTree |
[in] | resolution | of the octree. |
Definition at line 188 of file src/octree.cpp.
Quatf coal::makeQuat | ( | CoalScalar | w, |
CoalScalar | x, | ||
CoalScalar | y, | ||
CoalScalar | z | ||
) |
Definition at line 370 of file utility.cpp.
Box coal::makeRandomBox | ( | CoalScalar | min_size, |
CoalScalar | max_size | ||
) |
Definition at line 559 of file utility.cpp.
Capsule coal::makeRandomCapsule | ( | std::array< CoalScalar, 2 > | min_size, |
std::array< CoalScalar, 2 > | max_size | ||
) |
Definition at line 575 of file utility.cpp.
Cone coal::makeRandomCone | ( | std::array< CoalScalar, 2 > | min_size, |
std::array< CoalScalar, 2 > | max_size | ||
) |
Definition at line 581 of file utility.cpp.
Convex< Triangle > coal::makeRandomConvex | ( | CoalScalar | min_size, |
CoalScalar | max_size | ||
) |
Definition at line 593 of file utility.cpp.
Cylinder coal::makeRandomCylinder | ( | std::array< CoalScalar, 2 > | min_size, |
std::array< CoalScalar, 2 > | max_size | ||
) |
Definition at line 587 of file utility.cpp.
Ellipsoid coal::makeRandomEllipsoid | ( | CoalScalar | min_size, |
CoalScalar | max_size | ||
) |
Definition at line 569 of file utility.cpp.
Definition at line 607 of file utility.cpp.
Halfspace coal::makeRandomHalfspace | ( | CoalScalar | min_size, |
CoalScalar | max_size | ||
) |
Definition at line 602 of file utility.cpp.
Plane coal::makeRandomPlane | ( | CoalScalar | min_size, |
CoalScalar | max_size | ||
) |
Definition at line 598 of file utility.cpp.
Sphere coal::makeRandomSphere | ( | CoalScalar | min_size, |
CoalScalar | max_size | ||
) |
Definition at line 565 of file utility.cpp.
CoalScalar coal::maximumDistance | ( | Vec3s * | ps, |
Vec3s * | ps2, | ||
Triangle * | ts, | ||
unsigned int * | indices, | ||
unsigned int | n, | ||
const Vec3s & | query | ||
) |
Compute the maximum distance from a given center point to a point cloud.
Definition at line 659 of file BVH_utility.cpp.
|
inlinestatic |
Definition at line 599 of file BVH_utility.cpp.
|
inlinestatic |
Definition at line 634 of file BVH_utility.cpp.
|
inline |
|
inline |
bool coal::obbDisjointAndLowerBoundDistance | ( | const Matrix3s & | B, |
const Vec3s & | T, | ||
const Vec3s & | a_, | ||
const Vec3s & | b_, | ||
const CollisionRequest & | request, | ||
CoalScalar & | squaredLowerBoundDistance | ||
) |
|
inline |
Definition at line 1208 of file coal/collision_data.h.
|
inline |
Definition at line 1225 of file coal/collision_data.h.
|
inlinestatic |
Definition at line 49 of file coal/math/transform.h.
std::ostream& coal::operator<< | ( | std::ostream & | os, |
const Box & | b | ||
) |
Definition at line 74 of file test/geometric_shapes.cpp.
std::ostream& coal::operator<< | ( | std::ostream & | os, |
const ShapeBase & | |||
) |
Definition at line 70 of file test/geometric_shapes.cpp.
std::ostream & coal::operator<< | ( | std::ostream & | os, |
const Transform3s & | tf | ||
) |
Definition at line 379 of file utility.cpp.
|
inline |
Definition at line 1214 of file coal/collision_data.h.
|
inline |
Definition at line 1230 of file coal/collision_data.h.
|
inline |
Definition at line 1202 of file coal/collision_data.h.
|
inline |
Definition at line 1220 of file coal/collision_data.h.
|
inline |
Definition at line 1198 of file coal/collision_data.h.
void coal::propagateBVHFrontListCollisionRecurse | ( | CollisionTraversalNodeBase * | node, |
const CollisionRequest & | , | ||
CollisionResult & | result, | ||
BVHFrontList * | front_list | ||
) |
Definition at line 307 of file traversal_recurse.cpp.
CoalScalar coal::rand_interval | ( | CoalScalar | rmin, |
CoalScalar | rmax | ||
) |
Definition at line 92 of file utility.cpp.
CoalScalar coal::rectDistance | ( | const Matrix3s & | Rab, |
Vec3s const & | Tab, | ||
const CoalScalar | a[2], | ||
const CoalScalar | b[2], | ||
Vec3s * | P = NULL , |
||
Vec3s * | Q = NULL |
||
) |
void coal::relativeTransform | ( | const Eigen::MatrixBase< Derived > & | R1, |
const Eigen::MatrixBase< OtherDerived > & | t1, | ||
const Eigen::MatrixBase< Derived > & | R2, | ||
const Eigen::MatrixBase< OtherDerived > & | t2, | ||
const Eigen::MatrixBase< Derived > & | R, | ||
const Eigen::MatrixBase< OtherDerived > & | t | ||
) |
Definition at line 90 of file coal/internal/tools.h.
void coal::relativeTransform | ( | const Transform3s & | tf1, |
const Transform3s & | tf2, | ||
Transform3s & | tf | ||
) |
Definition at line 42 of file transform.cpp.
void coal::relativeTransform2 | ( | const Transform3s & | tf1, |
const Transform3s & | tf2, | ||
Transform3s & | tf | ||
) |
Definition at line 47 of file transform.cpp.
Definition at line 24 of file src/shape/convex.cpp.
void coal::saveOBJFile | ( | const char * | filename, |
std::vector< Vec3s > & | points, | ||
std::vector< Triangle > & | triangles | ||
) |
Definition at line 163 of file utility.cpp.
void coal::segCoords | ( | CoalScalar & | t, |
CoalScalar & | u, | ||
CoalScalar | a, | ||
CoalScalar | b, | ||
CoalScalar | A_dot_B, | ||
CoalScalar | A_dot_T, | ||
CoalScalar | B_dot_T | ||
) |
Finds the parameters t & u corresponding to the two closest points on a pair of line segments. The first segment is defined as Pa + A*t, 0 <= t <= a, where "Pa" is one endpoint of the segment, "A" is a unit vector pointing to the other endpoint, and t is a scalar that produces all the points between the two endpoints. Since "A" is a unit vector, "a" is the segment's length. The second segment is defined as Pb + B*u, 0 <= u <= b. Many of the terms needed by the algorithm are already computed for other purposes,so we just pass these terms into the function instead of complete specifications of each segment. "T" in the dot products is the vector betweeen Pa and Pb. Reference: "On fast computation of distance between line segments." Vladimir J. Lumelsky, in Information Processing Letters, no. 21, pages 55-61, 1985.
void coal::ShapeShapeContactPatch | ( | const CollisionGeometry * | o1, |
const Transform3s & | tf1, | ||
const CollisionGeometry * | o2, | ||
const Transform3s & | tf2, | ||
const CollisionResult & | collision_result, | ||
const ContactPatchSolver * | csolver, | ||
const ContactPatchRequest & | request, | ||
ContactPatchResult & | result | ||
) |
Definition at line 252 of file coal/internal/shape_shape_contact_patch_func.h.
Takes a point, projects it on the unit sphere and applies an ellipsoid transformation to it. A point x belongs to the surface of an ellipsoid if x^T * A * x = 1, where A = diag(1/r**2) with r being the radii of the ellipsoid. Thus, the point y = A^(1/2) * x belongs to the unit sphere if y * y = 1. Therefore, the tranformation which brings y to x is A^(-1/2) = diag(r).
Definition at line 494 of file utility.cpp.
void coal::toSphere | ( | Vec3s & | point | ) |
Takes a point and projects it onto the surface of the unit sphere.
Definition at line 483 of file utility.cpp.
Halfspace coal::transform | ( | const Halfspace & | a, |
const Transform3s & | tf | ||
) |
suppose the initial halfspace is n * x <= d after transform (R, T), x --> x' = R x + T and the new half space becomes n' * x' <= d' where n' = R * n and d' = d + n' * T
suppose the initial halfspace is n * x <= d after transform (R, T), x --> x' = R x + T and the new half space becomes n' * x' <= d' where n' = R * n and d' = d + n' * T
Definition at line 248 of file geometric_shapes_utility.cpp.
Plane coal::transform | ( | const Plane & | a, |
const Transform3s & | tf | ||
) |
suppose the initial halfspace is n * x <= d after transform (R, T), x --> x' = R x + T and the new half space becomes n' * x' <= d' where n' = R * n and d' = d + n' * T
suppose the initial halfspace is n * x <= d after transform (R, T), x --> x' = R x + T and the new half space becomes n' * x' <= d' where n' = R * n and d' = d + n' * T
Definition at line 263 of file geometric_shapes_utility.cpp.
std::array< Halfspace, 2 > coal::transformToHalfspaces | ( | const Plane & | a, |
const Transform3s & | tf | ||
) |
Definition at line 278 of file geometric_shapes_utility.cpp.
Definition at line 42 of file OBBRSS.cpp.
template KDOP<16> coal::translate< 16 > | ( | const KDOP< 16 > & | , |
const Vec3s & | |||
) |
template KDOP<18> coal::translate< 18 > | ( | const KDOP< 18 > & | , |
const Vec3s & | |||
) |
template KDOP<24> coal::translate< 24 > | ( | const KDOP< 24 > & | , |
const Vec3s & | |||
) |
|
inlinestatic |
Definition at line 52 of file coal/internal/tools.h.
|
inline |
Uniformly random quaternion sphere. Code taken from Pinocchio (https://github.com/stack-of-tasks/pinocchio).
Definition at line 231 of file coal/math/transform.h.
|
inline |
Add new front node into the front list.
Definition at line 69 of file coal/BVH/BVH_front.h.
|
static |
Definition at line 48 of file BV_fitter.cpp.
|
constexpr |
EPA EPA build a polytope which maximum size is:
#iterations + 4
vertices2 x #iterations + 4
faces Definition at line 59 of file coal/narrowphase/narrowphase_defaults.h.
|
constexpr |
Definition at line 60 of file coal/narrowphase/narrowphase_defaults.h.
|
constexpr |
Definition at line 61 of file coal/narrowphase/narrowphase_defaults.h.
|
constexpr |
GJK.
Definition at line 46 of file coal/narrowphase/narrowphase_defaults.h.
|
constexpr |
Definition at line 47 of file coal/narrowphase/narrowphase_defaults.h.
|
constexpr |
Note: if the considered shapes are on the order of the meter, and the convergence criterion of GJK is the default VDB criterion, setting a tolerance of 1e-6 on the GJK algorithm makes it precise up to the micro-meter. The same is true for EPA.
Definition at line 53 of file coal/narrowphase/narrowphase_defaults.h.
|
static |
Definition at line 47 of file BV_fitter.cpp.
|
static |
Definition at line 46 of file BV_fitter.cpp.
const Eigen::IOFormat coal::pyfmt |
Definition at line 85 of file utility.cpp.
COAL_DEPRECATED typedef Eigen::Quaternion<CoalScalar> coal::Quaternion3f |
Definition at line 46 of file coal/math/transform.h.
Definition at line 88 of file utility.cpp.
Definition at line 89 of file utility.cpp.
Definition at line 90 of file utility.cpp.
const Eigen::IOFormat coal::vfmt |
Definition at line 83 of file utility.cpp.