Main namespace. More...
Namespaces | |
detail | |
test | |
time | |
Namespace containing time datatypes and time operations. | |
Classes | |
class | AABB |
A class describing the AABB collision structure, which is a box in 3D space determined by two diagonal points. More... | |
class | aligned_allocator_cpp11 |
Aligned allocator that is compatible with c++11. More... | |
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... | |
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 | 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 | BVMotionBoundVisitor |
Compute the motion bound for a bounding volume, given the closest direction n between two query objects. More... | |
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 | Capsule |
Center at zero point capsule. 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 |
Parameters for performing collision request. More... | |
struct | CollisionResult |
collision result More... | |
class | Cone |
Center at zero cone. More... | |
struct | constants |
struct | Contact |
Contact information returned by collision. More... | |
struct | ContactPoint |
Minimal contact information returned by collision. More... | |
class | ContinuousCollisionObject |
the object for continuous collision or distance computation, contains the geometry and the motion information More... | |
struct | ContinuousCollisionRequest |
struct | ContinuousCollisionResult |
continuous collision result More... | |
class | Convex |
A convex polytope. More... | |
class | ConvexTester |
struct | CostSource |
Cost source describes an area with a cost. The area is described by an AABB | |
class | Cylinder |
Center at zero cylinder. More... | |
struct | DefaultCollisionData |
Collision data for use with the DefaultCollisionFunction. It stores the collision request and the result given by collision algorithm (and stores the conclusion of whether further evaluation of the broadphase collision manager has been deemed unnecessary). More... | |
struct | DefaultContinuousCollisionData |
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... | |
struct | DefaultDistanceData |
Distance data for use with the DefaultDistanceFunction. It stores the distance request and the result given by distance algorithm (and stores the conclusion of whether further evaluation of the broadphase collision manager has been deemed unnecessary). More... | |
struct | DistanceRequest |
request to the distance computation More... | |
struct | DistanceResult |
distance result More... | |
class | DummyCollisionObject |
Dummy collision object with a point AABB | |
class | DynamicAABBTreeCollisionManager |
class | DynamicAABBTreeCollisionManager_Array |
class | Ellipsoid |
Center at zero point ellipsoid. More... | |
class | Exception |
struct | GetDistancesImpl |
struct | GetDistancesImpl< S, 5 > |
struct | GetDistancesImpl< S, 6 > |
struct | GetDistancesImpl< S, 9 > |
struct | GetNodeTypeImpl |
struct | GetNodeTypeImpl< AABB< S > > |
struct | GetNodeTypeImpl< KDOP< S, 16 > > |
struct | GetNodeTypeImpl< KDOP< S, 18 > > |
struct | GetNodeTypeImpl< KDOP< S, 24 > > |
struct | GetNodeTypeImpl< kIOS< S > > |
struct | GetNodeTypeImpl< OBB< S > > |
struct | GetNodeTypeImpl< OBBRSS< S > > |
struct | GetNodeTypeImpl< RSS< S > > |
struct | GetOrientationImpl |
struct | GetOrientationImpl< S, OBB< S > > |
struct | GetOrientationImpl< S, OBBRSS< S > > |
struct | GetOrientationImpl< S, RSS< S > > |
class | Halfspace |
Half Space: this is equivalent to the Planed in ODE. 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. More... | |
struct | IMatrix3 |
class | InterpMotion |
Linear interpolation motion Each Motion is assumed to have constant linear velocity and angular velocity The motion is R(t)(p - p_ref) + p_ref + T(t) Therefore, R(0) = R0, R(1) = R1 T(0) = T0 + R0 p_ref - p_ref T(1) = T1 + R1 p_ref - p_ref. More... | |
struct | Interval |
Interval class for [a, b]. More... | |
class | IntervalTreeCollisionManager |
Collision manager based on interval tree. More... | |
struct | IntervalTreeCollisionManager< S > |
SAP end point. More... | |
struct | IVector3 |
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 | LibSVMClassifier |
struct | MakeParentRelativeRecurseImpl |
struct | MakeParentRelativeRecurseImpl< S, OBB< S > > |
struct | MakeParentRelativeRecurseImpl< S, OBBRSS< S > > |
struct | MakeParentRelativeRecurseImpl< S, RSS< S > > |
class | MotionBase |
class | NaiveCollisionManager |
Brute force N-body collision manager. More... | |
class | OBB |
Oriented bounding box class. More... | |
class | OBBRSS |
Class merging the OBB and RSS, can handle collision and distance simultaneously. More... | |
class | Plane |
Infinite plane. More... | |
class | RNG |
Random number generation. An instance of this class cannot be used by multiple threads at once (member functions are not const). However, the constructor is thread safe and different instances can be used safely in any number of threads. It is also guaranteed that all created instances will have a different random seed. More... | |
class | RSS |
A class for rectangle swept sphere bounding volume. More... | |
class | SamplerBase |
class | SamplerR |
class | SamplerSE2 |
class | SamplerSE2_disk |
class | SamplerSE3Euler |
class | SamplerSE3Euler_ball |
class | SamplerSE3Quat |
class | SamplerSE3Quat_ball |
class | SaPCollisionManager |
Rigorous SAP collision manager. More... | |
class | SaPCollisionManager< S > |
Functor to help unregister one object. More... | |
class | ScrewMotion |
class | ShapeBase |
Base class for all basic geometric shapes. More... | |
struct | SortByXLow |
Functor sorting objects according to the AABB | |
struct | SortByYLow |
Functor sorting objects according to the AABB | |
struct | SortByZLow |
Functor sorting objects according to the AABB | |
class | SpatialHashingCollisionManager |
spatial hashing collision mananger More... | |
class | Sphere |
Center at zero point sphere. More... | |
class | SplineMotion |
class | SSaPCollisionManager |
Simple SAP collision manager. More... | |
class | TaylorModel |
TaylorModel implements a third order Taylor model, i.e., a cubic approximation of a function over a time interval, with an interval remainder. All the operations on two Taylor models assume their time intervals are the same. More... | |
class | TBVMotionBoundVisitor |
struct | TBVMotionBoundVisitorVisitImpl |
struct | TBVMotionBoundVisitorVisitImpl< S, RSS< S >, InterpMotion< S > > |
Compute the motion bound for a bounding volume along a given direction n according to mu < |v * n| + ||w x n||(r + max(||ci*||)) where ||ci*|| = ||R0(ci) x w||. w is the angular axis (normalized) and ci are the endpoints of the generator primitives of RSS. Notice that all bv parameters are in the local frame of the object, but n should be in the global frame (the reason is that the motion (t1, t2 and t) is in global frame) More... | |
struct | TBVMotionBoundVisitorVisitImpl< S, RSS< S >, ScrewMotion< S > > |
Compute the motion bound for a bounding volume along a given direction n according to mu < |v * n| + ||w x n||(r + max(||ci*||)) where ||ci*|| = ||R0(ci) x w||. w is the angular axis (normalized) and ci are the endpoints of the generator primitives of RSS. Notice that all bv parameters are in the local frame of the object, but n should be in the global frame (the reason is that the motion (t1, t2 and t) is in global frame) More... | |
struct | TBVMotionBoundVisitorVisitImpl< S, RSS< S >, SplineMotion< S > > |
struct | TBVMotionBoundVisitorVisitImpl< S, RSS< S >, TranslationMotion< S > > |
Compute the motion bound for a bounding volume along a given direction n. More... | |
struct | TimeInterval |
class | TMatrix3 |
class | TranslationMotion |
class | Triangle |
Triangle with 3 indices for points. More... | |
class | TriangleMotionBoundVisitor |
struct | TriangleMotionBoundVisitorVisitImpl |
struct | TriangleMotionBoundVisitorVisitImpl< S, InterpMotion< S > > |
Compute the motion bound for a triangle along a given direction n according to mu < |v * n| + ||w x n||(max||ci*||) where ||ci*|| = ||R0(ci) x w|| / |w|. w is the angular velocity and ci are the triangle vertex coordinates. Notice that the triangle is in the local frame of the object, but n should be in the global frame (the reason is that the motion (t1, t2 and t) is in global frame) More... | |
struct | TriangleMotionBoundVisitorVisitImpl< S, ScrewMotion< S > > |
Compute the motion bound for a triangle along a given direction n according to mu < |v * n| + ||w x n||(max||ci*||) where ||ci*|| = ||R0(ci) x w|| / |w|. w is the angular velocity and ci are the triangle vertex coordinates. Notice that the triangle is in the local frame of the object, but n should be in the global frame (the reason is that the motion (t1, t2 and t) is in global frame) More... | |
struct | TriangleMotionBoundVisitorVisitImpl< S, SplineMotion< S > > |
struct | TriangleMotionBoundVisitorVisitImpl< S, TranslationMotion< S > > |
Compute the motion bound for a triangle along a given direction n. More... | |
class | TriangleP |
Triangle stores the points instead of only indices of points. More... | |
class | TVector3 |
class | Variance3 |
Class for variance matrix in 3d. More... | |
Typedefs | |
using | AABBd = AABB< double > |
using | AABBf = AABB< float > |
template<typename _Key , typename _Tp , typename _Compare = std::less<_Key>> | |
using | aligned_map = std::map< _Key, _Tp, _Compare, Eigen::aligned_allocator< std::pair< const _Key, _Tp > >> |
template<typename _Tp > | |
using | aligned_vector = std::vector< _Tp, Eigen::aligned_allocator< _Tp > > |
template<typename S > | |
using | AngleAxis = Eigen::AngleAxis< S > |
using | AngleAxisd = AngleAxis< double > |
using | AngleAxisf = AngleAxis< float > |
using | Boxd = Box< double > |
using | Boxf = Box< float > |
using | BroadPhaseCollisionManagerd = BroadPhaseCollisionManager< double > |
using | BroadPhaseCollisionManagerf = BroadPhaseCollisionManager< float > |
using | BroadPhaseContinuousCollisionManagerd = BroadPhaseContinuousCollisionManager< double > |
using | BroadPhaseContinuousCollisionManagerf = BroadPhaseContinuousCollisionManager< float > |
using | Capsuled = Capsule< double > |
using | Capsulef = Capsule< float > |
template<typename S > | |
using | CollisionCallBack = bool(*)(CollisionObject< S > *o1, CollisionObject< S > *o2, void *cdata) |
Callback for collision between two objects. Return value is whether can stop now. More... | |
using | CollisionGeometryd = CollisionGeometry< double > |
using | CollisionGeometryf = CollisionGeometry< float > |
using | CollisionObjectd = CollisionObject< double > |
using | CollisionObjectf = CollisionObject< float > |
using | CollisionRequestd = CollisionRequest< double > |
using | CollisionRequestf = CollisionRequest< float > |
using | CollisionResultd = CollisionResult< double > |
using | CollisionResultf = CollisionResult< float > |
using | Coned = Cone< double > |
using | Conef = Cone< float > |
using | constantsd = constants< double > |
using | constantsf = constants< float > |
using | Contactd = Contact< double > |
using | Contactf = Contact< float > |
using | ContactPointd = ContactPoint< double > |
using | ContactPointf = ContactPoint< float > |
template<typename S > | |
using | ContinuousCollisionCallBack = bool(*)(ContinuousCollisionObject< S > *o1, ContinuousCollisionObject< S > *o2, void *cdata) |
Callback for continuous collision between two objects. Return value is whether can stop now. More... | |
using | ContinuousCollisionObjectd = ContinuousCollisionObject< double > |
using | ContinuousCollisionObjectf = ContinuousCollisionObject< float > |
using | ContinuousCollisionRequestd = ContinuousCollisionRequest< double > |
using | ContinuousCollisionRequestf = ContinuousCollisionRequest< float > |
using | ContinuousCollisionResultd = ContinuousCollisionResult< double > |
using | ContinuousCollisionResultf = ContinuousCollisionResult< float > |
template<typename S > | |
using | ContinuousDistanceCallBack = bool(*)(ContinuousCollisionObject< S > *o1, ContinuousCollisionObject< S > *o2, void *cdata, S &dist) |
Callback for continuous distance between two objects, Return value is whether can stop now, also return the minimum distance till now. More... | |
using | Convexd = Convex< double > |
using | Convexf = Convex< float > |
using | CostSourced = CostSource< double > |
using | CostSourcef = CostSource< float > |
using | Cylinderd = Cylinder< double > |
using | Cylinderf = Cylinder< float > |
template<typename S > | |
using | DistanceCallBack = bool(*)(CollisionObject< S > *o1, CollisionObject< S > *o2, void *cdata, S &dist) |
Callback for distance between two objects, Return value is whether can stop now, also return the minimum distance till now. More... | |
using | DistanceRequestd = DistanceRequest< double > |
using | DistanceRequestf = DistanceRequest< float > |
using | DistanceResultd = DistanceResult< double > |
using | DistanceResultf = DistanceResult< float > |
using | DynamicAABBTreeCollisionManager_Arrayd = DynamicAABBTreeCollisionManager_Array< double > |
using | DynamicAABBTreeCollisionManager_Arrayf = DynamicAABBTreeCollisionManager_Array< float > |
using | DynamicAABBTreeCollisionManagerd = DynamicAABBTreeCollisionManager< double > |
using | DynamicAABBTreeCollisionManagerf = DynamicAABBTreeCollisionManager< float > |
using | Ellipsoidd = Ellipsoid< double > |
using | Ellipsoidf = Ellipsoid< float > |
typedef FCL_DEPRECATED std::int32_t | FCL_INT32 |
typedef FCL_DEPRECATED std::int64_t | FCL_INT64 |
typedef FCL_DEPRECATED double | FCL_REAL |
typedef FCL_DEPRECATED std::uint32_t | FCL_UINT32 |
typedef FCL_DEPRECATED std::uint64_t | FCL_UINT64 |
using | Halfspaced = Halfspace< double > |
using | Halfspacef = Halfspace< float > |
using | int32 = std::int32_t |
using | int64 = std::int64_t |
using | IntervalTreeCollisionManagerd = IntervalTreeCollisionManager< double > |
using | IntervalTreeCollisionManagerf = IntervalTreeCollisionManager< float > |
using | intptr_t = std::intptr_t |
template<std::size_t N> | |
using | KDOPd = KDOP< double, N > |
template<std::size_t N> | |
using | KDOPf = KDOP< float, N > |
using | kIOSd = kIOS< double > |
using | kIOSf = kIOS< float > |
template<typename S > | |
using | Matrix3 = Eigen::Matrix< S, 3, 3 > |
using | Matrix3d = Matrix3< double > |
using | Matrix3f = Matrix3< float > |
using | MotionBased = MotionBase< double > |
using | MotionBasef = MotionBase< float > |
template<typename S > | |
using | MotionBasePtr = std::shared_ptr< MotionBase< S > > |
using | NaiveCollisionManagerd = NaiveCollisionManager< double > |
using | NaiveCollisionManagerf = NaiveCollisionManager< float > |
using | OBBd = OBB< double > |
using | OBBf = OBB< float > |
using | OBBRSSd = OBBRSS< double > |
using | OBBRSSf = OBBRSS< float > |
using | Planed = Plane< double > |
using | Planef = Plane< float > |
template<typename S > | |
using | Quaternion = Eigen::Quaternion< S > |
using | Quaterniond = Quaternion< double > |
using | Quaternionf = Quaternion< float > |
using | RNGd = RNG< double > |
using | RNGf = RNG< float > |
using | RSSd = RSS< double > |
using | RSSf = RSS< float > |
template<std::size_t N> | |
using | SamplerRd = SamplerR< double, N > |
template<std::size_t N> | |
using | SamplerRf = SamplerR< float, N > |
using | SamplerSE2_diskd = SamplerSE2_disk< double > |
using | SamplerSE2_diskf = SamplerSE2_disk< float > |
using | SamplerSE2d = SamplerSE2< double > |
using | SamplerSE2f = SamplerSE2< float > |
using | SamplerSE3Euler_balld = SamplerSE3Euler_ball< double > |
using | SamplerSE3Euler_ballf = SamplerSE3Euler_ball< float > |
using | SamplerSE3Eulerd = SamplerSE3Euler< double > |
using | SamplerSE3Eulerf = SamplerSE3Euler< float > |
using | SamplerSE3Quat_balld = SamplerSE3Quat_ball< double > |
using | SamplerSE3Quat_ballf = SamplerSE3Quat_ball< float > |
using | SamplerSE3Quatd = SamplerSE3Quat< double > |
using | SamplerSE3Quatf = SamplerSE3Quat< float > |
using | SaPCollisionManagerd = SaPCollisionManager< double > |
using | SaPCollisionManagerf = SaPCollisionManager< float > |
using | ShapeBased = ShapeBase< double > |
using | ShapeBasef = ShapeBase< float > |
template<typename HashTable = detail::SimpleHashTable<AABB<double>, CollisionObject<double>*, detail::SpatialHash<double>>> | |
using | SpatialHashingCollisionManagerd = SpatialHashingCollisionManager< double, HashTable > |
template<typename HashTable = detail::SimpleHashTable<AABB<float>, CollisionObject<float>*, detail::SpatialHash<float>>> | |
using | SpatialHashingCollisionManagerf = SpatialHashingCollisionManager< float, HashTable > |
using | Sphered = Sphere< double > |
using | Spheref = Sphere< float > |
using | SSaPCollisionManagerd = SSaPCollisionManager< double > |
using | SSaPCollisionManagerf = SSaPCollisionManager< float > |
template<typename S > | |
using | Transform3 = Eigen::Transform< S, 3, Eigen::Isometry > |
using | Transform3d = Transform3< double > |
using | Transform3f = Transform3< float > |
template<typename S > | |
using | Translation3 = Eigen::Translation< S, 3 > |
using | Translation3d = Translation3< double > |
using | Translation3f = Translation3< float > |
using | TranslationMotiond = TranslationMotion< double > |
using | TranslationMotionf = TranslationMotion< float > |
using | TrianglePd = TriangleP< double > |
using | TrianglePf = TriangleP< float > |
using | uint32 = std::uint32_t |
using | uint64 = std::uint64_t |
using | uintptr_t = std::uintptr_t |
using | Variance3d = Variance3< double > |
using | Variance3f = Variance3< float > |
template<typename S > | |
using | Vector2 = Eigen::Matrix< S, 2, 1 > |
template<typename S > | |
using | Vector3 = Eigen::Matrix< S, 3, 1 > |
using | Vector3d = Vector3< double > |
using | Vector3f = Vector3< float > |
template<typename S > | |
using | Vector6 = Eigen::Matrix< S, 6, 1 > |
template<typename S > | |
using | Vector7 = Eigen::Matrix< S, 7, 1 > |
template<typename S , int N> | |
using | VectorN = Eigen::Matrix< S, N, 1 > |
template<int N> | |
using | VectorNd = VectorN< double, N > |
template<int N> | |
using | VectorNf = VectorN< float, N > |
template<typename S > | |
using | VectorX = Eigen::Matrix< S, Eigen::Dynamic, 1 > |
using | VectorXd = VectorX< double > |
using | VectorXf = VectorX< float > |
Functions | |
template<typename BV > | |
int | addTriangles (BVHModel< BV > &model, const std::vector< Vector3< typename BV::S >> &points, const std::vector< Triangle > &tri_indices, FinalizeModel finalize_model) |
template<typename S > | |
FCL_EXPORT void | axisFromEigen (const Matrix3< S > &eigenV, const Vector3< S > &eigenS, Matrix3< S > &axis) |
template<typename S > | |
FCL_EXPORT void | axisFromEigen (const Matrix3< S > &eigenV, const Vector3< S > &eigenS, Transform3< S > &tf) |
template void | axisFromEigen (const Matrix3d &eigenV, const Vector3d &eigenS, Matrix3d &axis) |
template void | axisFromEigen (const Matrix3d &eigenV, const Vector3d &eigenS, Transform3d &tf) |
template Interval< double > | bound (const Interval< double > &i, const Interval< double > &other) |
template Interval< double > | bound (const Interval< double > &i, double v) |
template<typename S > | |
FCL_EXPORT Interval< S > | bound (const Interval< S > &i, const Interval< S > &other) |
template<typename S > | |
Interval< S > | bound (const Interval< S > &i, const Interval< S > &other) |
template<typename S > | |
FCL_EXPORT Interval< S > | bound (const Interval< S > &i, S v) |
template<typename S > | |
Interval< S > | bound (const Interval< S > &i, S v) |
template IVector3< double > | bound (const IVector3< double > &i, const IVector3< double > &v) |
template IVector3< double > | bound (const IVector3< double > &i, const Vector3< double > &v) |
template<typename S > | |
FCL_EXPORT IVector3< S > | bound (const IVector3< S > &i, const IVector3< S > &v) |
template<typename S > | |
IVector3< S > | bound (const IVector3< S > &i, const IVector3< S > &v) |
template<typename S > | |
FCL_EXPORT IVector3< S > | bound (const IVector3< S > &i, const Vector3< S > &v) |
template<typename S > | |
IVector3< S > | bound (const IVector3< S > &i, const Vector3< S > &v) |
template<typename S , typename BV > | |
FCL_EXPORT void | BVHExpand (BVHModel< BV > &model, const Variance3< S > *ucs, S r) |
Expand the BVH bounding boxes according to the variance matrix corresponding to the data stored within each BV node. More... | |
template void | BVHExpand (BVHModel< OBB< double >> &model, const Variance3< double > *ucs, double r) |
template<typename S > | |
FCL_EXPORT void | BVHExpand (BVHModel< OBB< S >> &model, const Variance3< S > *ucs, S r=1.0) |
Expand the BVH bounding boxes according to the corresponding variance information, for OBB. More... | |
template void | BVHExpand (BVHModel< RSS< double >> &model, const Variance3< double > *ucs, double r) |
template<typename S > | |
FCL_EXPORT void | BVHExpand (BVHModel< RSS< S >> &model, const Variance3< S > *ucs, S r=1.0) |
Expand the BVH bounding boxes according to the corresponding variance information, for RSS. More... | |
template<typename S > | |
FCL_EXPORT void | circumCircleComputation (const Vector3< S > &a, const Vector3< S > &b, const Vector3< S > &c, Vector3< S > ¢er, S &radius) |
Compute the center and radius for a triangle's circumcircle. More... | |
template void | circumCircleComputation (const Vector3d &a, const Vector3d &b, const Vector3d &c, Vector3d ¢er, double &radius) |
template void | clipToRange (double &val, double a, double b) |
template<typename S > | |
FCL_EXPORT void | clipToRange (S &val, S a, S b) |
Clip value between a and b. More... | |
template<typename S > | |
void | clipToRange (S &val, S a, S b) |
Clip value between a and b. More... | |
template FCL_EXPORT std::size_t | collide (const CollisionGeometry< double > *o1, const Transform3< double > &tf1, const CollisionGeometry< double > *o2, const Transform3< double > &tf2, const CollisionRequest< double > &request, CollisionResult< double > &result) |
template<typename S > | |
FCL_EXPORT std::size_t | collide (const CollisionGeometry< S > *o1, const Transform3< S > &tf1, const CollisionGeometry< S > *o2, const Transform3< S > &tf2, const CollisionRequest< S > &request, CollisionResult< S > &result) |
template<typename S , typename NarrowPhaseSolver > | |
FCL_EXPORT std::size_t | collide (const CollisionGeometry< S > *o1, const Transform3< S > &tf1, const CollisionGeometry< S > *o2, const Transform3< S > &tf2, const NarrowPhaseSolver *nsolver_, const CollisionRequest< S > &request, CollisionResult< S > &result) |
template FCL_EXPORT std::size_t | collide (const CollisionObject< double > *o1, const CollisionObject< double > *o2, const CollisionRequest< double > &request, CollisionResult< double > &result) |
template<typename S > | |
FCL_EXPORT std::size_t | collide (const CollisionObject< S > *o1, const CollisionObject< S > *o2, const CollisionRequest< S > &request, CollisionResult< S > &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... | |
template<typename S , typename NarrowPhaseSolver > | |
FCL_EXPORT std::size_t | collide (const CollisionObject< S > *o1, const CollisionObject< S > *o2, const NarrowPhaseSolver *nsolver, const CollisionRequest< S > &request, CollisionResult< S > &result) |
template double | collide (const ContinuousCollisionObject< double > *o1, const ContinuousCollisionObject< double > *o2, const ContinuousCollisionRequest< double > &request, ContinuousCollisionResult< double > &result) |
template<typename S > | |
FCL_EXPORT S | collide (const ContinuousCollisionObject< S > *o1, const ContinuousCollisionObject< S > *o2, const ContinuousCollisionRequest< S > &request, ContinuousCollisionResult< S > &result) |
template<typename S , int M, int N> | |
FCL_EXPORT VectorN< S, M+N > | combine (const VectorN< S, M > &v1, const VectorN< S, N > &v2) |
template<typename DerivedA , typename DerivedB > | |
::testing::AssertionResult | CompareMatrices (const Eigen::MatrixBase< DerivedA > &m1, const Eigen::MatrixBase< DerivedB > &m2, double tolerance=0.0, MatrixCompareType compare_type=MatrixCompareType::absolute) |
template bool | comparePenDepth (const ContactPoint< double > &_cp1, const ContactPoint< double > &_cp2) |
template<typename S > | |
FCL_EXPORT bool | comparePenDepth (const ContactPoint< S > &_cp1, const ContactPoint< S > &_cp2) |
Return true if _cp1's penentration depth is less than _cp2's. More... | |
template<typename S > | |
bool | comparePenDepth (const ContactPoint< S > &_cp1, const ContactPoint< S > &_cp2) |
Return true if _cp1's penentration depth is less than _cp2's. More... | |
template<typename BV , typename Shape > | |
FCL_EXPORT void | computeBV (const Shape &s, const Transform3< typename BV::S > &tf, BV &bv) |
calculate a bounding volume for a shape in a specific configuration More... | |
template void | computeVertices (const OBB< double > &b, Vector3< double > vertices[8]) |
template<typename S > | |
FCL_EXPORT void | computeVertices (const OBB< S > &b, Vector3< S > vertices[8]) |
Compute the 8 vertices of a OBB. More... | |
template<typename S > | |
void | computeVertices (const OBB< S > &b, Vector3< S > vertices[8]) |
Compute the 8 vertices of a OBB. More... | |
template void | constructBox (const AABB< double > &bv, Box< double > &box, Transform3< double > &tf) |
template void | constructBox (const AABB< double > &bv, const Transform3< double > &tf_bv, Box< double > &box, Transform3< double > &tf) |
template<typename S > | |
FCL_EXPORT void | constructBox (const AABB< S > &bv, Box< S > &box, Transform3< S > &tf) |
construct a box shape (with a configuration) from a given bounding volume More... | |
template<typename S > | |
void | constructBox (const AABB< S > &bv, Box< S > &box, Transform3< S > &tf) |
construct a box shape (with a configuration) from a given bounding volume More... | |
template<typename S > | |
FCL_EXPORT void | constructBox (const AABB< S > &bv, const Transform3< S > &tf_bv, Box< S > &box, Transform3< S > &tf) |
template<typename S > | |
void | constructBox (const AABB< S > &bv, const Transform3< S > &tf_bv, Box< S > &box, Transform3< S > &tf) |
template void | constructBox (const KDOP< double, 16 > &bv, Box< double > &box, Transform3< double > &tf) |
template void | constructBox (const KDOP< double, 16 > &bv, const Transform3< double > &tf_bv, Box< double > &box, Transform3< double > &tf) |
template void | constructBox (const KDOP< double, 18 > &bv, Box< double > &box, Transform3< double > &tf) |
template void | constructBox (const KDOP< double, 18 > &bv, const Transform3< double > &tf_bv, Box< double > &box, Transform3< double > &tf) |
template void | constructBox (const KDOP< double, 24 > &bv, Box< double > &box, Transform3< double > &tf) |
template void | constructBox (const KDOP< double, 24 > &bv, const Transform3< double > &tf_bv, Box< double > &box, Transform3< double > &tf) |
template<typename S > | |
FCL_EXPORT void | constructBox (const KDOP< S, 16 > &bv, Box< S > &box, Transform3< S > &tf) |
template<typename S > | |
void | constructBox (const KDOP< S, 16 > &bv, Box< S > &box, Transform3< S > &tf) |
template<typename S > | |
FCL_EXPORT void | constructBox (const KDOP< S, 16 > &bv, const Transform3< S > &tf_bv, Box< S > &box, Transform3< S > &tf) |
template<typename S > | |
void | constructBox (const KDOP< S, 16 > &bv, const Transform3< S > &tf_bv, Box< S > &box, Transform3< S > &tf) |
template<typename S > | |
FCL_EXPORT void | constructBox (const KDOP< S, 18 > &bv, Box< S > &box, Transform3< S > &tf) |
template<typename S > | |
void | constructBox (const KDOP< S, 18 > &bv, Box< S > &box, Transform3< S > &tf) |
template<typename S > | |
FCL_EXPORT void | constructBox (const KDOP< S, 18 > &bv, const Transform3< S > &tf_bv, Box< S > &box, Transform3< S > &tf) |
template<typename S > | |
void | constructBox (const KDOP< S, 18 > &bv, const Transform3< S > &tf_bv, Box< S > &box, Transform3< S > &tf) |
template<typename S > | |
FCL_EXPORT void | constructBox (const KDOP< S, 24 > &bv, Box< S > &box, Transform3< S > &tf) |
template<typename S > | |
void | constructBox (const KDOP< S, 24 > &bv, Box< S > &box, Transform3< S > &tf) |
template<typename S > | |
FCL_EXPORT void | constructBox (const KDOP< S, 24 > &bv, const Transform3< S > &tf_bv, Box< S > &box, Transform3< S > &tf) |
template<typename S > | |
void | constructBox (const KDOP< S, 24 > &bv, const Transform3< S > &tf_bv, Box< S > &box, Transform3< S > &tf) |
template void | constructBox (const kIOS< double > &bv, Box< double > &box, Transform3< double > &tf) |
template void | constructBox (const kIOS< double > &bv, const Transform3< double > &tf_bv, Box< double > &box, Transform3< double > &tf) |
template<typename S > | |
FCL_EXPORT void | constructBox (const kIOS< S > &bv, Box< S > &box, Transform3< S > &tf) |
template<typename S > | |
void | constructBox (const kIOS< S > &bv, Box< S > &box, Transform3< S > &tf) |
template<typename S > | |
FCL_EXPORT void | constructBox (const kIOS< S > &bv, const Transform3< S > &tf_bv, Box< S > &box, Transform3< S > &tf) |
template<typename S > | |
void | constructBox (const kIOS< S > &bv, const Transform3< S > &tf_bv, Box< S > &box, Transform3< S > &tf) |
template void | constructBox (const OBB< double > &bv, Box< double > &box, Transform3< double > &tf) |
template void | constructBox (const OBB< double > &bv, const Transform3< double > &tf_bv, Box< double > &box, Transform3< double > &tf) |
template<typename S > | |
FCL_EXPORT void | constructBox (const OBB< S > &bv, Box< S > &box, Transform3< S > &tf) |
template<typename S > | |
void | constructBox (const OBB< S > &bv, Box< S > &box, Transform3< S > &tf) |
template<typename S > | |
FCL_EXPORT void | constructBox (const OBB< S > &bv, const Transform3< S > &tf_bv, Box< S > &box, Transform3< S > &tf) |
template<typename S > | |
void | constructBox (const OBB< S > &bv, const Transform3< S > &tf_bv, Box< S > &box, Transform3< S > &tf) |
template void | constructBox (const OBBRSS< double > &bv, Box< double > &box, Transform3< double > &tf) |
template void | constructBox (const OBBRSS< double > &bv, const Transform3< double > &tf_bv, Box< double > &box, Transform3< double > &tf) |
template<typename S > | |
FCL_EXPORT void | constructBox (const OBBRSS< S > &bv, Box< S > &box, Transform3< S > &tf) |
template<typename S > | |
void | constructBox (const OBBRSS< S > &bv, Box< S > &box, Transform3< S > &tf) |
template<typename S > | |
FCL_EXPORT void | constructBox (const OBBRSS< S > &bv, const Transform3< S > &tf_bv, Box< S > &box, Transform3< S > &tf) |
template<typename S > | |
void | constructBox (const OBBRSS< S > &bv, const Transform3< S > &tf_bv, Box< S > &box, Transform3< S > &tf) |
template void | constructBox (const RSS< double > &bv, Box< double > &box, Transform3< double > &tf) |
template void | constructBox (const RSS< double > &bv, const Transform3< double > &tf_bv, Box< double > &box, Transform3< double > &tf) |
template<typename S > | |
FCL_EXPORT void | constructBox (const RSS< S > &bv, Box< S > &box, Transform3< S > &tf) |
template<typename S > | |
void | constructBox (const RSS< S > &bv, Box< S > &box, Transform3< S > &tf) |
template<typename S > | |
FCL_EXPORT void | constructBox (const RSS< S > &bv, const Transform3< S > &tf_bv, Box< S > &box, Transform3< S > &tf) |
template<typename S > | |
void | constructBox (const RSS< S > &bv, const Transform3< S > &tf_bv, Box< S > &box, Transform3< S > &tf) |
template double | continuousCollide (const CollisionGeometry< double > *o1, const MotionBase< double > *motion1, const CollisionGeometry< double > *o2, const MotionBase< double > *motion2, const ContinuousCollisionRequest< double > &request, ContinuousCollisionResult< double > &result) |
template double | continuousCollide (const CollisionGeometry< double > *o1, const Transform3< double > &tf1_beg, const Transform3< double > &tf1_end, const CollisionGeometry< double > *o2, const Transform3< double > &tf2_beg, const Transform3< double > &tf2_end, const ContinuousCollisionRequest< double > &request, ContinuousCollisionResult< double > &result) |
template<typename S > | |
FCL_EXPORT S | continuousCollide (const CollisionGeometry< S > *o1, const MotionBase< S > *motion1, const CollisionGeometry< S > *o2, const MotionBase< S > *motion2, const ContinuousCollisionRequest< S > &request, ContinuousCollisionResult< S > &result) |
continous collision checking between two objects More... | |
template<typename S > | |
FCL_EXPORT S | continuousCollide (const CollisionGeometry< S > *o1, const Transform3< S > &tf1_beg, const Transform3< S > &tf1_end, const CollisionGeometry< S > *o2, const Transform3< S > &tf2_beg, const Transform3< S > &tf2_end, const ContinuousCollisionRequest< S > &request, ContinuousCollisionResult< S > &result) |
template double | continuousCollide (const CollisionObject< double > *o1, const Transform3< double > &tf1_end, const CollisionObject< double > *o2, const Transform3< double > &tf2_end, const ContinuousCollisionRequest< double > &request, ContinuousCollisionResult< double > &result) |
template<typename S > | |
FCL_EXPORT S | continuousCollide (const CollisionObject< S > *o1, const Transform3< S > &tf1_end, const CollisionObject< S > *o2, const Transform3< S > &tf2_end, const ContinuousCollisionRequest< S > &request, ContinuousCollisionResult< S > &result) |
template<typename S > | |
FCL_EXPORT S | continuousCollideBVHPolynomial (const CollisionGeometry< S > *o1, const TranslationMotion< S > *motion1, const CollisionGeometry< S > *o2, const TranslationMotion< S > *motion2, const ContinuousCollisionRequest< S > &request, ContinuousCollisionResult< S > &result) |
template<typename S > | |
FCL_EXPORT S | continuousCollideConservativeAdvancement (const CollisionGeometry< S > *o1, const MotionBase< S > *motion1, const CollisionGeometry< S > *o2, const MotionBase< S > *motion2, const ContinuousCollisionRequest< S > &request, ContinuousCollisionResult< S > &result) |
template<typename S > | |
FCL_EXPORT S | continuousCollideNaive (const CollisionGeometry< S > *o1, const MotionBase< S > *motion1, const CollisionGeometry< S > *o2, const MotionBase< S > *motion2, const ContinuousCollisionRequest< S > &request, ContinuousCollisionResult< S > &result) |
template<typename BV1 , typename BV2 > | |
FCL_EXPORT void | convertBV (const BV1 &bv1, const Transform3< typename BV1::S > &tf1, BV2 &bv2) |
Convert a bounding volume of type BV1 in configuration tf1 to bounding volume of type BV2 in identity configuration. More... | |
template<typename S > | |
bool | DefaultCollisionFunction (CollisionObject< S > *o1, CollisionObject< S > *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 DefaultCollisionData. It simply invokes the collide() method on the culled pair of geometries and stores the results in the data's CollisionResult instance. More... | |
template<typename S > | |
bool | DefaultContinuousCollisionFunction (ContinuousCollisionObject< S > *o1, ContinuousCollisionObject< S > *o2, void *data) |
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. More... | |
template<typename S > | |
bool | DefaultDistanceFunction (CollisionObject< S > *o1, CollisionObject< S > *o2, void *data, S &dist) |
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 DefaultDistanceData. It simply invokes the distance() method on the culled pair of geometries and stores the results in the data's DistanceResult instance. More... | |
template double | distance (const CollisionGeometry< double > *o1, const Transform3< double > &tf1, const CollisionGeometry< double > *o2, const Transform3< double > &tf2, const DistanceRequest< double > &request, DistanceResult< double > &result) |
template<typename S > | |
FCL_EXPORT S | distance (const CollisionGeometry< S > *o1, const Transform3< S > &tf1, const CollisionGeometry< S > *o2, const Transform3< S > &tf2, const DistanceRequest< S > &request, DistanceResult< S > &result) |
template<typename S > | |
S | distance (const CollisionGeometry< S > *o1, const Transform3< S > &tf1, const CollisionGeometry< S > *o2, const Transform3< S > &tf2, const DistanceRequest< S > &request, DistanceResult< S > &result) |
template<typename NarrowPhaseSolver > | |
NarrowPhaseSolver::S | distance (const CollisionGeometry< typename NarrowPhaseSolver::S > *o1, const Transform3< typename NarrowPhaseSolver::S > &tf1, const CollisionGeometry< typename NarrowPhaseSolver::S > *o2, const Transform3< typename NarrowPhaseSolver::S > &tf2, const NarrowPhaseSolver *nsolver_, const DistanceRequest< typename NarrowPhaseSolver::S > &request, DistanceResult< typename NarrowPhaseSolver::S > &result) |
template double | distance (const CollisionObject< double > *o1, const CollisionObject< double > *o2, const DistanceRequest< double > &request, DistanceResult< double > &result) |
template<typename S > | |
FCL_EXPORT S | distance (const CollisionObject< S > *o1, const CollisionObject< S > *o2, const DistanceRequest< S > &request, DistanceResult< S > &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... | |
template<typename S > | |
S | distance (const CollisionObject< S > *o1, const CollisionObject< S > *o2, const DistanceRequest< S > &request, DistanceResult< S > &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... | |
template<typename NarrowPhaseSolver > | |
NarrowPhaseSolver::S | distance (const CollisionObject< typename NarrowPhaseSolver::S > *o1, const CollisionObject< typename NarrowPhaseSolver::S > *o2, const NarrowPhaseSolver *nsolver, const DistanceRequest< typename NarrowPhaseSolver::S > &request, DistanceResult< typename NarrowPhaseSolver::S > &result) |
template<typename S , typename DerivedA , typename DerivedB > | |
S | distance (const Eigen::MatrixBase< DerivedA > &R0, const Eigen::MatrixBase< DerivedB > &T0, const kIOS< S > &b1, const kIOS< S > &b2, Vector3< S > *P, Vector3< S > *Q) |
Approximate distance between two kIOS bounding volumes. More... | |
template<typename S , typename DerivedA , typename DerivedB > | |
FCL_EXPORT S | distance (const Eigen::MatrixBase< DerivedA > &R0, const Eigen::MatrixBase< DerivedB > &T0, const kIOS< S > &b1, const kIOS< S > &b2, Vector3< S > *P=nullptr, Vector3< S > *Q=nullptr) |
Approximate distance between two kIOS bounding volumes. More... | |
template<typename S , typename DerivedA , typename DerivedB > | |
S | distance (const Eigen::MatrixBase< DerivedA > &R0, const Eigen::MatrixBase< DerivedB > &T0, const OBBRSS< S > &b1, const OBBRSS< S > &b2, Vector3< S > *P, Vector3< S > *Q) |
Computate distance between two OBBRSS, b1 is in configuation (R0, T0) and b2 is in indentity; P and Q, is not nullptr, returns the nearest points. More... | |
template<typename S , typename DerivedA , typename DerivedB > | |
FCL_EXPORT S | distance (const Eigen::MatrixBase< DerivedA > &R0, const Eigen::MatrixBase< DerivedB > &T0, const OBBRSS< S > &b1, const OBBRSS< S > &b2, Vector3< S > *P=nullptr, Vector3< S > *Q=nullptr) |
Computate distance between two OBBRSS, b1 is in configuation (R0, T0) and b2 is in indentity; P and Q, is not nullptr, returns the nearest points. More... | |
template<typename S , typename DerivedA , typename DerivedB > | |
S | distance (const Eigen::MatrixBase< DerivedA > &R0, const Eigen::MatrixBase< DerivedB > &T0, const RSS< S > &b1, const RSS< S > &b2, Vector3< S > *P, Vector3< S > *Q) |
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... | |
template<typename S , typename DerivedA , typename DerivedB > | |
FCL_EXPORT S | distance (const Eigen::MatrixBase< DerivedA > &R0, const Eigen::MatrixBase< DerivedB > &T0, const RSS< S > &b1, const RSS< S > &b2, Vector3< S > *P=nullptr, Vector3< S > *Q=nullptr) |
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... | |
template<typename S > | |
S | distance (const Transform3< S > &tf, const kIOS< S > &b1, const kIOS< S > &b2, Vector3< S > *P, Vector3< S > *Q) |
Approximate distance between two kIOS bounding volumes. More... | |
template<typename S > | |
FCL_EXPORT S | distance (const Transform3< S > &tf, const kIOS< S > &b1, const kIOS< S > &b2, Vector3< S > *P=nullptr, Vector3< S > *Q=nullptr) |
Approximate distance between two kIOS bounding volumes. More... | |
template<typename S > | |
FCL_EXPORT S | distance (const Transform3< S > &tf, const OBBRSS< S > &b1, const OBBRSS< S > &b2, Vector3< S > *P=nullptr, Vector3< S > *Q=nullptr) |
Computate distance between two OBBRSS, b1 is in configuation (R0, T0) and b2 is in indentity; P and Q, is not nullptr, returns the nearest points. More... | |
template<typename S > | |
FCL_EXPORT void | eigen (const Matrix3< S > &m, Vector3< S > &dout, Matrix3< S > &vout) |
compute the eigen vector and eigen vector of a matrix. dout is the eigen values, vout is the eigen vectors More... | |
template void | eigen (const Matrix3d &m, Vector3d &dout, Matrix3d &vout) |
template<typename S > | |
FCL_EXPORT void | eigen_old (const Matrix3< S > &m, Vector3< S > &dout, Matrix3< S > &vout) |
compute the eigen vector and eigen vector of a matrix. dout is the eigen values, vout is the eigen vectors More... | |
template void | eigen_old (const Matrix3d &m, Vector3d &dout, Matrix3d &vout) |
template<typename BV > | |
FCL_EXPORT void | fit (const Vector3< typename BV::S > *const ps, int n, BV &bv) |
Compute a bounding volume that fits a set of n points. More... | |
template void | flipNormal (std::vector< ContactPoint< double >> &contacts) |
template<typename S > | |
FCL_EXPORT void | flipNormal (std::vector< ContactPoint< S >> &contacts) |
template<typename S > | |
void | flipNormal (std::vector< ContactPoint< S >> &contacts) |
template<typename BV > | |
int | generateBVHModel (BVHModel< BV > &model, const Box< typename BV::S > &shape, const Transform3< typename BV::S > &pose, FinalizeModel finalize_model=FinalizeModel::DO) |
Generate BVH model from box. More... | |
template<typename BV > | |
int | generateBVHModel (BVHModel< BV > &model, const Cone< typename BV::S > &shape, const Transform3< typename BV::S > &pose, unsigned int circle_split_tot, unsigned int h_num, FinalizeModel finalize_model=FinalizeModel::DO) |
Generate BVH model from cone. More... | |
template<typename BV > | |
int | generateBVHModel (BVHModel< BV > &model, const Cone< typename BV::S > &shape, const Transform3< typename BV::S > &pose, unsigned int circle_split_tot_for_unit_cone, FinalizeModel finalize_model=FinalizeModel::DO) |
Generate BVH model from cone. More... | |
template<typename BV > | |
int | generateBVHModel (BVHModel< BV > &model, const Cylinder< typename BV::S > &shape, const Transform3< typename BV::S > &pose, unsigned int circle_split_tot, unsigned int h_num, FinalizeModel finalize_model=FinalizeModel::DO) |
Generate BVH model from cylinder, given the number of segments along circle and the number of segments along axis. More... | |
template<typename BV > | |
int | generateBVHModel (BVHModel< BV > &model, const Cylinder< typename BV::S > &shape, const Transform3< typename BV::S > &pose, unsigned int circle_split_tot_for_unit_cylinder, FinalizeModel finalize_model=FinalizeModel::DO) |
Generate BVH model from cylinder. More... | |
template<typename BV > | |
int | generateBVHModel (BVHModel< BV > &model, const Ellipsoid< typename BV::S > &shape, const Transform3< typename BV::S > &pose, unsigned int n_faces_for_unit_ellipsoid, FinalizeModel finalize_model=FinalizeModel::DO) |
Generate BVH model from ellipsoid. More... | |
template<typename BV > | |
int | generateBVHModel (BVHModel< BV > &model, const Ellipsoid< typename BV::S > &shape, const Transform3< typename BV::S > &pose, unsigned int seg, unsigned int ring, FinalizeModel finalize_model=FinalizeModel::DO) |
Generate BVH model from ellipsoid. More... | |
template<typename BV > | |
int | generateBVHModel (BVHModel< BV > &model, const Sphere< typename BV::S > &shape, const Transform3< typename BV::S > &pose, unsigned int n_faces_for_unit_sphere, FinalizeModel finalize_model=FinalizeModel::DO) |
Generate BVH model from sphere. More... | |
template<typename BV > | |
int | generateBVHModel (BVHModel< BV > &model, const Sphere< typename BV::S > &shape, const Transform3< typename BV::S > &pose, unsigned int seg, unsigned int ring, FinalizeModel finalize_model=FinalizeModel::DO) |
Generate BVH model from sphere. More... | |
template<typename S > | |
FCL_EXPORT Matrix3< S > | generateCoordinateSystem (const Vector3< S > &x_axis) |
compute orthogonal coordinate system basis with given x-axis. More... | |
template Matrix3d | generateCoordinateSystem (const Vector3d &x_axis) |
template void | generateTaylorModelForCosFunc (TaylorModel< double > &tm, double w, double q0) |
template<typename S > | |
FCL_EXPORT void | generateTaylorModelForCosFunc (TaylorModel< S > &tm, S w, S q0) |
Generate Taylor model for cos(w t + q0) More... | |
template<typename S > | |
void | generateTaylorModelForCosFunc (TaylorModel< S > &tm, S w, S q0) |
Generate Taylor model for cos(w t + q0) More... | |
template void | generateTaylorModelForLinearFunc (TaylorModel< double > &tm, double p, double v) |
template<typename S > | |
FCL_EXPORT void | generateTaylorModelForLinearFunc (TaylorModel< S > &tm, S p, S v) |
Generate Taylor model for p + v t. More... | |
template<typename S > | |
void | generateTaylorModelForLinearFunc (TaylorModel< S > &tm, S p, S v) |
Generate Taylor model for p + v t. More... | |
template void | generateTaylorModelForSinFunc (TaylorModel< double > &tm, double w, double q0) |
template<typename S > | |
FCL_EXPORT void | generateTaylorModelForSinFunc (TaylorModel< S > &tm, S w, S q0) |
Generate Taylor model for sin(w t + q0) More... | |
template<typename S > | |
void | generateTaylorModelForSinFunc (TaylorModel< S > &tm, S w, S q0) |
Generate Taylor model for sin(w t + q0) More... | |
template void | generateTVector3ForLinearFunc (TVector3< double > &v, const Vector3< double > &position, const Vector3< double > &velocity) |
template<typename S > | |
FCL_EXPORT void | generateTVector3ForLinearFunc (TVector3< S > &v, const Vector3< S > &position, const Vector3< S > &velocity) |
template<typename S > | |
void | generateTVector3ForLinearFunc (TVector3< S > &v, const Vector3< S > &position, const Vector3< S > &velocity) |
template<typename GJKSolver > | |
detail::CollisionFunctionMatrix< GJKSolver > & | getCollisionFunctionLookTable () |
template<typename GJKSolver > | |
detail::ConservativeAdvancementFunctionMatrix< GJKSolver > & | getConservativeAdvancementFunctionLookTable () |
template<typename S > | |
FCL_EXPORT void | getCovariance (const Vector3< S > *const ps, const Vector3< S > *const ps2, Triangle *ts, unsigned int *indices, int n, Matrix3< S > &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... | |
template void | getCovariance (const Vector3d *const ps, const Vector3d *const ps2, Triangle *ts, unsigned int *indices, int n, Matrix3d &M) |
template<typename GJKSolver > | |
detail::DistanceFunctionMatrix< GJKSolver > & | getDistanceFunctionLookTable () |
template<typename S , std::size_t N> | |
FCL_EXPORT void | getDistances (const Vector3< S > &p, S *d) |
Compute the distances to planes with normals from KDOP vectors except those of AABB face planes. More... | |
template void | getDistances< double, 5 > (const Vector3< double > &p, double *d) |
template void | getDistances< double, 6 > (const Vector3< double > &p, double *d) |
template void | getDistances< double, 9 > (const Vector3< double > &p, double *d) |
template<typename S > | |
FCL_EXPORT void | getExtentAndCenter (const Vector3< S > *const ps, const Vector3< S > *const ps2, Triangle *ts, unsigned int *indices, int n, const Matrix3< S > &axis, Vector3< S > ¢er, Vector3< S > &extent) |
Compute the bounding volume extent and center for a set or subset of points, given the BV axises. More... | |
template<typename S > | |
FCL_EXPORT void | getExtentAndCenter (const Vector3< S > *const ps, const Vector3< S > *const ps2, Triangle *ts, unsigned int *indices, int n, Transform3< S > &tf, Vector3< S > &extent) |
Compute the bounding volume extent and center for a set or subset of points, given the BV axises. More... | |
template void | getExtentAndCenter (const Vector3d *const ps, const Vector3d *const ps2, Triangle *ts, unsigned int *indices, int n, const Matrix3d &axis, Vector3d ¢er, Vector3d &extent) |
template<typename S > | |
FCL_EXPORT MotionBasePtr< S > | getMotionBase (const Transform3< S > &tf_beg, const Transform3< S > &tf_end, CCDMotionType motion_type) |
template<typename S > | |
FCL_EXPORT void | getRadiusAndOriginAndRectangleSize (const Vector3< S > *const ps, const Vector3< S > *const ps2, Triangle *ts, unsigned int *indices, int n, const Matrix3< S > &axis, Vector3< S > &origin, S l[2], S &r) |
Compute the RSS bounding volume parameters: radius, rectangle size and the origin, given the BV axises. More... | |
template<typename S > | |
FCL_EXPORT void | getRadiusAndOriginAndRectangleSize (const Vector3< S > *const ps, const Vector3< S > *const ps2, Triangle *ts, unsigned int *indices, int n, Transform3< S > &tf, S l[2], S &r) |
Compute the RSS bounding volume parameters: radius, rectangle size and the origin, given the BV axises. More... | |
template void | getRadiusAndOriginAndRectangleSize (const Vector3d *const ps, const Vector3d *const ps2, Triangle *ts, unsigned int *indices, int n, const Matrix3d &axis, Vector3d &origin, double l[2], double &r) |
template void | getRadiusAndOriginAndRectangleSize (const Vector3d *const ps, const Vector3d *const ps2, Triangle *ts, unsigned int *indices, int n, Transform3d &tf, double l[2], double &r) |
template<typename S > | |
FCL_EXPORT void | hat (Matrix3< S > &mat, const Vector3< S > &vec) |
template void | hat (Matrix3d &mat, const Vector3d &vec) |
template bool | inVoronoi (double a, double b, double Anorm_dot_B, double Anorm_dot_T, double A_dot_B, double A_dot_T, double B_dot_T) |
template<typename S > | |
FCL_EXPORT bool | inVoronoi (S a, S b, S Anorm_dot_B, S Anorm_dot_T, S A_dot_B, S A_dot_T, S 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 S > | |
bool | inVoronoi (S a, S b, S Anorm_dot_B, S Anorm_dot_T, S A_dot_B, S A_dot_T, S 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 _Tp , typename... _Args> | |
std::shared_ptr< _Tp > | make_aligned_shared (_Args &&... __args) |
template<typename S > | |
FCL_EXPORT S | maximumDistance (const Vector3< S > *const ps, const Vector3< S > *const ps2, Triangle *ts, unsigned int *indices, int n, const Vector3< S > &query) |
Compute the maximum distance from a given center point to a point cloud. More... | |
template double | maximumDistance (const Vector3d *const ps, const Vector3d *const ps2, Triangle *ts, unsigned int *indices, int n, const Vector3d &query) |
template OBB< double > | merge_largedist (const OBB< double > &b1, const OBB< double > &b2) |
template<typename S > | |
FCL_EXPORT OBB< S > | merge_largedist (const OBB< S > &b1, const OBB< S > &b2) |
OBB merge method when the centers of two smaller OBB are far away. More... | |
template<typename S > | |
OBB< S > | merge_largedist (const OBB< S > &b1, const OBB< S > &b2) |
OBB merge method when the centers of two smaller OBB are far away. More... | |
template OBB< double > | merge_smalldist (const OBB< double > &b1, const OBB< double > &b2) |
template<typename S > | |
FCL_EXPORT OBB< S > | merge_smalldist (const OBB< S > &b1, const OBB< S > &b2) |
OBB merge method when the centers of two smaller OBB are close. More... | |
template<typename S > | |
OBB< S > | merge_smalldist (const OBB< S > &b1, const OBB< S > &b2) |
OBB merge method when the centers of two smaller OBB are close. More... | |
template void | minmax (double a, double b, double &minv, double &maxv) |
template void | minmax (double p, double &minv, double &maxv) |
template<typename S > | |
FCL_EXPORT void | minmax (S a, S b, S &minv, S &maxv) |
Find the smaller and larger one of two values. More... | |
template<typename S > | |
FCL_EXPORT void | minmax (S p, S &minv, S &maxv) |
Merge the interval [minv, maxv] and value p/. More... | |
template<typename S > | |
FCL_EXPORT void | normalize (Vector3< S > &v, bool *signal) |
template void | normalize (Vector3d &v, bool *signal) |
template bool | obbDisjoint (const Matrix3< double > &B, const Vector3< double > &T, const Vector3< double > &a, const Vector3< double > &b) |
template<typename S > | |
FCL_EXPORT bool | obbDisjoint (const Matrix3< S > &B, const Vector3< S > &T, const Vector3< S > &a, const Vector3< S > &b) |
Check collision between two boxes: the first box is in configuration (R, T) and its half dimension is set by a; the second box is in identity configuration and its half dimension is set by b. More... | |
template<typename S > | |
bool | obbDisjoint (const Matrix3< S > &B, const Vector3< S > &T, const Vector3< S > &a, const Vector3< S > &b) |
Check collision between two boxes: the first box is in configuration (R, T) and its half dimension is set by a; the second box is in identity configuration and its half dimension is set by b. More... | |
template bool | obbDisjoint (const Transform3< double > &tf, const Vector3< double > &a, const Vector3< double > &b) |
template<typename S > | |
FCL_EXPORT bool | obbDisjoint (const Transform3< S > &tf, const Vector3< S > &a, const Vector3< S > &b) |
Check collision between two boxes: the first box is in configuration (R, T) and its half dimension is set by a; the second box is in identity configuration and its half dimension is set by b. More... | |
template<typename S > | |
bool | obbDisjoint (const Transform3< S > &tf, const Vector3< S > &a, const Vector3< S > &b) |
Check collision between two boxes: the first box is in configuration (R, T) and its half dimension is set by a; the second box is in identity configuration and its half dimension is set by b. More... | |
template TMatrix3< double > | operator* (const Matrix3< double > &m, const TaylorModel< double > &a) |
template<typename S > | |
FCL_EXPORT TMatrix3< S > | operator* (const Matrix3< S > &m, const TaylorModel< S > &a) |
template<typename S > | |
TMatrix3< S > | operator* (const Matrix3< S > &m, const TaylorModel< S > &a) |
template TMatrix3< double > | operator* (const TaylorModel< double > &a, const Matrix3< double > &m) |
template TMatrix3< double > | operator* (const TaylorModel< double > &a, const TMatrix3< double > &m) |
template<typename S > | |
FCL_EXPORT TMatrix3< S > | operator* (const TaylorModel< S > &a, const Matrix3< S > &m) |
template<typename S > | |
TMatrix3< S > | operator* (const TaylorModel< S > &a, const Matrix3< S > &m) |
template<typename S > | |
FCL_EXPORT TMatrix3< S > | operator* (const TaylorModel< S > &a, const TMatrix3< S > &m) |
template<typename S > | |
TMatrix3< S > | operator* (const TaylorModel< S > &a, const TMatrix3< S > &m) |
template TVector3< double > | operator* (const Vector3< double > &v, const TaylorModel< double > &a) |
template<typename S > | |
FCL_EXPORT TVector3< S > | operator* (const Vector3< S > &v, const TaylorModel< S > &a) |
template<typename S > | |
TVector3< S > | operator* (const Vector3< S > &v, const TaylorModel< S > &a) |
template TaylorModel< double > | operator* (double d, const TaylorModel< double > &a) |
template TMatrix3< double > | operator* (double d, const TMatrix3< double > &m) |
template<typename S > | |
FCL_EXPORT TaylorModel< S > | operator* (S d, const TaylorModel< S > &a) |
template<typename S > | |
TaylorModel< S > | operator* (S d, const TaylorModel< S > &a) |
template<typename S > | |
FCL_EXPORT TMatrix3< S > | operator* (S d, const TMatrix3< S > &m) |
template<typename S > | |
TMatrix3< S > | operator* (S d, const TMatrix3< S > &m) |
template TMatrix3< double > | operator+ (const Matrix3< double > &m1, const TMatrix3< double > &m2) |
template<typename S > | |
FCL_EXPORT TMatrix3< S > | operator+ (const Matrix3< S > &m1, const TMatrix3< S > &m2) |
template<typename S > | |
TMatrix3< S > | operator+ (const Matrix3< S > &m1, const TMatrix3< S > &m2) |
template TVector3< double > | operator+ (const Vector3< double > &v1, const TVector3< double > &v2) |
template<typename S > | |
FCL_EXPORT TVector3< S > | operator+ (const Vector3< S > &v1, const TVector3< S > &v2) |
template<typename S > | |
TVector3< S > | operator+ (const Vector3< S > &v1, const TVector3< S > &v2) |
template TaylorModel< double > | operator+ (double d, const TaylorModel< double > &a) |
template<typename S > | |
FCL_EXPORT TaylorModel< S > | operator+ (S d, const TaylorModel< S > &a) |
template<typename S > | |
TaylorModel< S > | operator+ (S d, const TaylorModel< S > &a) |
template TMatrix3< double > | operator- (const Matrix3< double > &m1, const TMatrix3< double > &m2) |
template<typename S > | |
FCL_EXPORT TMatrix3< S > | operator- (const Matrix3< S > &m1, const TMatrix3< S > &m2) |
template<typename S > | |
TMatrix3< S > | operator- (const Matrix3< S > &m1, const TMatrix3< S > &m2) |
template TVector3< double > | operator- (const Vector3< double > &v1, const TVector3< double > &v2) |
template<typename S > | |
FCL_EXPORT TVector3< S > | operator- (const Vector3< S > &v1, const TVector3< S > &v2) |
template<typename S > | |
TVector3< S > | operator- (const Vector3< S > &v1, const TVector3< S > &v2) |
template TaylorModel< double > | operator- (double d, const TaylorModel< double > &a) |
template<typename S > | |
FCL_EXPORT TaylorModel< S > | operator- (S d, const TaylorModel< S > &a) |
template<typename S > | |
TaylorModel< S > | operator- (S d, const TaylorModel< S > &a) |
std::ostream & | operator<< (std::ostream &out, const NODE_TYPE &node) |
template<typename S , typename DerivedA , typename DerivedB > | |
FCL_EXPORT bool | overlap (const Eigen::MatrixBase< DerivedA > &R0, const Eigen::MatrixBase< DerivedB > &T0, const kIOS< S > &b1, const kIOS< S > &b2) |
Check collision between two kIOSs, b1 is in configuration (R0, T0) and b2 is in identity. More... | |
template<typename S , typename DerivedA , typename DerivedB > | |
bool | overlap (const Eigen::MatrixBase< DerivedA > &R0, const Eigen::MatrixBase< DerivedB > &T0, const kIOS< S > &b1, const kIOS< S > &b2) |
Check collision between two kIOSs, b1 is in configuration (R0, T0) and b2 is in identity. More... | |
template<typename S , typename DerivedA , typename DerivedB > | |
FCL_EXPORT bool | overlap (const Eigen::MatrixBase< DerivedA > &R0, const Eigen::MatrixBase< DerivedB > &T0, const OBB< S > &b1, const OBB< S > &b2) |
Check collision between two obbs, b1 is in configuration (R0, T0) and b2 is in identity. More... | |
template<typename S , typename DerivedA , typename DerivedB > | |
bool | overlap (const Eigen::MatrixBase< DerivedA > &R0, const Eigen::MatrixBase< DerivedB > &T0, const OBB< S > &b1, const OBB< S > &b2) |
Check collision between two obbs, b1 is in configuration (R0, T0) and b2 is in identity. More... | |
template<typename S , typename DerivedA , typename DerivedB > | |
FCL_EXPORT bool | overlap (const Eigen::MatrixBase< DerivedA > &R0, const Eigen::MatrixBase< DerivedB > &T0, const OBBRSS< S > &b1, const OBBRSS< S > &b2) |
Check collision between two OBBRSS, b1 is in configuration (R0, T0) and b2 is in indentity. More... | |
template<typename S , typename DerivedA , typename DerivedB > | |
bool | overlap (const Eigen::MatrixBase< DerivedA > &R0, const Eigen::MatrixBase< DerivedB > &T0, const OBBRSS< S > &b1, const OBBRSS< S > &b2) |
Check collision between two OBBRSS, b1 is in configuration (R0, T0) and b2 is in indentity. More... | |
template<typename S , typename DerivedA , typename DerivedB > | |
FCL_EXPORT bool | overlap (const Eigen::MatrixBase< DerivedA > &R0, const Eigen::MatrixBase< DerivedB > &T0, const RSS< S > &b1, const RSS< S > &b2) |
Check collision between two RSSs, b1 is in configuration (R0, T0) and b2 is in identity. More... | |
template<typename S , typename DerivedA , typename DerivedB > | |
bool | overlap (const Eigen::MatrixBase< DerivedA > &R0, const Eigen::MatrixBase< DerivedB > &T0, const RSS< S > &b1, const RSS< S > &b2) |
Check collision between two RSSs, b1 is in configuration (R0, T0) and b2 is in identity. More... | |
template<typename S > | |
FCL_EXPORT bool | overlap (const Transform3< S > &tf, const kIOS< S > &b1, const kIOS< S > &b2) |
Check collision between two kIOSs, b1 is in configuration (R0, T0) and b2 is in identity. More... | |
template<typename S > | |
FCL_EXPORT bool | overlap (const Transform3< S > &tf, const OBBRSS< S > &b1, const OBBRSS< S > &b2) |
Check collision between two OBBRSS, b1 is in configuration (R0, T0) and b2 is in indentity. More... | |
template double | rectDistance (const Matrix3< double > &Rab, const Vector3< double > &Tab, const double a[2], const double b[2], Vector3< double > *P, Vector3< double > *Q) |
template<typename S > | |
FCL_EXPORT S | rectDistance (const Matrix3< S > &Rab, const Vector3< S > &Tab, const S a[2], const S b[2], Vector3< S > *P=nullptr, Vector3< S > *Q=nullptr) |
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 S > | |
S | rectDistance (const Matrix3< S > &Rab, Vector3< S > const &Tab, const S a[2], const S b[2], Vector3< S > *P, Vector3< S > *Q) |
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 double | rectDistance (const Transform3< double > &tfab, const double a[2], const double b[2], Vector3< double > *P, Vector3< double > *Q) |
template<typename S > | |
S | rectDistance (const Transform3< S > &tfab, const S a[2], const S b[2], Vector3< S > *P, Vector3< S > *Q) |
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 S > | |
FCL_EXPORT S | rectDistance (const Transform3< S > &tfab, const S a[2], const S b[2], Vector3< S > *P=nullptr, Vector3< S > *Q=nullptr) |
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 DerivedA , typename DerivedB , typename DerivedC , typename DerivedD > | |
FCL_EXPORT void | relativeTransform (const Eigen::MatrixBase< DerivedA > &R1, const Eigen::MatrixBase< DerivedB > &t1, const Eigen::MatrixBase< DerivedA > &R2, const Eigen::MatrixBase< DerivedB > &t2, Eigen::MatrixBase< DerivedC > &R, Eigen::MatrixBase< DerivedD > &t) |
template<typename S , typename DerivedA , typename DerivedB > | |
FCL_EXPORT void | relativeTransform (const Eigen::Transform< S, 3, Eigen::Isometry > &T1, const Eigen::Transform< S, 3, Eigen::Isometry > &T2, Eigen::MatrixBase< DerivedA > &R, Eigen::MatrixBase< DerivedB > &t) |
template<typename S , typename DerivedA , typename DerivedB > | |
FCL_EXPORT void | relativeTransform (const Transform3< S > &T1, const Transform3< S > &T2, Eigen::MatrixBase< DerivedA > &R, Eigen::MatrixBase< DerivedB > &t) |
template IMatrix3< double > | rotationConstrain (const IMatrix3< double > &m) |
template<typename S > | |
FCL_EXPORT IMatrix3< S > | rotationConstrain (const IMatrix3< S > &m) |
template<typename S > | |
IMatrix3< S > | rotationConstrain (const IMatrix3< S > &m) |
template TMatrix3< double > | rotationConstrain (const TMatrix3< double > &m) |
template<typename S > | |
FCL_EXPORT TMatrix3< S > | rotationConstrain (const TMatrix3< S > &m) |
template<typename S > | |
TMatrix3< S > | rotationConstrain (const TMatrix3< S > &m) |
template void | segCoords (double &t, double &u, double a, double b, double A_dot_B, double A_dot_T, double B_dot_T) |
template<typename S > | |
FCL_EXPORT void | segCoords (S &t, S &u, S a, S b, S A_dot_B, S A_dot_T, S 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 S > | |
void | segCoords (S &t, S &u, S a, S b, S A_dot_B, S A_dot_T, S 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 Halfspace< double > | transform (const Halfspace< double > &a, const Transform3< double > &tf) |
template<typename S > | |
FCL_EXPORT Halfspace< S > | transform (const Halfspace< S > &a, const Transform3< S > &tf) |
template<typename S > | |
Halfspace< S > | transform (const Halfspace< S > &a, const Transform3< S > &tf) |
template Plane< double > | transform (const Plane< double > &a, const Transform3< double > &tf) |
template<typename S > | |
FCL_EXPORT Plane< S > | transform (const Plane< S > &a, const Transform3< S > &tf) |
template<typename S > | |
Plane< S > | transform (const Plane< S > &a, const Transform3< S > &tf) |
template<typename S , typename Derived > | |
AABB< S > | translate (const AABB< S > &aabb, const Eigen::MatrixBase< Derived > &t) |
translate the center of AABB by t More... | |
template<typename S , std::size_t N, typename Derived > | |
FCL_EXPORT KDOP< S, N > | translate (const KDOP< S, N > &bv, const Eigen::MatrixBase< Derived > &t) |
translate the KDOP BV More... | |
template<typename S , typename Derived > | |
FCL_EXPORT kIOS< S > | translate (const kIOS< S > &bv, const Eigen::MatrixBase< Derived > &t) |
Translate the kIOS BV. More... | |
template<typename S , typename Derived > | |
kIOS< S > | translate (const kIOS< S > &bv, const Eigen::MatrixBase< Derived > &t) |
Translate the kIOS BV. More... | |
template<typename S , typename Derived > | |
FCL_EXPORT OBB< S > | translate (const OBB< S > &bv, const Eigen::MatrixBase< Derived > &t) |
Translate the OBB bv. More... | |
template<typename S , typename Derived > | |
OBB< S > | translate (const OBB< S > &bv, const Eigen::MatrixBase< Derived > &t) |
Translate the OBB bv. More... | |
template OBBRSS< double > | translate (const OBBRSS< double > &bv, const Vector3< double > &t) |
template<typename S > | |
FCL_EXPORT OBBRSS< S > | translate (const OBBRSS< S > &bv, const Vector3< S > &t) |
Translate the OBBRSS bv. More... | |
template<typename S > | |
OBBRSS< S > | translate (const OBBRSS< S > &bv, const Vector3< S > &t) |
Translate the OBBRSS bv. More... | |
template RSS< double > | translate (const RSS< double > &bv, const Vector3< double > &t) |
template<typename S > | |
FCL_EXPORT RSS< S > | translate (const RSS< S > &bv, const Vector3< S > &t) |
Translate the RSS bv. More... | |
template<typename S > | |
RSS< S > | translate (const RSS< S > &bv, const Vector3< S > &t) |
Translate the RSS bv. More... | |
template<typename Derived > | |
FCL_EXPORT Derived::RealScalar | triple (const Eigen::MatrixBase< Derived > &x, const Eigen::MatrixBase< Derived > &y, const Eigen::MatrixBase< Derived > &z) |
Variables | |
template class FCL_EXPORT | AABB< double > |
template class FCL_EXPORT | Box< double > |
template class FCL_EXPORT | BroadPhaseCollisionManager< double > |
template class FCL_EXPORT | BroadPhaseContinuousCollisionManager< double > |
template class FCL_EXPORT | Capsule< double > |
template class FCL_EXPORT | CollisionGeometry< double > |
template class FCL_EXPORT | CollisionObject< double > |
template class FCL_EXPORT | Cone< double > |
template class FCL_EXPORT | ContinuousCollisionObject< double > |
template class FCL_EXPORT | Convex< double > |
template class FCL_EXPORT | Cylinder< double > |
template class FCL_EXPORT | DynamicAABBTreeCollisionManager< double > |
template class FCL_EXPORT | DynamicAABBTreeCollisionManager_Array< double > |
template class FCL_EXPORT | Ellipsoid< double > |
template class FCL_EXPORT | Halfspace< double > |
template class FCL_EXPORT | InterpMotion< double > |
template class FCL_EXPORT | IntervalTreeCollisionManager< double > |
template class FCL_EXPORT | KDOP< double, 16 > |
template class FCL_EXPORT | KDOP< double, 18 > |
template class FCL_EXPORT | KDOP< double, 24 > |
template class FCL_EXPORT | kIOS< double > |
template class FCL_EXPORT | MotionBase< double > |
template class FCL_EXPORT | NaiveCollisionManager< double > |
template class FCL_EXPORT | OBB< double > |
template class FCL_EXPORT | OBBRSS< double > |
template class FCL_EXPORT | Plane< double > |
template class FCL_EXPORT | RNG< double > |
template class FCL_EXPORT | RSS< double > |
template class FCL_EXPORT | SamplerBase< double > |
template class FCL_EXPORT | SamplerSE2< double > |
template class FCL_EXPORT | SamplerSE2_disk< double > |
template class FCL_EXPORT | SamplerSE3Euler< double > |
template class FCL_EXPORT | SamplerSE3Euler_ball< double > |
template class FCL_EXPORT | SamplerSE3Quat< double > |
template class FCL_EXPORT | SamplerSE3Quat_ball< double > |
template class FCL_EXPORT | SaPCollisionManager< double > |
template class FCL_EXPORT | ScrewMotion< double > |
template class FCL_EXPORT | ShapeBase< double > |
template class FCL_EXPORT | Sphere< double > |
template class FCL_EXPORT | SplineMotion< double > |
template class FCL_EXPORT | SSaPCollisionManager< double > |
template class FCL_EXPORT | TaylorModel< double > |
template class FCL_EXPORT | TMatrix3< double > |
template class FCL_EXPORT | TranslationMotion< double > |
template class FCL_EXPORT | TriangleMotionBoundVisitor< double > |
template class FCL_EXPORT | TriangleP< double > |
template class FCL_EXPORT | TVector3< double > |
template class FCL_EXPORT | Variance3< double > |
Main namespace.
collision and distance function on traversal nodes. these functions provide a higher level abstraction for collision functions provided in collision_func_matrix
using fcl::AABBd = typedef AABB<double> |
using fcl::AABBf = typedef AABB<float> |
using fcl::aligned_map = typedef std::map<_Key, _Tp, _Compare, Eigen::aligned_allocator<std::pair<const _Key, _Tp> >> |
using fcl::aligned_vector = typedef std::vector<_Tp, Eigen::aligned_allocator<_Tp> > |
using fcl::AngleAxis = typedef Eigen::AngleAxis<S> |
using fcl::AngleAxisd = typedef AngleAxis<double> |
using fcl::AngleAxisf = typedef AngleAxis<float> |
using fcl::BroadPhaseCollisionManagerd = typedef BroadPhaseCollisionManager<double> |
Definition at line 137 of file broadphase_collision_manager.h.
using fcl::BroadPhaseCollisionManagerf = typedef BroadPhaseCollisionManager<float> |
Definition at line 136 of file broadphase_collision_manager.h.
using fcl::BroadPhaseContinuousCollisionManagerd = typedef BroadPhaseContinuousCollisionManager<double> |
Definition at line 126 of file broadphase_continuous_collision_manager.h.
using fcl::BroadPhaseContinuousCollisionManagerf = typedef BroadPhaseContinuousCollisionManager<float> |
Definition at line 125 of file broadphase_continuous_collision_manager.h.
using fcl::Capsuled = typedef Capsule<double> |
using fcl::Capsulef = typedef Capsule<float> |
using fcl::CollisionCallBack = typedef bool (*)( CollisionObject<S>* o1, CollisionObject<S>* o2, void* cdata) |
Callback for collision between two objects. Return value is whether can stop now.
Definition at line 53 of file broadphase_collision_manager.h.
using fcl::CollisionGeometryd = typedef CollisionGeometry<double> |
Definition at line 125 of file collision_geometry.h.
using fcl::CollisionGeometryf = typedef CollisionGeometry<float> |
Definition at line 124 of file collision_geometry.h.
using fcl::CollisionObjectd = typedef CollisionObject<double> |
Definition at line 160 of file collision_object.h.
using fcl::CollisionObjectf = typedef CollisionObject<float> |
Definition at line 159 of file collision_object.h.
using fcl::CollisionRequestd = typedef CollisionRequest<double> |
Definition at line 109 of file collision_request.h.
using fcl::CollisionRequestf = typedef CollisionRequest<float> |
Definition at line 108 of file collision_request.h.
using fcl::CollisionResultd = typedef CollisionResult<double> |
Definition at line 96 of file collision_result.h.
using fcl::CollisionResultf = typedef CollisionResult<float> |
Definition at line 95 of file collision_result.h.
using fcl::Coned = typedef Cone<double> |
using fcl::Conef = typedef Cone<float> |
using fcl::constantsd = typedef constants<double> |
Definition at line 184 of file constants.h.
using fcl::constantsf = typedef constants<float> |
Definition at line 183 of file constants.h.
using fcl::Contactd = typedef Contact<double> |
using fcl::Contactf = typedef Contact<float> |
using fcl::ContactPointd = typedef ContactPoint<double> |
Definition at line 67 of file contact_point.h.
using fcl::ContactPointf = typedef ContactPoint<float> |
Definition at line 66 of file contact_point.h.
using fcl::ContinuousCollisionCallBack = typedef bool (*)( ContinuousCollisionObject<S>* o1, ContinuousCollisionObject<S>* o2, void* cdata) |
Callback for continuous collision between two objects. Return value is whether can stop now.
Definition at line 53 of file broadphase_continuous_collision_manager.h.
using fcl::ContinuousCollisionObjectd = typedef ContinuousCollisionObject<double> |
Definition at line 106 of file continuous_collision_object.h.
using fcl::ContinuousCollisionObjectf = typedef ContinuousCollisionObject<float> |
Definition at line 105 of file continuous_collision_object.h.
using fcl::ContinuousCollisionRequestd = typedef ContinuousCollisionRequest<double> |
Definition at line 78 of file continuous_collision_request.h.
using fcl::ContinuousCollisionRequestf = typedef ContinuousCollisionRequest<float> |
Definition at line 77 of file continuous_collision_request.h.
using fcl::ContinuousCollisionResultd = typedef ContinuousCollisionResult<double> |
Definition at line 66 of file continuous_collision_result.h.
using fcl::ContinuousCollisionResultf = typedef ContinuousCollisionResult<float> |
Definition at line 65 of file continuous_collision_result.h.
using fcl::ContinuousDistanceCallBack = typedef bool (*)( ContinuousCollisionObject<S>* o1, ContinuousCollisionObject<S>* o2, void* cdata, 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 60 of file broadphase_continuous_collision_manager.h.
using fcl::Convexd = typedef Convex<double> |
using fcl::Convexf = typedef Convex<float> |
using fcl::CostSourced = typedef CostSource<double> |
Definition at line 72 of file cost_source.h.
using fcl::CostSourcef = typedef CostSource<float> |
Definition at line 71 of file cost_source.h.
using fcl::Cylinderd = typedef Cylinder<double> |
Definition at line 97 of file cylinder.h.
using fcl::Cylinderf = typedef Cylinder<float> |
Definition at line 96 of file cylinder.h.
using fcl::DistanceCallBack = typedef bool (*)( CollisionObject<S>* o1, CollisionObject<S>* o2, void* cdata, S& dist) |
Callback for distance between two objects, Return value is whether can stop now, also return the minimum distance till now.
Definition at line 60 of file broadphase_collision_manager.h.
using fcl::DistanceRequestd = typedef DistanceRequest<double> |
Definition at line 116 of file distance_request.h.
using fcl::DistanceRequestf = typedef DistanceRequest<float> |
Definition at line 115 of file distance_request.h.
using fcl::DistanceResultd = typedef DistanceResult<double> |
Definition at line 110 of file distance_result.h.
using fcl::DistanceResultf = typedef DistanceResult<float> |
Definition at line 109 of file distance_result.h.
using fcl::DynamicAABBTreeCollisionManager_Arrayd = typedef DynamicAABBTreeCollisionManager_Array<double> |
Definition at line 136 of file broadphase_dynamic_AABB_tree_array.h.
using fcl::DynamicAABBTreeCollisionManager_Arrayf = typedef DynamicAABBTreeCollisionManager_Array<float> |
Definition at line 135 of file broadphase_dynamic_AABB_tree_array.h.
using fcl::DynamicAABBTreeCollisionManagerd = typedef DynamicAABBTreeCollisionManager<double> |
Definition at line 135 of file broadphase_dynamic_AABB_tree.h.
using fcl::DynamicAABBTreeCollisionManagerf = typedef DynamicAABBTreeCollisionManager<float> |
Definition at line 134 of file broadphase_dynamic_AABB_tree.h.
using fcl::Ellipsoidd = typedef Ellipsoid<double> |
Definition at line 97 of file ellipsoid.h.
using fcl::Ellipsoidf = typedef Ellipsoid<float> |
Definition at line 96 of file ellipsoid.h.
typedef FCL_DEPRECATED std::int32_t fcl::FCL_INT32 |
typedef FCL_DEPRECATED std::int64_t fcl::FCL_INT64 |
typedef FCL_DEPRECATED double fcl::FCL_REAL |
typedef FCL_DEPRECATED std::uint32_t fcl::FCL_UINT32 |
typedef FCL_DEPRECATED std::uint64_t fcl::FCL_UINT64 |
using fcl::Halfspaced = typedef Halfspace<double> |
Definition at line 111 of file geometry/shape/halfspace.h.
using fcl::Halfspacef = typedef Halfspace<float> |
Definition at line 110 of file geometry/shape/halfspace.h.
using fcl::int32 = typedef std::int32_t |
using fcl::int64 = typedef std::int64_t |
using fcl::IntervalTreeCollisionManagerd = typedef IntervalTreeCollisionManager<double> |
Definition at line 146 of file broadphase_interval_tree.h.
using fcl::IntervalTreeCollisionManagerf = typedef IntervalTreeCollisionManager<float> |
Definition at line 145 of file broadphase_interval_tree.h.
using fcl::intptr_t = typedef std::intptr_t |
using fcl::KDOPd = typedef KDOP<double, N> |
using fcl::KDOPf = typedef KDOP<float, N> |
using fcl::kIOSd = typedef kIOS<double> |
using fcl::kIOSf = typedef kIOS<float> |
using fcl::Matrix3 = typedef Eigen::Matrix<S, 3, 3> |
using fcl::Matrix3d = typedef Matrix3<double> |
using fcl::Matrix3f = typedef Matrix3<float> |
using fcl::MotionBased = typedef MotionBase<double> |
Definition at line 94 of file motion_base.h.
using fcl::MotionBasef = typedef MotionBase<float> |
Definition at line 93 of file motion_base.h.
using fcl::MotionBasePtr = typedef std::shared_ptr<MotionBase<S> > |
Definition at line 97 of file motion_base.h.
using fcl::NaiveCollisionManagerd = typedef NaiveCollisionManager<double> |
Definition at line 106 of file broadphase_bruteforce.h.
using fcl::NaiveCollisionManagerf = typedef NaiveCollisionManager<float> |
Definition at line 105 of file broadphase_bruteforce.h.
using fcl::OBBRSSd = typedef OBBRSS<double> |
using fcl::OBBRSSf = typedef OBBRSS<float> |
using fcl::Planed = typedef Plane<double> |
Definition at line 101 of file geometry/shape/plane.h.
using fcl::Planef = typedef Plane<float> |
Definition at line 100 of file geometry/shape/plane.h.
using fcl::Quaternion = typedef Eigen::Quaternion<S> |
using fcl::Quaterniond = typedef Quaternion<double> |
using fcl::Quaternionf = typedef Quaternion<float> |
using fcl::SamplerRd = typedef SamplerR<double, N> |
Definition at line 77 of file sampler_r.h.
using fcl::SamplerRf = typedef SamplerR<float, N> |
Definition at line 75 of file sampler_r.h.
using fcl::SamplerSE2_diskd = typedef SamplerSE2_disk<double> |
Definition at line 70 of file sampler_se2_disk.h.
using fcl::SamplerSE2_diskf = typedef SamplerSE2_disk<float> |
Definition at line 69 of file sampler_se2_disk.h.
using fcl::SamplerSE2d = typedef SamplerSE2<double> |
Definition at line 78 of file sampler_se2.h.
using fcl::SamplerSE2f = typedef SamplerSE2<float> |
Definition at line 77 of file sampler_se2.h.
using fcl::SamplerSE3Euler_balld = typedef SamplerSE3Euler_ball<double> |
Definition at line 67 of file sampler_se3_euler_ball.h.
using fcl::SamplerSE3Euler_ballf = typedef SamplerSE3Euler_ball<float> |
Definition at line 66 of file sampler_se3_euler_ball.h.
using fcl::SamplerSE3Eulerd = typedef SamplerSE3Euler<double> |
Definition at line 71 of file sampler_se3_euler.h.
using fcl::SamplerSE3Eulerf = typedef SamplerSE3Euler<float> |
Definition at line 70 of file sampler_se3_euler.h.
using fcl::SamplerSE3Quat_balld = typedef SamplerSE3Quat_ball<double> |
Definition at line 66 of file sampler_se3_quat_ball.h.
using fcl::SamplerSE3Quat_ballf = typedef SamplerSE3Quat_ball<float> |
Definition at line 65 of file sampler_se3_quat_ball.h.
using fcl::SamplerSE3Quatd = typedef SamplerSE3Quat<double> |
Definition at line 71 of file sampler_se3_quat.h.
using fcl::SamplerSE3Quatf = typedef SamplerSE3Quat<float> |
Definition at line 70 of file sampler_se3_quat.h.
using fcl::SaPCollisionManagerd = typedef SaPCollisionManager<double> |
Definition at line 157 of file broadphase_SaP.h.
using fcl::SaPCollisionManagerf = typedef SaPCollisionManager<float> |
Definition at line 156 of file broadphase_SaP.h.
using fcl::ShapeBased = typedef ShapeBase<double> |
Definition at line 61 of file shape_base.h.
using fcl::ShapeBasef = typedef ShapeBase<float> |
Definition at line 60 of file shape_base.h.
using fcl::SpatialHashingCollisionManagerd = typedef SpatialHashingCollisionManager<double, HashTable> |
Definition at line 168 of file broadphase_spatialhash.h.
using fcl::SpatialHashingCollisionManagerf = typedef SpatialHashingCollisionManager<float, HashTable> |
Definition at line 165 of file broadphase_spatialhash.h.
using fcl::Sphered = typedef Sphere<double> |
using fcl::Spheref = typedef Sphere<float> |
using fcl::SSaPCollisionManagerd = typedef SSaPCollisionManager<double> |
Definition at line 130 of file broadphase_SSaP.h.
using fcl::SSaPCollisionManagerf = typedef SSaPCollisionManager<float> |
Definition at line 129 of file broadphase_SSaP.h.
using fcl::Transform3 = typedef Eigen::Transform<S, 3, Eigen::Isometry> |
using fcl::Transform3d = typedef Transform3<double> |
using fcl::Transform3f = typedef Transform3<float> |
using fcl::Translation3 = typedef Eigen::Translation<S, 3> |
using fcl::Translation3d = typedef Translation3<double> |
using fcl::Translation3f = typedef Translation3<float> |
using fcl::TranslationMotiond = typedef TranslationMotion<double> |
Definition at line 84 of file translation_motion.h.
using fcl::TranslationMotionf = typedef TranslationMotion<float> |
Definition at line 83 of file translation_motion.h.
using fcl::TrianglePd = typedef TriangleP<double> |
Definition at line 83 of file triangle_p.h.
using fcl::TrianglePf = typedef TriangleP<float> |
Definition at line 82 of file triangle_p.h.
using fcl::uint32 = typedef std::uint32_t |
using fcl::uint64 = typedef std::uint64_t |
using fcl::uintptr_t = typedef std::uintptr_t |
using fcl::Variance3d = typedef Variance3<double> |
Definition at line 77 of file variance3.h.
using fcl::Variance3f = typedef Variance3<float> |
Definition at line 76 of file variance3.h.
using fcl::Vector2 = typedef Eigen::Matrix<S, 2, 1> |
using fcl::Vector3 = typedef Eigen::Matrix<S, 3, 1> |
using fcl::Vector3d = typedef Vector3<double> |
using fcl::Vector3f = typedef Vector3<float> |
using fcl::Vector6 = typedef Eigen::Matrix<S, 6, 1> |
using fcl::Vector7 = typedef Eigen::Matrix<S, 7, 1> |
using fcl::VectorN = typedef Eigen::Matrix<S, N, 1> |
using fcl::VectorNd = typedef VectorN<double, N> |
using fcl::VectorNf = typedef VectorN<float, N> |
using fcl::VectorX = typedef Eigen::Matrix<S, Eigen::Dynamic, 1> |
using fcl::VectorXd = typedef VectorX<double> |
using fcl::VectorXf = typedef VectorX<float> |
enum fcl::BVHBuildState |
States for BVH construction empty->begun->processed ->replace_begun->processed -> ...... | |-> update_begun -> updated -> .....
Definition at line 50 of file BVH_internal.h.
enum fcl::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 75 of file BVH_internal.h.
enum fcl::BVHReturnCode |
Error code for BVH.
Definition at line 61 of file BVH_internal.h.
enum fcl::CCDMotionType |
Enumerator | |
---|---|
CCDM_TRANS | |
CCDM_LINEAR | |
CCDM_SCREW | |
CCDM_SPLINE |
Definition at line 48 of file continuous_collision_request.h.
enum fcl::CCDSolverType |
Enumerator | |
---|---|
CCDC_NAIVE | |
CCDC_CONSERVATIVE_ADVANCEMENT | |
CCDC_RAY_SHOOTING | |
CCDC_POLYNOMIAL_SOLVER |
Definition at line 49 of file continuous_collision_request.h.
|
strong |
enum class used to indicate whether we simply want to add more primitives to the model or finalize it.
Enumerator | |
---|---|
DO | |
DONT |
Definition at line 59 of file geometric_shape_to_BVH_model.h.
enum fcl::GJKSolverType |
Type of narrow phase GJK solver.
Enumerator | |
---|---|
GST_LIBCCD | |
GST_INDEP |
Definition at line 45 of file gjk_solver_type.h.
|
strong |
Enumerator | |
---|---|
absolute | |
relative |
Definition at line 50 of file eigen_matrix_compare.h.
enum fcl::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, halfspace, triangle), and octree
Definition at line 53 of file collision_geometry.h.
enum fcl::OBJECT_TYPE |
object type: BVH (mesh, points), basic geometry, octree
Enumerator | |
---|---|
OT_UNKNOWN | |
OT_BVH | |
OT_GEOM | |
OT_OCTREE | |
OT_COUNT |
Definition at line 50 of file collision_geometry.h.
int fcl::addTriangles | ( | BVHModel< BV > & | model, |
const std::vector< Vector3< typename BV::S >> & | points, | ||
const std::vector< Triangle > & | tri_indices, | ||
FinalizeModel | finalize_model | ||
) |
Definition at line 49 of file geometric_shape_to_BVH_model-inl.h.
FCL_EXPORT void fcl::axisFromEigen | ( | const Matrix3< S > & | eigenV, |
const Vector3< S > & | eigenS, | ||
Matrix3< S > & | axis | ||
) |
Definition at line 567 of file geometry-inl.h.
FCL_EXPORT void fcl::axisFromEigen | ( | const Matrix3< S > & | eigenV, |
const Vector3< S > & | eigenS, | ||
Transform3< S > & | tf | ||
) |
Definition at line 607 of file geometry-inl.h.
template void fcl::axisFromEigen | ( | const Matrix3d & | eigenV, |
const Vector3d & | eigenS, | ||
Matrix3d & | axis | ||
) |
template void fcl::axisFromEigen | ( | const Matrix3d & | eigenV, |
const Vector3d & | eigenS, | ||
Transform3d & | tf | ||
) |
template Interval< double > fcl::bound | ( | const Interval< double > & | i, |
const Interval< double > & | other | ||
) |
FCL_EXPORT Interval<S> fcl::bound | ( | const Interval< S > & | i, |
const Interval< S > & | other | ||
) |
Definition at line 427 of file interval-inl.h.
Interval<S> fcl::bound | ( | const Interval< S > & | i, |
const Interval< S > & | other | ||
) |
Definition at line 427 of file interval-inl.h.
Definition at line 417 of file interval-inl.h.
Definition at line 417 of file interval-inl.h.
template IVector3< double > fcl::bound | ( | const IVector3< double > & | i, |
const IVector3< double > & | v | ||
) |
template IVector3< double > fcl::bound | ( | const IVector3< double > & | i, |
const Vector3< double > & | v | ||
) |
FCL_EXPORT IVector3<S> fcl::bound | ( | const IVector3< S > & | i, |
const IVector3< S > & | v | ||
) |
Definition at line 338 of file interval_vector-inl.h.
Definition at line 338 of file interval_vector-inl.h.
FCL_EXPORT IVector3<S> fcl::bound | ( | const IVector3< S > & | i, |
const Vector3< S > & | v | ||
) |
Definition at line 354 of file interval_vector-inl.h.
Definition at line 354 of file interval_vector-inl.h.
FCL_EXPORT void fcl::BVHExpand | ( | BVHModel< BV > & | model, |
const Variance3< S > * | ucs, | ||
S | r | ||
) |
Expand the BVH bounding boxes according to the variance matrix corresponding to the data stored within each BV node.
Definition at line 61 of file BVH_utility-inl.h.
template void fcl::BVHExpand | ( | BVHModel< OBB< double >> & | model, |
const Variance3< double > * | ucs, | ||
double | r | ||
) |
FCL_EXPORT void fcl::BVHExpand | ( | BVHModel< OBB< S >> & | model, |
const Variance3< S > * | ucs, | ||
S | r | ||
) |
Expand the BVH bounding boxes according to the corresponding variance information, for OBB.
Definition at line 89 of file BVH_utility-inl.h.
template void fcl::BVHExpand | ( | BVHModel< RSS< double >> & | model, |
const Variance3< double > * | ucs, | ||
double | r | ||
) |
FCL_EXPORT void fcl::BVHExpand | ( | BVHModel< RSS< S >> & | model, |
const Variance3< S > * | ucs, | ||
S | r | ||
) |
Expand the BVH bounding boxes according to the corresponding variance information, for RSS.
Definition at line 133 of file BVH_utility-inl.h.
FCL_EXPORT void fcl::circumCircleComputation | ( | const Vector3< S > & | a, |
const Vector3< S > & | b, | ||
const Vector3< S > & | c, | ||
Vector3< S > & | center, | ||
S & | radius | ||
) |
Compute the center and radius for a triangle's circumcircle.
Definition at line 1278 of file geometry-inl.h.
template void fcl::circumCircleComputation | ( | const Vector3d & | a, |
const Vector3d & | b, | ||
const Vector3d & | c, | ||
Vector3d & | center, | ||
double & | radius | ||
) |
template void fcl::clipToRange | ( | double & | val, |
double | a, | ||
double | b | ||
) |
FCL_EXPORT void fcl::clipToRange | ( | S & | val, |
S | a, | ||
S | b | ||
) |
void fcl::clipToRange | ( | S & | val, |
S | a, | ||
S | b | ||
) |
template std::size_t fcl::collide | ( | const CollisionGeometry< double > * | o1, |
const Transform3< double > & | tf1, | ||
const CollisionGeometry< double > * | o2, | ||
const Transform3< double > & | tf2, | ||
const CollisionRequest< double > & | request, | ||
CollisionResult< double > & | result | ||
) |
FCL_EXPORT std::size_t fcl::collide | ( | const CollisionGeometry< S > * | o1, |
const Transform3< S > & | tf1, | ||
const CollisionGeometry< S > * | o2, | ||
const Transform3< S > & | tf2, | ||
const CollisionRequest< S > & | request, | ||
CollisionResult< S > & | result | ||
) |
Definition at line 180 of file collision-inl.h.
FCL_EXPORT std::size_t fcl::collide | ( | const CollisionGeometry< S > * | o1, |
const Transform3< S > & | tf1, | ||
const CollisionGeometry< S > * | o2, | ||
const Transform3< S > & | tf2, | ||
const NarrowPhaseSolver * | nsolver_, | ||
const CollisionRequest< S > & | request, | ||
CollisionResult< S > & | result | ||
) |
Definition at line 95 of file collision-inl.h.
template std::size_t fcl::collide | ( | const CollisionObject< double > * | o1, |
const CollisionObject< double > * | o2, | ||
const CollisionRequest< double > & | request, | ||
CollisionResult< double > & | result | ||
) |
FCL_EXPORT std::size_t fcl::collide | ( | const CollisionObject< S > * | o1, |
const CollisionObject< S > * | o2, | ||
const CollisionRequest< S > & | request, | ||
CollisionResult< S > & | 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 154 of file collision-inl.h.
FCL_EXPORT std::size_t fcl::collide | ( | const CollisionObject< S > * | o1, |
const CollisionObject< S > * | o2, | ||
const NarrowPhaseSolver * | nsolver, | ||
const CollisionRequest< S > & | request, | ||
CollisionResult< S > & | result | ||
) |
Definition at line 81 of file collision-inl.h.
template double fcl::collide | ( | const ContinuousCollisionObject< double > * | o1, |
const ContinuousCollisionObject< double > * | o2, | ||
const ContinuousCollisionRequest< double > & | request, | ||
ContinuousCollisionResult< double > & | result | ||
) |
FCL_EXPORT S fcl::collide | ( | const ContinuousCollisionObject< S > * | o1, |
const ContinuousCollisionObject< S > * | o2, | ||
const ContinuousCollisionRequest< S > & | request, | ||
ContinuousCollisionResult< S > & | result | ||
) |
Definition at line 472 of file continuous_collision-inl.h.
FCL_EXPORT VectorN< S, M+N > fcl::combine | ( | const VectorN< S, M > & | v1, |
const VectorN< S, N > & | v2 | ||
) |
Definition at line 441 of file geometry-inl.h.
::testing::AssertionResult fcl::CompareMatrices | ( | const Eigen::MatrixBase< DerivedA > & | m1, |
const Eigen::MatrixBase< DerivedB > & | m2, | ||
double | tolerance = 0.0 , |
||
MatrixCompareType | compare_type = MatrixCompareType::absolute |
||
) |
Compares two matrices to determine whether they are equal to within a certain threshold.
m1 | The first matrix to compare. |
m2 | The second matrix to compare. |
tolerance | The tolerance for determining equivalence. |
compare_type | Whether the tolerance is absolute or relative. |
Definition at line 63 of file eigen_matrix_compare.h.
template bool fcl::comparePenDepth | ( | const ContactPoint< double > & | _cp1, |
const ContactPoint< double > & | _cp2 | ||
) |
FCL_EXPORT bool fcl::comparePenDepth | ( | const ContactPoint< S > & | _cp1, |
const ContactPoint< S > & | _cp2 | ||
) |
Return true if _cp1's penentration depth is less than _cp2's.
Definition at line 80 of file contact_point-inl.h.
bool fcl::comparePenDepth | ( | const ContactPoint< S > & | _cp1, |
const ContactPoint< S > & | _cp2 | ||
) |
Return true if _cp1's penentration depth is less than _cp2's.
Definition at line 80 of file contact_point-inl.h.
FCL_EXPORT void fcl::computeBV | ( | const Shape & | s, |
const Transform3< typename BV::S > & | tf, | ||
BV & | bv | ||
) |
calculate a bounding volume for a shape in a specific configuration
Definition at line 1056 of file geometry/shape/utility-inl.h.
template void fcl::constructBox | ( | const AABB< double > & | bv, |
Box< double > & | box, | ||
Transform3< double > & | tf | ||
) |
template void fcl::constructBox | ( | const AABB< double > & | bv, |
const Transform3< double > & | tf_bv, | ||
Box< double > & | box, | ||
Transform3< double > & | tf | ||
) |
FCL_EXPORT void fcl::constructBox | ( | const AABB< S > & | bv, |
Box< S > & | box, | ||
Transform3< S > & | tf | ||
) |
construct a box shape (with a configuration) from a given bounding volume
Definition at line 1065 of file geometry/shape/utility-inl.h.
void fcl::constructBox | ( | const AABB< S > & | bv, |
Box< S > & | box, | ||
Transform3< S > & | tf | ||
) |
construct a box shape (with a configuration) from a given bounding volume
Definition at line 1065 of file geometry/shape/utility-inl.h.
FCL_EXPORT void fcl::constructBox | ( | const AABB< S > & | bv, |
const Transform3< S > & | tf_bv, | ||
Box< S > & | box, | ||
Transform3< S > & | tf | ||
) |
Definition at line 1137 of file geometry/shape/utility-inl.h.
void fcl::constructBox | ( | const AABB< S > & | bv, |
const Transform3< S > & | tf_bv, | ||
Box< S > & | box, | ||
Transform3< S > & | tf | ||
) |
Definition at line 1137 of file geometry/shape/utility-inl.h.
template void fcl::constructBox | ( | const KDOP< double, 16 > & | bv, |
Box< double > & | box, | ||
Transform3< double > & | tf | ||
) |
template void fcl::constructBox | ( | const KDOP< double, 16 > & | bv, |
const Transform3< double > & | tf_bv, | ||
Box< double > & | box, | ||
Transform3< double > & | tf | ||
) |
template void fcl::constructBox | ( | const KDOP< double, 18 > & | bv, |
Box< double > & | box, | ||
Transform3< double > & | tf | ||
) |
template void fcl::constructBox | ( | const KDOP< double, 18 > & | bv, |
const Transform3< double > & | tf_bv, | ||
Box< double > & | box, | ||
Transform3< double > & | tf | ||
) |
template void fcl::constructBox | ( | const KDOP< double, 24 > & | bv, |
Box< double > & | box, | ||
Transform3< double > & | tf | ||
) |
template void fcl::constructBox | ( | const KDOP< double, 24 > & | bv, |
const Transform3< double > & | tf_bv, | ||
Box< double > & | box, | ||
Transform3< double > & | tf | ||
) |
FCL_EXPORT void fcl::constructBox | ( | const KDOP< S, 16 > & | bv, |
Box< S > & | box, | ||
Transform3< S > & | tf | ||
) |
Definition at line 1110 of file geometry/shape/utility-inl.h.
void fcl::constructBox | ( | const KDOP< S, 16 > & | bv, |
Box< S > & | box, | ||
Transform3< S > & | tf | ||
) |
Definition at line 1110 of file geometry/shape/utility-inl.h.
FCL_EXPORT void fcl::constructBox | ( | const KDOP< S, 16 > & | bv, |
const Transform3< S > & | tf_bv, | ||
Box< S > & | box, | ||
Transform3< S > & | tf | ||
) |
Definition at line 1187 of file geometry/shape/utility-inl.h.
void fcl::constructBox | ( | const KDOP< S, 16 > & | bv, |
const Transform3< S > & | tf_bv, | ||
Box< S > & | box, | ||
Transform3< S > & | tf | ||
) |
Definition at line 1187 of file geometry/shape/utility-inl.h.
FCL_EXPORT void fcl::constructBox | ( | const KDOP< S, 18 > & | bv, |
Box< S > & | box, | ||
Transform3< S > & | tf | ||
) |
Definition at line 1119 of file geometry/shape/utility-inl.h.
void fcl::constructBox | ( | const KDOP< S, 18 > & | bv, |
Box< S > & | box, | ||
Transform3< S > & | tf | ||
) |
Definition at line 1119 of file geometry/shape/utility-inl.h.
FCL_EXPORT void fcl::constructBox | ( | const KDOP< S, 18 > & | bv, |
const Transform3< S > & | tf_bv, | ||
Box< S > & | box, | ||
Transform3< S > & | tf | ||
) |
Definition at line 1195 of file geometry/shape/utility-inl.h.
void fcl::constructBox | ( | const KDOP< S, 18 > & | bv, |
const Transform3< S > & | tf_bv, | ||
Box< S > & | box, | ||
Transform3< S > & | tf | ||
) |
Definition at line 1195 of file geometry/shape/utility-inl.h.
FCL_EXPORT void fcl::constructBox | ( | const KDOP< S, 24 > & | bv, |
Box< S > & | box, | ||
Transform3< S > & | tf | ||
) |
Definition at line 1128 of file geometry/shape/utility-inl.h.
void fcl::constructBox | ( | const KDOP< S, 24 > & | bv, |
Box< S > & | box, | ||
Transform3< S > & | tf | ||
) |
Definition at line 1128 of file geometry/shape/utility-inl.h.
FCL_EXPORT void fcl::constructBox | ( | const KDOP< S, 24 > & | bv, |
const Transform3< S > & | tf_bv, | ||
Box< S > & | box, | ||
Transform3< S > & | tf | ||
) |
Definition at line 1203 of file geometry/shape/utility-inl.h.
void fcl::constructBox | ( | const KDOP< S, 24 > & | bv, |
const Transform3< S > & | tf_bv, | ||
Box< S > & | box, | ||
Transform3< S > & | tf | ||
) |
Definition at line 1203 of file geometry/shape/utility-inl.h.
template void fcl::constructBox | ( | const kIOS< double > & | bv, |
Box< double > & | box, | ||
Transform3< double > & | tf | ||
) |
template void fcl::constructBox | ( | const kIOS< double > & | bv, |
const Transform3< double > & | tf_bv, | ||
Box< double > & | box, | ||
Transform3< double > & | tf | ||
) |
FCL_EXPORT void fcl::constructBox | ( | const kIOS< S > & | bv, |
Box< S > & | box, | ||
Transform3< S > & | tf | ||
) |
Definition at line 1092 of file geometry/shape/utility-inl.h.
void fcl::constructBox | ( | const kIOS< S > & | bv, |
Box< S > & | box, | ||
Transform3< S > & | tf | ||
) |
Definition at line 1092 of file geometry/shape/utility-inl.h.
FCL_EXPORT void fcl::constructBox | ( | const kIOS< S > & | bv, |
const Transform3< S > & | tf_bv, | ||
Box< S > & | box, | ||
Transform3< S > & | tf | ||
) |
Definition at line 1166 of file geometry/shape/utility-inl.h.
void fcl::constructBox | ( | const kIOS< S > & | bv, |
const Transform3< S > & | tf_bv, | ||
Box< S > & | box, | ||
Transform3< S > & | tf | ||
) |
Definition at line 1166 of file geometry/shape/utility-inl.h.
template void fcl::constructBox | ( | const OBB< double > & | bv, |
Box< double > & | box, | ||
Transform3< double > & | tf | ||
) |
template void fcl::constructBox | ( | const OBB< double > & | bv, |
const Transform3< double > & | tf_bv, | ||
Box< double > & | box, | ||
Transform3< double > & | tf | ||
) |
FCL_EXPORT void fcl::constructBox | ( | const OBB< S > & | bv, |
Box< S > & | box, | ||
Transform3< S > & | tf | ||
) |
Definition at line 1074 of file geometry/shape/utility-inl.h.
void fcl::constructBox | ( | const OBB< S > & | bv, |
Box< S > & | box, | ||
Transform3< S > & | tf | ||
) |
Definition at line 1074 of file geometry/shape/utility-inl.h.
FCL_EXPORT void fcl::constructBox | ( | const OBB< S > & | bv, |
const Transform3< S > & | tf_bv, | ||
Box< S > & | box, | ||
Transform3< S > & | tf | ||
) |
Definition at line 1145 of file geometry/shape/utility-inl.h.
void fcl::constructBox | ( | const OBB< S > & | bv, |
const Transform3< S > & | tf_bv, | ||
Box< S > & | box, | ||
Transform3< S > & | tf | ||
) |
Definition at line 1145 of file geometry/shape/utility-inl.h.
template void fcl::constructBox | ( | const OBBRSS< double > & | bv, |
Box< double > & | box, | ||
Transform3< double > & | tf | ||
) |
template void fcl::constructBox | ( | const OBBRSS< double > & | bv, |
const Transform3< double > & | tf_bv, | ||
Box< double > & | box, | ||
Transform3< double > & | tf | ||
) |
FCL_EXPORT void fcl::constructBox | ( | const OBBRSS< S > & | bv, |
Box< S > & | box, | ||
Transform3< S > & | tf | ||
) |
Definition at line 1083 of file geometry/shape/utility-inl.h.
void fcl::constructBox | ( | const OBBRSS< S > & | bv, |
Box< S > & | box, | ||
Transform3< S > & | tf | ||
) |
Definition at line 1083 of file geometry/shape/utility-inl.h.
FCL_EXPORT void fcl::constructBox | ( | const OBBRSS< S > & | bv, |
const Transform3< S > & | tf_bv, | ||
Box< S > & | box, | ||
Transform3< S > & | tf | ||
) |
Definition at line 1156 of file geometry/shape/utility-inl.h.
void fcl::constructBox | ( | const OBBRSS< S > & | bv, |
const Transform3< S > & | tf_bv, | ||
Box< S > & | box, | ||
Transform3< S > & | tf | ||
) |
Definition at line 1156 of file geometry/shape/utility-inl.h.
template void fcl::constructBox | ( | const RSS< double > & | bv, |
Box< double > & | box, | ||
Transform3< double > & | tf | ||
) |
template void fcl::constructBox | ( | const RSS< double > & | bv, |
const Transform3< double > & | tf_bv, | ||
Box< double > & | box, | ||
Transform3< double > & | tf | ||
) |
FCL_EXPORT void fcl::constructBox | ( | const RSS< S > & | bv, |
Box< S > & | box, | ||
Transform3< S > & | tf | ||
) |
Definition at line 1101 of file geometry/shape/utility-inl.h.
void fcl::constructBox | ( | const RSS< S > & | bv, |
Box< S > & | box, | ||
Transform3< S > & | tf | ||
) |
Definition at line 1101 of file geometry/shape/utility-inl.h.
FCL_EXPORT void fcl::constructBox | ( | const RSS< S > & | bv, |
const Transform3< S > & | tf_bv, | ||
Box< S > & | box, | ||
Transform3< S > & | tf | ||
) |
Definition at line 1177 of file geometry/shape/utility-inl.h.
void fcl::constructBox | ( | const RSS< S > & | bv, |
const Transform3< S > & | tf_bv, | ||
Box< S > & | box, | ||
Transform3< S > & | tf | ||
) |
Definition at line 1177 of file geometry/shape/utility-inl.h.
template double fcl::continuousCollide | ( | const CollisionGeometry< double > * | o1, |
const MotionBase< double > * | motion1, | ||
const CollisionGeometry< double > * | o2, | ||
const MotionBase< double > * | motion2, | ||
const ContinuousCollisionRequest< double > & | request, | ||
ContinuousCollisionResult< double > & | result | ||
) |
template double fcl::continuousCollide | ( | const CollisionGeometry< double > * | o1, |
const Transform3< double > & | tf1_beg, | ||
const Transform3< double > & | tf1_end, | ||
const CollisionGeometry< double > * | o2, | ||
const Transform3< double > & | tf2_beg, | ||
const Transform3< double > & | tf2_end, | ||
const ContinuousCollisionRequest< double > & | request, | ||
ContinuousCollisionResult< double > & | result | ||
) |
FCL_EXPORT S fcl::continuousCollide | ( | const CollisionGeometry< S > * | o1, |
const MotionBase< S > * | motion1, | ||
const CollisionGeometry< S > * | o2, | ||
const MotionBase< S > * | motion2, | ||
const ContinuousCollisionRequest< S > & | request, | ||
ContinuousCollisionResult< S > & | result | ||
) |
continous collision checking between two objects
Definition at line 387 of file continuous_collision-inl.h.
FCL_EXPORT S fcl::continuousCollide | ( | const CollisionGeometry< S > * | o1, |
const Transform3< S > & | tf1_beg, | ||
const Transform3< S > & | tf1_end, | ||
const CollisionGeometry< S > * | o2, | ||
const Transform3< S > & | tf2_beg, | ||
const Transform3< S > & | tf2_end, | ||
const ContinuousCollisionRequest< S > & | request, | ||
ContinuousCollisionResult< S > & | result | ||
) |
Definition at line 437 of file continuous_collision-inl.h.
template double fcl::continuousCollide | ( | const CollisionObject< double > * | o1, |
const Transform3< double > & | tf1_end, | ||
const CollisionObject< double > * | o2, | ||
const Transform3< double > & | tf2_end, | ||
const ContinuousCollisionRequest< double > & | request, | ||
ContinuousCollisionResult< double > & | result | ||
) |
FCL_EXPORT S fcl::continuousCollide | ( | const CollisionObject< S > * | o1, |
const Transform3< S > & | tf1_end, | ||
const CollisionObject< S > * | o2, | ||
const Transform3< S > & | tf2_end, | ||
const ContinuousCollisionRequest< S > & | request, | ||
ContinuousCollisionResult< S > & | result | ||
) |
Definition at line 456 of file continuous_collision-inl.h.
FCL_EXPORT S fcl::continuousCollideBVHPolynomial | ( | const CollisionGeometry< S > * | o1, |
const TranslationMotion< S > * | motion1, | ||
const CollisionGeometry< S > * | o2, | ||
const TranslationMotion< S > * | motion2, | ||
const ContinuousCollisionRequest< S > & | request, | ||
ContinuousCollisionResult< S > & | result | ||
) |
Definition at line 248 of file continuous_collision-inl.h.
FCL_EXPORT S fcl::continuousCollideConservativeAdvancement | ( | const CollisionGeometry< S > * | o1, |
const MotionBase< S > * | motion1, | ||
const CollisionGeometry< S > * | o2, | ||
const MotionBase< S > * | motion2, | ||
const ContinuousCollisionRequest< S > & | request, | ||
ContinuousCollisionResult< S > & | result | ||
) |
Definition at line 359 of file continuous_collision-inl.h.
FCL_EXPORT S fcl::continuousCollideNaive | ( | const CollisionGeometry< S > * | o1, |
const MotionBase< S > * | motion1, | ||
const CollisionGeometry< S > * | o2, | ||
const MotionBase< S > * | motion2, | ||
const ContinuousCollisionRequest< S > & | request, | ||
ContinuousCollisionResult< S > & | result | ||
) |
Definition at line 136 of file continuous_collision-inl.h.
FCL_EXPORT void fcl::convertBV | ( | const BV1 & | bv1, |
const Transform3< typename BV1::S > & | tf1, | ||
BV2 & | bv2 | ||
) |
Convert a bounding volume of type BV1 in configuration tf1 to bounding volume of type BV2 in identity configuration.
Definition at line 973 of file math/bv/utility-inl.h.
bool fcl::DefaultCollisionFunction | ( | CollisionObject< S > * | o1, |
CollisionObject< S > * | 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 DefaultCollisionData. It simply invokes the collide()
method on the culled pair of geometries and stores the results in the data's CollisionResult instance.
This callback will cause the broadphase evaluation to stop if:
For a given instance of DefaultCollisionData, if broadphase evaluation has already terminated (i.e., DefaultCollisionFunction() returned true
), subsequent invocations with the same instance of DefaultCollisionData 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 DefaultCollisionData instance. |
true
if the broadphase evaluation should stop. S | The scalar type with which the computation will be performed. |
Definition at line 88 of file default_broadphase_callbacks.h.
bool fcl::DefaultContinuousCollisionFunction | ( | ContinuousCollisionObject< S > * | o1, |
ContinuousCollisionObject< S > * | o2, | ||
void * | data | ||
) |
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 DefaultCollisionData 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 DefaultCollisionData instance. |
S | The scalar type with which the computation will be performed. |
Definition at line 145 of file default_broadphase_callbacks.h.
bool fcl::DefaultDistanceFunction | ( | CollisionObject< S > * | o1, |
CollisionObject< S > * | o2, | ||
void * | data, | ||
S & | dist | ||
) |
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 DefaultDistanceData. 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 DefaultDistanceData, if broadphase evaluation has already terminated (i.e., DefaultDistanceFunction() returned true
), subsequent invocations with the same instance of DefaultDistanceData 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 DefaultDistanceData 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 196 of file default_broadphase_callbacks.h.
template double fcl::distance | ( | const CollisionGeometry< double > * | o1, |
const Transform3< double > & | tf1, | ||
const CollisionGeometry< double > * | o2, | ||
const Transform3< double > & | tf2, | ||
const DistanceRequest< double > & | request, | ||
DistanceResult< double > & | result | ||
) |
FCL_EXPORT S fcl::distance | ( | const CollisionGeometry< S > * | o1, |
const Transform3< S > & | tf1, | ||
const CollisionGeometry< S > * | o2, | ||
const Transform3< S > & | tf2, | ||
const DistanceRequest< S > & | request, | ||
DistanceResult< S > & | result | ||
) |
Definition at line 224 of file distance-inl.h.
S fcl::distance | ( | const CollisionGeometry< S > * | o1, |
const Transform3< S > & | tf1, | ||
const CollisionGeometry< S > * | o2, | ||
const Transform3< S > & | tf2, | ||
const DistanceRequest< S > & | request, | ||
DistanceResult< S > & | result | ||
) |
Definition at line 224 of file distance-inl.h.
NarrowPhaseSolver::S fcl::distance | ( | const CollisionGeometry< typename NarrowPhaseSolver::S > * | o1, |
const Transform3< typename NarrowPhaseSolver::S > & | tf1, | ||
const CollisionGeometry< typename NarrowPhaseSolver::S > * | o2, | ||
const Transform3< typename NarrowPhaseSolver::S > & | tf2, | ||
const NarrowPhaseSolver * | nsolver_, | ||
const DistanceRequest< typename NarrowPhaseSolver::S > & | request, | ||
DistanceResult< typename NarrowPhaseSolver::S > & | result | ||
) |
Definition at line 92 of file distance-inl.h.
template double fcl::distance | ( | const CollisionObject< double > * | o1, |
const CollisionObject< double > * | o2, | ||
const DistanceRequest< double > & | request, | ||
DistanceResult< double > & | result | ||
) |
FCL_EXPORT S fcl::distance | ( | const CollisionObject< S > * | o1, |
const CollisionObject< S > * | o2, | ||
const DistanceRequest< S > & | request, | ||
DistanceResult< S > & | 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 197 of file distance-inl.h.
S fcl::distance | ( | const CollisionObject< S > * | o1, |
const CollisionObject< S > * | o2, | ||
const DistanceRequest< S > & | request, | ||
DistanceResult< S > & | 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 197 of file distance-inl.h.
NarrowPhaseSolver::S fcl::distance | ( | const CollisionObject< typename NarrowPhaseSolver::S > * | o1, |
const CollisionObject< typename NarrowPhaseSolver::S > * | o2, | ||
const NarrowPhaseSolver * | nsolver, | ||
const DistanceRequest< typename NarrowPhaseSolver::S > & | request, | ||
DistanceResult< typename NarrowPhaseSolver::S > & | result | ||
) |
Definition at line 73 of file distance-inl.h.
S fcl::distance | ( | const Eigen::MatrixBase< DerivedA > & | R0, |
const Eigen::MatrixBase< DerivedB > & | T0, | ||
const kIOS< S > & | b1, | ||
const kIOS< S > & | b2, | ||
Vector3< S > * | P = nullptr , |
||
Vector3< S > * | Q = nullptr |
||
) |
Approximate distance between two kIOS bounding volumes.
Definition at line 266 of file kIOS-inl.h.
FCL_EXPORT S fcl::distance | ( | const Eigen::MatrixBase< DerivedA > & | R0, |
const Eigen::MatrixBase< DerivedB > & | T0, | ||
const kIOS< S > & | b1, | ||
const kIOS< S > & | b2, | ||
Vector3< S > * | P = nullptr , |
||
Vector3< S > * | Q = nullptr |
||
) |
Approximate distance between two kIOS bounding volumes.
Definition at line 266 of file kIOS-inl.h.
S fcl::distance | ( | const Eigen::MatrixBase< DerivedA > & | R0, |
const Eigen::MatrixBase< DerivedB > & | T0, | ||
const OBBRSS< S > & | b1, | ||
const OBBRSS< S > & | b2, | ||
Vector3< S > * | P, | ||
Vector3< S > * | Q | ||
) |
Computate distance between two OBBRSS, b1 is in configuation (R0, T0) and b2 is in indentity; P and Q, is not nullptr, returns the nearest points.
Definition at line 164 of file OBBRSS-inl.h.
FCL_EXPORT S fcl::distance | ( | const Eigen::MatrixBase< DerivedA > & | R0, |
const Eigen::MatrixBase< DerivedB > & | T0, | ||
const OBBRSS< S > & | b1, | ||
const OBBRSS< S > & | b2, | ||
Vector3< S > * | P = nullptr , |
||
Vector3< S > * | Q = nullptr |
||
) |
Computate distance between two OBBRSS, b1 is in configuation (R0, T0) and b2 is in indentity; P and Q, is not nullptr, returns the nearest points.
Definition at line 164 of file OBBRSS-inl.h.
S fcl::distance | ( | const Eigen::MatrixBase< DerivedA > & | R0, |
const Eigen::MatrixBase< DerivedB > & | T0, | ||
const RSS< S > & | b1, | ||
const RSS< S > & | b2, | ||
Vector3< S > * | P, | ||
Vector3< S > * | Q | ||
) |
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)
FCL_EXPORT S fcl::distance | ( | const Eigen::MatrixBase< DerivedA > & | R0, |
const Eigen::MatrixBase< DerivedB > & | T0, | ||
const RSS< S > & | b1, | ||
const RSS< S > & | b2, | ||
Vector3< S > * | P = nullptr , |
||
Vector3< S > * | Q = nullptr |
||
) |
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)
S fcl::distance | ( | const Transform3< S > & | tf, |
const kIOS< S > & | b1, | ||
const kIOS< S > & | b2, | ||
Vector3< S > * | P = nullptr , |
||
Vector3< S > * | Q = nullptr |
||
) |
Approximate distance between two kIOS bounding volumes.
Definition at line 281 of file kIOS-inl.h.
FCL_EXPORT S fcl::distance | ( | const Transform3< S > & | tf, |
const kIOS< S > & | b1, | ||
const kIOS< S > & | b2, | ||
Vector3< S > * | P = nullptr , |
||
Vector3< S > * | Q = nullptr |
||
) |
Approximate distance between two kIOS bounding volumes.
Definition at line 281 of file kIOS-inl.h.
FCL_EXPORT S fcl::distance | ( | const Transform3< S > & | tf, |
const OBBRSS< S > & | b1, | ||
const OBBRSS< S > & | b2, | ||
Vector3< S > * | P = nullptr , |
||
Vector3< S > * | Q = nullptr |
||
) |
Computate distance between two OBBRSS, b1 is in configuation (R0, T0) and b2 is in indentity; P and Q, is not nullptr, returns the nearest points.
FCL_EXPORT void fcl::eigen | ( | const Matrix3< S > & | m, |
Vector3< S > & | dout, | ||
Matrix3< S > & | vout | ||
) |
compute the eigen vector and eigen vector of a matrix. dout is the eigen values, vout is the eigen vectors
Definition at line 461 of file geometry-inl.h.
FCL_EXPORT void fcl::eigen_old | ( | const Matrix3< S > & | m, |
Vector3< S > & | dout, | ||
Matrix3< S > & | vout | ||
) |
compute the eigen vector and eigen vector of a matrix. dout is the eigen values, vout is the eigen vectors
Definition at line 477 of file geometry-inl.h.
FCL_EXPORT void fcl::fit | ( | const Vector3< typename BV::S > *const | ps, |
int | n, | ||
BV & | bv | ||
) |
Compute a bounding volume that fits a set of n points.
Definition at line 671 of file math/bv/utility-inl.h.
template void fcl::flipNormal | ( | std::vector< ContactPoint< double >> & | contacts | ) |
FCL_EXPORT void fcl::flipNormal | ( | std::vector< ContactPoint< S >> & | contacts | ) |
Definition at line 87 of file contact_point-inl.h.
void fcl::flipNormal | ( | std::vector< ContactPoint< S >> & | contacts | ) |
Definition at line 87 of file contact_point-inl.h.
FCL_EXPORT Matrix3< S > fcl::generateCoordinateSystem | ( | const Vector3< S > & | x_axis | ) |
compute orthogonal coordinate system basis with given x-axis.
x_axis | Direction of x-axis. Must have non-zero length. For best results, length should be much greater than constants<S>::eps_12(). |
Definition at line 647 of file geometry-inl.h.
template void fcl::generateTaylorModelForCosFunc | ( | TaylorModel< double > & | tm, |
double | w, | ||
double | q0 | ||
) |
FCL_EXPORT void fcl::generateTaylorModelForCosFunc | ( | TaylorModel< S > & | tm, |
S | w, | ||
S | q0 | ||
) |
Generate Taylor model for cos(w t + q0)
Definition at line 491 of file taylor_model-inl.h.
void fcl::generateTaylorModelForCosFunc | ( | TaylorModel< S > & | tm, |
S | w, | ||
S | q0 | ||
) |
Generate Taylor model for cos(w t + q0)
Definition at line 491 of file taylor_model-inl.h.
template void fcl::generateTaylorModelForLinearFunc | ( | TaylorModel< double > & | tm, |
double | p, | ||
double | v | ||
) |
FCL_EXPORT void fcl::generateTaylorModelForLinearFunc | ( | TaylorModel< S > & | tm, |
S | p, | ||
S | v | ||
) |
Generate Taylor model for p + v t.
Definition at line 634 of file taylor_model-inl.h.
void fcl::generateTaylorModelForLinearFunc | ( | TaylorModel< S > & | tm, |
S | p, | ||
S | v | ||
) |
Generate Taylor model for p + v t.
Definition at line 634 of file taylor_model-inl.h.
template void fcl::generateTaylorModelForSinFunc | ( | TaylorModel< double > & | tm, |
double | w, | ||
double | q0 | ||
) |
FCL_EXPORT void fcl::generateTaylorModelForSinFunc | ( | TaylorModel< S > & | tm, |
S | w, | ||
S | q0 | ||
) |
Generate Taylor model for sin(w t + q0)
Definition at line 562 of file taylor_model-inl.h.
void fcl::generateTaylorModelForSinFunc | ( | TaylorModel< S > & | tm, |
S | w, | ||
S | q0 | ||
) |
Generate Taylor model for sin(w t + q0)
Definition at line 562 of file taylor_model-inl.h.
template void fcl::generateTVector3ForLinearFunc | ( | TVector3< double > & | v, |
const Vector3< double > & | position, | ||
const Vector3< double > & | velocity | ||
) |
FCL_EXPORT void fcl::generateTVector3ForLinearFunc | ( | TVector3< S > & | v, |
const Vector3< S > & | position, | ||
const Vector3< S > & | velocity | ||
) |
Definition at line 356 of file taylor_vector-inl.h.
void fcl::generateTVector3ForLinearFunc | ( | TVector3< S > & | v, |
const Vector3< S > & | position, | ||
const Vector3< S > & | velocity | ||
) |
Definition at line 356 of file taylor_vector-inl.h.
detail::CollisionFunctionMatrix<GJKSolver>& fcl::getCollisionFunctionLookTable | ( | ) |
Definition at line 72 of file collision-inl.h.
detail::ConservativeAdvancementFunctionMatrix<GJKSolver>& fcl::getConservativeAdvancementFunctionLookTable | ( | ) |
Definition at line 100 of file continuous_collision-inl.h.
FCL_EXPORT void fcl::getCovariance | ( | const Vector3< S > *const | ps, |
const Vector3< S > *const | ps2, | ||
Triangle * | ts, | ||
unsigned int * | indices, | ||
int | n, | ||
Matrix3< S > & | 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 1339 of file geometry-inl.h.
template void fcl::getCovariance | ( | const Vector3d *const | ps, |
const Vector3d *const | ps2, | ||
Triangle * | ts, | ||
unsigned int * | indices, | ||
int | n, | ||
Matrix3d & | M | ||
) |
detail::DistanceFunctionMatrix<GJKSolver>& fcl::getDistanceFunctionLookTable | ( | ) |
Definition at line 65 of file distance-inl.h.
FCL_EXPORT void fcl::getDistances | ( | const Vector3< S > & | p, |
S * | d | ||
) |
Compute the distances to planes with normals from KDOP vectors except those of AABB face planes.
Definition at line 350 of file kDOP-inl.h.
template void fcl::getDistances< double, 5 > | ( | const Vector3< double > & | p, |
double * | d | ||
) |
template void fcl::getDistances< double, 6 > | ( | const Vector3< double > & | p, |
double * | d | ||
) |
template void fcl::getDistances< double, 9 > | ( | const Vector3< double > & | p, |
double * | d | ||
) |
FCL_EXPORT void fcl::getExtentAndCenter | ( | const Vector3< S > *const | ps, |
const Vector3< S > *const | ps2, | ||
Triangle * | ts, | ||
unsigned int * | indices, | ||
int | n, | ||
const Matrix3< S > & | axis, | ||
Vector3< S > & | center, | ||
Vector3< S > & | extent | ||
) |
Compute the bounding volume extent and center for a set or subset of points, given the BV axises.
Definition at line 1320 of file geometry-inl.h.
FCL_EXPORT void fcl::getExtentAndCenter | ( | const Vector3< S > *const | ps, |
const Vector3< S > *const | ps2, | ||
Triangle * | ts, | ||
unsigned int * | indices, | ||
int | n, | ||
Transform3< S > & | tf, | ||
Vector3< S > & | extent | ||
) |
Compute the bounding volume extent and center for a set or subset of points, given the BV axises.
template void fcl::getExtentAndCenter | ( | const Vector3d *const | ps, |
const Vector3d *const | ps2, | ||
Triangle * | ts, | ||
unsigned int * | indices, | ||
int | n, | ||
const Matrix3d & | axis, | ||
Vector3d & | center, | ||
Vector3d & | extent | ||
) |
FCL_EXPORT MotionBasePtr<S> fcl::getMotionBase | ( | const Transform3< S > & | tf_beg, |
const Transform3< S > & | tf_end, | ||
CCDMotionType | motion_type | ||
) |
Definition at line 109 of file continuous_collision-inl.h.
FCL_EXPORT void fcl::getRadiusAndOriginAndRectangleSize | ( | const Vector3< S > *const | ps, |
const Vector3< S > *const | ps2, | ||
Triangle * | ts, | ||
unsigned int * | indices, | ||
int | n, | ||
const Matrix3< S > & | axis, | ||
Vector3< S > & | origin, | ||
S | l[2], | ||
S & | r | ||
) |
Compute the RSS bounding volume parameters: radius, rectangle size and the origin, given the BV axises.
Definition at line 713 of file geometry-inl.h.
FCL_EXPORT void fcl::getRadiusAndOriginAndRectangleSize | ( | const Vector3< S > *const | ps, |
const Vector3< S > *const | ps2, | ||
Triangle * | ts, | ||
unsigned int * | indices, | ||
int | n, | ||
Transform3< S > & | tf, | ||
S | l[2], | ||
S & | r | ||
) |
Compute the RSS bounding volume parameters: radius, rectangle size and the origin, given the BV axises.
Definition at line 996 of file geometry-inl.h.
template void fcl::getRadiusAndOriginAndRectangleSize | ( | const Vector3d *const | ps, |
const Vector3d *const | ps2, | ||
Triangle * | ts, | ||
unsigned int * | indices, | ||
int | n, | ||
const Matrix3d & | axis, | ||
Vector3d & | origin, | ||
double | l[2], | ||
double & | r | ||
) |
template void fcl::getRadiusAndOriginAndRectangleSize | ( | const Vector3d *const | ps, |
const Vector3d *const | ps2, | ||
Triangle * | ts, | ||
unsigned int * | indices, | ||
int | n, | ||
Transform3d & | tf, | ||
double | l[2], | ||
double & | r | ||
) |
Definition at line 453 of file geometry-inl.h.
template bool fcl::inVoronoi | ( | double | a, |
double | b, | ||
double | Anorm_dot_B, | ||
double | Anorm_dot_T, | ||
double | A_dot_B, | ||
double | A_dot_T, | ||
double | B_dot_T | ||
) |
FCL_EXPORT bool fcl::inVoronoi | ( | S | a, |
S | b, | ||
S | Anorm_dot_B, | ||
S | Anorm_dot_T, | ||
S | A_dot_B, | ||
S | A_dot_T, | ||
S | 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 fcl::inVoronoi | ( | S | a, |
S | b, | ||
S | Anorm_dot_B, | ||
S | Anorm_dot_T, | ||
S | A_dot_B, | ||
S | A_dot_T, | ||
S | 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.
|
inline |
FCL_EXPORT S fcl::maximumDistance | ( | const Vector3< S > *const | ps, |
const Vector3< S > *const | ps2, | ||
Triangle * | ts, | ||
unsigned int * | indices, | ||
int | n, | ||
const Vector3< S > & | query | ||
) |
Compute the maximum distance from a given center point to a point cloud.
Definition at line 1303 of file geometry-inl.h.
template double fcl::maximumDistance | ( | const Vector3d *const | ps, |
const Vector3d *const | ps2, | ||
Triangle * | ts, | ||
unsigned int * | indices, | ||
int | n, | ||
const Vector3d & | query | ||
) |
template void fcl::minmax | ( | double | a, |
double | b, | ||
double & | minv, | ||
double & | maxv | ||
) |
template void fcl::minmax | ( | double | p, |
double & | minv, | ||
double & | maxv | ||
) |
FCL_EXPORT void fcl::minmax | ( | S | a, |
S | b, | ||
S & | minv, | ||
S & | maxv | ||
) |
Find the smaller and larger one of two values.
Definition at line 314 of file kDOP-inl.h.
FCL_EXPORT void fcl::minmax | ( | S | p, |
S & | minv, | ||
S & | maxv | ||
) |
Merge the interval [minv, maxv] and value p/.
Definition at line 331 of file kDOP-inl.h.
FCL_EXPORT void fcl::normalize | ( | Vector3< S > & | v, |
bool * | signal | ||
) |
Definition at line 413 of file geometry-inl.h.
template void fcl::normalize | ( | Vector3d & | v, |
bool * | signal | ||
) |
template bool fcl::obbDisjoint | ( | const Matrix3< double > & | B, |
const Vector3< double > & | T, | ||
const Vector3< double > & | a, | ||
const Vector3< double > & | b | ||
) |
template bool fcl::obbDisjoint | ( | const Transform3< double > & | tf, |
const Vector3< double > & | a, | ||
const Vector3< double > & | b | ||
) |
FCL_EXPORT bool fcl::obbDisjoint | ( | const Transform3< S > & | tf, |
const Vector3< S > & | a, | ||
const Vector3< S > & | b | ||
) |
bool fcl::obbDisjoint | ( | const Transform3< S > & | tf, |
const Vector3< S > & | a, | ||
const Vector3< S > & | b | ||
) |
template TMatrix3< double > fcl::operator* | ( | const Matrix3< double > & | m, |
const TaylorModel< double > & | a | ||
) |
FCL_EXPORT TMatrix3<S> fcl::operator* | ( | const Matrix3< S > & | m, |
const TaylorModel< S > & | a | ||
) |
Definition at line 512 of file taylor_matrix-inl.h.
TMatrix3<S> fcl::operator* | ( | const Matrix3< S > & | m, |
const TaylorModel< S > & | a | ||
) |
Definition at line 512 of file taylor_matrix-inl.h.
template TMatrix3< double > fcl::operator* | ( | const TaylorModel< double > & | a, |
const Matrix3< double > & | m | ||
) |
template TMatrix3< double > fcl::operator* | ( | const TaylorModel< double > & | a, |
const TMatrix3< double > & | m | ||
) |
FCL_EXPORT TMatrix3<S> fcl::operator* | ( | const TaylorModel< S > & | a, |
const Matrix3< S > & | m | ||
) |
Definition at line 532 of file taylor_matrix-inl.h.
TMatrix3<S> fcl::operator* | ( | const TaylorModel< S > & | a, |
const Matrix3< S > & | m | ||
) |
Definition at line 532 of file taylor_matrix-inl.h.
FCL_EXPORT TMatrix3<S> fcl::operator* | ( | const TaylorModel< S > & | a, |
const TMatrix3< S > & | m | ||
) |
Definition at line 539 of file taylor_matrix-inl.h.
TMatrix3<S> fcl::operator* | ( | const TaylorModel< S > & | a, |
const TMatrix3< S > & | m | ||
) |
Definition at line 539 of file taylor_matrix-inl.h.
template TVector3< double > fcl::operator* | ( | const Vector3< double > & | v, |
const TaylorModel< double > & | a | ||
) |
FCL_EXPORT TVector3<S> fcl::operator* | ( | const Vector3< S > & | v, |
const TaylorModel< S > & | a | ||
) |
Definition at line 365 of file taylor_vector-inl.h.
TVector3<S> fcl::operator* | ( | const Vector3< S > & | v, |
const TaylorModel< S > & | a | ||
) |
Definition at line 365 of file taylor_vector-inl.h.
template TaylorModel< double > fcl::operator* | ( | double | d, |
const TaylorModel< double > & | a | ||
) |
FCL_EXPORT TaylorModel<S> fcl::operator* | ( | S | d, |
const TaylorModel< S > & | a | ||
) |
Definition at line 464 of file taylor_model-inl.h.
TaylorModel<S> fcl::operator* | ( | S | d, |
const TaylorModel< S > & | a | ||
) |
Definition at line 464 of file taylor_model-inl.h.
Definition at line 546 of file taylor_matrix-inl.h.
Definition at line 546 of file taylor_matrix-inl.h.
template TMatrix3< double > fcl::operator+ | ( | const Matrix3< double > & | m1, |
const TMatrix3< double > & | m2 | ||
) |
FCL_EXPORT TMatrix3<S> fcl::operator+ | ( | const Matrix3< S > & | m1, |
const TMatrix3< S > & | m2 | ||
) |
Definition at line 553 of file taylor_matrix-inl.h.
TMatrix3<S> fcl::operator+ | ( | const Matrix3< S > & | m1, |
const TMatrix3< S > & | m2 | ||
) |
Definition at line 553 of file taylor_matrix-inl.h.
template TVector3< double > fcl::operator+ | ( | const Vector3< double > & | v1, |
const TVector3< double > & | v2 | ||
) |
FCL_EXPORT TVector3<S> fcl::operator+ | ( | const Vector3< S > & | v1, |
const TVector3< S > & | v2 | ||
) |
Definition at line 377 of file taylor_vector-inl.h.
TVector3<S> fcl::operator+ | ( | const Vector3< S > & | v1, |
const TVector3< S > & | v2 | ||
) |
Definition at line 377 of file taylor_vector-inl.h.
template TaylorModel< double > fcl::operator+ | ( | double | d, |
const TaylorModel< double > & | a | ||
) |
FCL_EXPORT TaylorModel<S> fcl::operator+ | ( | S | d, |
const TaylorModel< S > & | a | ||
) |
Definition at line 477 of file taylor_model-inl.h.
TaylorModel<S> fcl::operator+ | ( | S | d, |
const TaylorModel< S > & | a | ||
) |
Definition at line 477 of file taylor_model-inl.h.
template TMatrix3< double > fcl::operator- | ( | const Matrix3< double > & | m1, |
const TMatrix3< double > & | m2 | ||
) |
FCL_EXPORT TMatrix3<S> fcl::operator- | ( | const Matrix3< S > & | m1, |
const TMatrix3< S > & | m2 | ||
) |
Definition at line 560 of file taylor_matrix-inl.h.
TMatrix3<S> fcl::operator- | ( | const Matrix3< S > & | m1, |
const TMatrix3< S > & | m2 | ||
) |
Definition at line 560 of file taylor_matrix-inl.h.
template TVector3< double > fcl::operator- | ( | const Vector3< double > & | v1, |
const TVector3< double > & | v2 | ||
) |
FCL_EXPORT TVector3<S> fcl::operator- | ( | const Vector3< S > & | v1, |
const TVector3< S > & | v2 | ||
) |
Definition at line 384 of file taylor_vector-inl.h.
TVector3<S> fcl::operator- | ( | const Vector3< S > & | v1, |
const TVector3< S > & | v2 | ||
) |
Definition at line 384 of file taylor_vector-inl.h.
template TaylorModel< double > fcl::operator- | ( | double | d, |
const TaylorModel< double > & | a | ||
) |
FCL_EXPORT TaylorModel<S> fcl::operator- | ( | S | d, |
const TaylorModel< S > & | a | ||
) |
Definition at line 484 of file taylor_model-inl.h.
TaylorModel<S> fcl::operator- | ( | S | d, |
const TaylorModel< S > & | a | ||
) |
Definition at line 484 of file taylor_model-inl.h.
std::ostream& fcl::operator<< | ( | std::ostream & | out, |
const NODE_TYPE & | node | ||
) |
Definition at line 55 of file test_collision_func_matrix.cpp.
FCL_EXPORT bool fcl::overlap | ( | const Eigen::MatrixBase< DerivedA > & | R0, |
const Eigen::MatrixBase< DerivedB > & | T0, | ||
const kIOS< S > & | b1, | ||
const kIOS< S > & | b2 | ||
) |
Check collision between two kIOSs, b1 is in configuration (R0, T0) and b2 is in identity.
Definition at line 249 of file kIOS-inl.h.
bool fcl::overlap | ( | const Eigen::MatrixBase< DerivedA > & | R0, |
const Eigen::MatrixBase< DerivedB > & | T0, | ||
const kIOS< S > & | b1, | ||
const kIOS< S > & | b2 | ||
) |
Check collision between two kIOSs, b1 is in configuration (R0, T0) and b2 is in identity.
Definition at line 249 of file kIOS-inl.h.
FCL_EXPORT bool fcl::overlap | ( | const Eigen::MatrixBase< DerivedA > & | R0, |
const Eigen::MatrixBase< DerivedB > & | T0, | ||
const OBBRSS< S > & | b1, | ||
const OBBRSS< S > & | b2 | ||
) |
Check collision between two OBBRSS, b1 is in configuration (R0, T0) and b2 is in indentity.
Definition at line 155 of file OBBRSS-inl.h.
bool fcl::overlap | ( | const Eigen::MatrixBase< DerivedA > & | R0, |
const Eigen::MatrixBase< DerivedB > & | T0, | ||
const OBBRSS< S > & | b1, | ||
const OBBRSS< S > & | b2 | ||
) |
Check collision between two OBBRSS, b1 is in configuration (R0, T0) and b2 is in indentity.
Definition at line 155 of file OBBRSS-inl.h.
FCL_EXPORT bool fcl::overlap | ( | const Transform3< S > & | tf, |
const kIOS< S > & | b1, | ||
const kIOS< S > & | b2 | ||
) |
Check collision between two kIOSs, b1 is in configuration (R0, T0) and b2 is in identity.
FCL_EXPORT bool fcl::overlap | ( | const Transform3< S > & | tf, |
const OBBRSS< S > & | b1, | ||
const OBBRSS< S > & | b2 | ||
) |
Check collision between two OBBRSS, b1 is in configuration (R0, T0) and b2 is in indentity.
template double fcl::rectDistance | ( | const Matrix3< double > & | Rab, |
const Vector3< double > & | Tab, | ||
const double | a[2], | ||
const double | b[2], | ||
Vector3< double > * | P, | ||
Vector3< double > * | Q | ||
) |
template double fcl::rectDistance | ( | const Transform3< double > & | tfab, |
const double | a[2], | ||
const double | b[2], | ||
Vector3< double > * | P, | ||
Vector3< double > * | Q | ||
) |
S fcl::rectDistance | ( | const Transform3< S > & | tfab, |
const S | a[2], | ||
const S | b[2], | ||
Vector3< S > * | P, | ||
Vector3< S > * | Q | ||
) |
FCL_EXPORT S fcl::rectDistance | ( | const Transform3< S > & | tfab, |
const S | a[2], | ||
const S | b[2], | ||
Vector3< S > * | P = nullptr , |
||
Vector3< S > * | Q = nullptr |
||
) |
FCL_EXPORT void fcl::relativeTransform | ( | const Eigen::MatrixBase< DerivedA > & | R1, |
const Eigen::MatrixBase< DerivedB > & | t1, | ||
const Eigen::MatrixBase< DerivedA > & | R2, | ||
const Eigen::MatrixBase< DerivedB > & | t2, | ||
Eigen::MatrixBase< DerivedC > & | R, | ||
Eigen::MatrixBase< DerivedD > & | t | ||
) |
Definition at line 659 of file geometry-inl.h.
FCL_EXPORT void fcl::relativeTransform | ( | const Eigen::Transform< S, 3, Eigen::Isometry > & | T1, |
const Eigen::Transform< S, 3, Eigen::Isometry > & | T2, | ||
Eigen::MatrixBase< DerivedA > & | R, | ||
Eigen::MatrixBase< DerivedB > & | t | ||
) |
FCL_EXPORT void fcl::relativeTransform | ( | const Transform3< S > & | T1, |
const Transform3< S > & | T2, | ||
Eigen::MatrixBase< DerivedA > & | R, | ||
Eigen::MatrixBase< DerivedB > & | t | ||
) |
Definition at line 691 of file geometry-inl.h.
Definition at line 323 of file interval_matrix-inl.h.
Definition at line 323 of file interval_matrix-inl.h.
Definition at line 483 of file taylor_matrix-inl.h.
Definition at line 483 of file taylor_matrix-inl.h.
template void fcl::segCoords | ( | double & | t, |
double & | u, | ||
double | a, | ||
double | b, | ||
double | A_dot_B, | ||
double | A_dot_T, | ||
double | B_dot_T | ||
) |
FCL_EXPORT void fcl::segCoords | ( | S & | t, |
S & | u, | ||
S | a, | ||
S | b, | ||
S | A_dot_B, | ||
S | A_dot_T, | ||
S | 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 fcl::segCoords | ( | S & | t, |
S & | u, | ||
S | a, | ||
S | b, | ||
S | A_dot_B, | ||
S | A_dot_T, | ||
S | 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.
template Halfspace< double > fcl::transform | ( | const Halfspace< double > & | a, |
const Transform3< double > & | tf | ||
) |
FCL_EXPORT Halfspace<S> fcl::transform | ( | const Halfspace< S > & | a, |
const Transform3< S > & | 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
Definition at line 168 of file geometry/shape/halfspace-inl.h.
Halfspace<S> fcl::transform | ( | const Halfspace< S > & | a, |
const Transform3< S > & | 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
Definition at line 168 of file geometry/shape/halfspace-inl.h.
template Plane< double > fcl::transform | ( | const Plane< double > & | a, |
const Transform3< double > & | tf | ||
) |
FCL_EXPORT Plane<S> fcl::transform | ( | const Plane< S > & | a, |
const Transform3< S > & | 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
Definition at line 168 of file geometry/shape/plane-inl.h.
Plane<S> fcl::transform | ( | const Plane< S > & | a, |
const Transform3< S > & | 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
Definition at line 168 of file geometry/shape/plane-inl.h.
AABB< S > fcl::translate | ( | const AABB< S > & | aabb, |
const Eigen::MatrixBase< Derived > & | t | ||
) |
translate the center of AABB by t
Definition at line 345 of file AABB-inl.h.
FCL_EXPORT KDOP< S, N > fcl::translate | ( | const KDOP< S, N > & | bv, |
const Eigen::MatrixBase< Derived > & | t | ||
) |
translate the KDOP BV
Definition at line 290 of file kDOP-inl.h.
FCL_EXPORT kIOS<S> fcl::translate | ( | const kIOS< S > & | bv, |
const Eigen::MatrixBase< Derived > & | t | ||
) |
Translate the kIOS BV.
Definition at line 298 of file kIOS-inl.h.
kIOS<S> fcl::translate | ( | const kIOS< S > & | bv, |
const Eigen::MatrixBase< Derived > & | t | ||
) |
Translate the kIOS BV.
Definition at line 298 of file kIOS-inl.h.
template OBBRSS< double > fcl::translate | ( | const OBBRSS< double > & | bv, |
const Vector3< double > & | t | ||
) |
FCL_EXPORT OBBRSS<S> fcl::translate | ( | const OBBRSS< S > & | bv, |
const Vector3< S > & | t | ||
) |
Translate the OBBRSS bv.
Definition at line 175 of file OBBRSS-inl.h.
Translate the OBBRSS bv.
Definition at line 175 of file OBBRSS-inl.h.
FCL_EXPORT Derived::RealScalar fcl::triple | ( | const Eigen::MatrixBase< Derived > & | x, |
const Eigen::MatrixBase< Derived > & | y, | ||
const Eigen::MatrixBase< Derived > & | z | ||
) |
Definition at line 431 of file geometry-inl.h.
template class FCL_EXPORT fcl::AABB< double > |
template class FCL_EXPORT fcl::Box< double > |
template class FCL_EXPORT fcl::BroadPhaseCollisionManager< double > |
template class FCL_EXPORT fcl::BroadPhaseContinuousCollisionManager< double > |
template class FCL_EXPORT fcl::Capsule< double > |
template class FCL_EXPORT fcl::CollisionGeometry< double > |
template class FCL_EXPORT fcl::CollisionObject< double > |
template class FCL_EXPORT fcl::Cone< double > |
template class FCL_EXPORT fcl::ContinuousCollisionObject< double > |
template class FCL_EXPORT fcl::Convex< double > |
template class FCL_EXPORT fcl::Cylinder< double > |
template class FCL_EXPORT fcl::DynamicAABBTreeCollisionManager< double > |
template class FCL_EXPORT fcl::DynamicAABBTreeCollisionManager_Array< double > |
template class FCL_EXPORT fcl::Ellipsoid< double > |
template class FCL_EXPORT fcl::Halfspace< double > |
template class FCL_EXPORT fcl::InterpMotion< double > |
template class FCL_EXPORT fcl::IntervalTreeCollisionManager< double > |
template class FCL_EXPORT fcl::KDOP< double, 16 > |
template class FCL_EXPORT fcl::KDOP< double, 18 > |
template class FCL_EXPORT fcl::KDOP< double, 24 > |
template class FCL_EXPORT fcl::kIOS< double > |
template class FCL_EXPORT fcl::MotionBase< double > |
template class FCL_EXPORT fcl::NaiveCollisionManager< double > |
template class FCL_EXPORT fcl::OBB< double > |
template class FCL_EXPORT fcl::OBBRSS< double > |
template class FCL_EXPORT fcl::Plane< double > |
template class FCL_EXPORT fcl::RNG< double > |
template class FCL_EXPORT fcl::RSS< double > |
template class FCL_EXPORT fcl::SamplerBase< double > |
template class FCL_EXPORT fcl::SamplerSE2< double > |
template class FCL_EXPORT fcl::SamplerSE2_disk< double > |
template class FCL_EXPORT fcl::SamplerSE3Euler< double > |
template class FCL_EXPORT fcl::SamplerSE3Euler_ball< double > |
template class FCL_EXPORT fcl::SamplerSE3Quat< double > |
template class FCL_EXPORT fcl::SamplerSE3Quat_ball< double > |
template class FCL_EXPORT fcl::SaPCollisionManager< double > |
template class FCL_EXPORT fcl::ScrewMotion< double > |
template class FCL_EXPORT fcl::ShapeBase< double > |
template class FCL_EXPORT fcl::Sphere< double > |
template class FCL_EXPORT fcl::SplineMotion< double > |
template class FCL_EXPORT fcl::SSaPCollisionManager< double > |
template class FCL_EXPORT fcl::TaylorModel< double > |
template class FCL_EXPORT fcl::TMatrix3< double > |
template class FCL_EXPORT fcl::TranslationMotion< double > |
template class FCL_EXPORT fcl::TriangleMotionBoundVisitor< double > |
template class FCL_EXPORT fcl::TriangleP< double > |
template class FCL_EXPORT fcl::TVector3< double > |
template class FCL_EXPORT fcl::Variance3< double > |