fcl::AABB | A class describing the AABB collision structure, which is a box in 3D space determined by two diagonal points |
fcl::tools::Profiler::AvgInfo | Information maintained about averaged values |
fcl::BallEulerJoint | |
fcl::Box | Center at zero point, axis aligned box |
fcl::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 |
fcl::BVFitter< BV > | The class for the default algorithm fitting a bounding volume to a set of points |
fcl::BVFitter< kIOS > | Specification of BVFitter for kIOS bounding volume |
fcl::BVFitter< OBB > | Specification of BVFitter for OBB bounding volume |
fcl::BVFitter< OBBRSS > | Specification of BVFitter for OBBRSS bounding volume |
fcl::BVFitter< RSS > | Specification of BVFitter for RSS bounding volume |
fcl::BVFitterBase< BV > | Interface for fitting a bv given the triangles or points inside it |
fcl::BVHCollisionTraversalNode< BV > | Traversal node for collision between BVH models |
fcl::BVHContinuousCollisionPair | Traversal node for continuous collision between BVH models |
fcl::BVHDistanceTraversalNode< BV > | Traversal node for distance computation between BVH models |
fcl::BVHFrontNode | Front list acceleration for collision Front list is a set of internal and leaf nodes in the BVTT hierarchy, where the traversal terminates while performing a query during a given time instance. The front list reflects the subset of a BVTT that is traversed for that particular proximity query |
fcl::BVHModel< BV > | A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as a degraded version of mesh) |
fcl::BVHShapeCollider< T_BVH, T_SH, NarrowPhaseSolver > | |
fcl::BVHShapeCollider< kIOS, T_SH, NarrowPhaseSolver > | |
fcl::BVHShapeCollider< OBB, T_SH, NarrowPhaseSolver > | |
fcl::BVHShapeCollider< OBBRSS, T_SH, NarrowPhaseSolver > | |
fcl::BVHShapeCollider< RSS, T_SH, NarrowPhaseSolver > | |
fcl::BVHShapeCollisionTraversalNode< BV, S > | Traversal node for collision between BVH and shape |
fcl::BVHShapeDistancer< T_BVH, T_SH, NarrowPhaseSolver > | |
fcl::BVHShapeDistancer< kIOS, T_SH, NarrowPhaseSolver > | |
fcl::BVHShapeDistancer< OBBRSS, T_SH, NarrowPhaseSolver > | |
fcl::BVHShapeDistancer< RSS, T_SH, NarrowPhaseSolver > | |
fcl::BVHShapeDistanceTraversalNode< BV, S > | Traversal node for distance computation between BVH and shape |
fcl::BVNode< BV > | 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 |
fcl::BVNodeBase | BVNodeBase encodes the tree structure for BVH |
fcl::BVSplitter< BV > | A class describing the split rule that splits each BV node |
fcl::BVSplitterBase< BV > | Base interface for BV splitting algorithm |
fcl::BVT | Bounding volume test structure |
fcl::BVT_Comparer | Comparer between two BVT |
fcl::BVTQ | |
fcl::Capsule | Center at zero point capsule |
fcl::details::ccd_box_t | |
fcl::details::ccd_cap_t | |
fcl::details::ccd_cone_t | |
fcl::details::ccd_convex_t | |
fcl::details::ccd_cyl_t | |
fcl::details::ccd_obj_t | |
fcl::details::ccd_sphere_t | |
fcl::details::ccd_triangle_t | |
fcl::CollisionData | Collision data stores the collision request and the result given by collision algorithm |
fcl::CollisionFunctionMatrix< NarrowPhaseSolver > | Collision matrix stores the functions for collision between different types of objects and provides a uniform call interface |
fcl::CollisionGeometry | The geometry for the object for collision or distance computation |
fcl::CollisionObject | Object for collision or distance computation, contains the geometry and the transform information |
fcl::CollisionRequest | Request to the collision algorithm |
fcl::CollisionResult | Collision result |
fcl::CollisionTraversalNodeBase | Node structure encoding the information required for collision traversal |
fcl::Cone | Center at zero cone |
fcl::ConservativeAdvancementStackData | |
fcl::Contact | Contact information returned by collision |
fcl::details::ContactPoint | |
fcl::Convex | Convex polytope |
fcl::CostSource | Cost source describes an area with a cost. The area is described by an AABB region |
fcl::Cylinder | Center at zero cylinder |
fcl::DistanceData | Distance data stores the distance request and the result given by distance algorithm |
fcl::DistanceFunctionMatrix< NarrowPhaseSolver > | Distance matrix stores the functions for distance between different types of objects and provides a uniform call interface |
fcl::DistanceRequest | Request to the distance computation |
fcl::DistanceRes | @ brief Structure for minimum distance between two meshes and the corresponding nearest point pair |
fcl::DistanceResult | Distance result |
fcl::DistanceTraversalNodeBase | Node structure encoding the information required for distance traversal |
fcl::DummyCollisionObject | Dummy collision object with a point AABB |
fcl::DynamicAABBTreeCollisionManager | |
fcl::DynamicAABBTreeCollisionManager_Array | |
fcl::Convex::Edge | |
fcl::IntervalTreeCollisionManager::EndPoint | SAP end point |
fcl::SaPCollisionManager::EndPoint | End point for an interval |
fcl::details::EPA | Class for EPA algorithm |
fcl::details::GJK | Class for GJK algorithm |
fcl::details::GJKInitializer< T > | Initialize GJK stuffs |
fcl::details::GJKInitializer< Box > | Initialize GJK Box |
fcl::details::GJKInitializer< Capsule > | Initialize GJK Capsule |
fcl::details::GJKInitializer< Cone > | Initialize GJK Cone |
fcl::details::GJKInitializer< Convex > | Initialize GJK Convex |
fcl::details::GJKInitializer< Cylinder > | Initialize GJK Cylinder |
fcl::details::GJKInitializer< Sphere > | Initialize GJK Sphere |
fcl::GJKSolver_indep | Collision and distance solver based on GJK algorithm implemented in fcl (rewritten the code from the GJK in bullet) |
fcl::GJKSolver_libccd | Collision and distance solver based on libccd library |
fcl::Halfspace | Half Space: this is equivalent to the Plane 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 |
fcl::implementation_array::HierarchyTree< BV > | Class for hierarchy tree structure |
fcl::HierarchyTree< BV > | Class for hierarchy tree structure |
fcl::IMatrix3 | |
fcl::InterpMotion< BV > | 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 |
fcl::Interpolation | |
fcl::InterpolationFactory | |
fcl::InterpolationLinear | |
fcl::Intersect | CCD intersect kernel among primitives |
fcl::Interval | Interval class for [a, b] |
fcl::IntervalTree | Interval tree |
fcl::IntervalTreeCollisionManager | Collision manager based on interval tree |
fcl::IntervalTreeNode | The node for interval tree |
fcl::SaPCollisionManager::isNotValidPair | Functor to help remove collision pairs no longer valid (i.e., should be culled away) |
fcl::SaPCollisionManager::isUnregistered | Functor to help unregister one object |
fcl::it_recursion_node | Class describes the information needed when we take the right branch in searching for intervals but possibly come back and check the left branch as well |
fcl::IVector3 | |
fcl::Joint | Base Joint |
fcl::JointConfig | |
fcl::KDOP< N > | 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 |
fcl::kIOS | A class describing the kIOS collision structure, which is a set of spheres |
fcl::kIOS::kIOS_Sphere | One sphere in kIOS |
fcl::Link | |
fcl::details::Matrix3Data< T > | |
fcl::Matrix3fX< T > | Matrix2 class wrapper. the core data is in the template parameter class |
fcl::MeshCollisionTraversalNode< BV > | Traversal node for collision between two meshes |
fcl::MeshCollisionTraversalNodekIOS | |
fcl::MeshCollisionTraversalNodeOBB | Traversal node for collision between two meshes if their underlying BVH node is oriented node (OBB, RSS, OBBRSS, kIOS) |
fcl::MeshCollisionTraversalNodeOBBRSS | |
fcl::MeshCollisionTraversalNodeRSS | |
fcl::MeshConservativeAdvancementTraversalNode< BV > | Continuous collision node using conservative advancement. when using this default version, must refit the BVH in current configuration (R_t, T_t) into default configuration |
fcl::MeshConservativeAdvancementTraversalNodeRSS | |
fcl::MeshContinuousCollisionTraversalNode< BV > | Traversal node for continuous collision between meshes |
fcl::MeshDistanceTraversalNode< BV > | Traversal node for distance computation between two meshes |
fcl::MeshDistanceTraversalNodekIOS | |
fcl::MeshDistanceTraversalNodeOBBRSS | |
fcl::MeshDistanceTraversalNodeRSS | Traversal node for distance computation between two meshes if their underlying BVH node is oriented node (RSS, OBBRSS, kIOS) |
fcl::MeshOcTreeCollisionTraversalNode< BV, NarrowPhaseSolver > | Traversal node for mesh-octree collision |
fcl::MeshOcTreeDistanceTraversalNode< BV, NarrowPhaseSolver > | Traversal node for mesh-octree distance |
fcl::MeshShapeCollisionTraversalNode< BV, S, NarrowPhaseSolver > | Traversal node for collision between mesh and shape |
fcl::MeshShapeCollisionTraversalNodekIOS< S, NarrowPhaseSolver > | |
fcl::MeshShapeCollisionTraversalNodeOBB< S, NarrowPhaseSolver > | Traversal node for mesh and shape, when mesh BVH is one of the oriented node (OBB, RSS, OBBRSS, kIOS) |
fcl::MeshShapeCollisionTraversalNodeOBBRSS< S, NarrowPhaseSolver > | |
fcl::MeshShapeCollisionTraversalNodeRSS< S, NarrowPhaseSolver > | |
fcl::MeshShapeDistanceTraversalNode< BV, S, NarrowPhaseSolver > | Traversal node for distance between mesh and shape |
fcl::MeshShapeDistanceTraversalNodekIOS< S, NarrowPhaseSolver > | |
fcl::MeshShapeDistanceTraversalNodeOBBRSS< S, NarrowPhaseSolver > | |
fcl::MeshShapeDistanceTraversalNodeRSS< S, NarrowPhaseSolver > | Traversal node for distance between mesh and shape, when mesh BVH is one of the oriented node (RSS, OBBRSS, kIOS) |
fcl::details::MinkowskiDiff | Minkowski difference class of two shapes |
fcl::Model | |
fcl::ModelConfig | |
fcl::ModelParseError | |
fcl::morton_functor< T > | Functor to compute the morton code for a given AABB |
fcl::morton_functor< boost::dynamic_bitset<> > | Functor to compute n bit morton code for a given AABB |
fcl::morton_functor< FCL_UINT32 > | Functor to compute 30 bit morton code for a given AABB |
fcl::morton_functor< FCL_UINT64 > | Functor to compute 60 bit morton code for a given AABB |
fcl::MotionBase< BV > | |
fcl::NaiveCollisionManager | Brute force N-body collision manager |
fcl::implementation_array::NodeBase< BV > | |
fcl::NodeBase< BV > | Dynamic AABB tree node |
fcl::implementation_array::nodeBaseLess< BV > | Functor comparing two nodes |
fcl::OBB | Oriented bounding box class |
fcl::OBBRSS | Class merging the OBB and RSS, can handle collision and distance simultaneously |
fcl::OcTree | Octree is one type of collision geometry which can encode uncertainty information in the sensor data |
fcl::OcTreeCollisionTraversalNode< NarrowPhaseSolver > | Traversal node for octree collision |
fcl::OcTreeDistanceTraversalNode< NarrowPhaseSolver > | Traversal node for octree distance |
fcl::OcTreeMeshCollisionTraversalNode< BV, NarrowPhaseSolver > | Traversal node for octree-mesh collision |
fcl::OcTreeMeshDistanceTraversalNode< BV, NarrowPhaseSolver > | Traversal node for octree-mesh distance |
fcl::OcTreeShapeCollisionTraversalNode< S, NarrowPhaseSolver > | Traversal node for octree-shape collision |
fcl::OcTreeShapeDistanceTraversalNode< S, NarrowPhaseSolver > | Traversal node for octree-shape distance |
fcl::OcTreeSolver< NarrowPhaseSolver > | Algorithms for collision related with octree |
fcl::tools::Profiler::PerThread | Information to be maintained for each thread |
fcl::Plane | Infinite plane |
fcl::PolySolver | A class solves polynomial degree (1,2,3) equations |
fcl::PrismaticJoint | |
fcl::tools::Profiler | This is a simple thread-safe tool for counting time spent in various chunks of code. This is different from external profiling tools in that it allows the user to count time spent in various bits of code (sub-function granularity) or count how many times certain pieces of code are executed |
fcl::Quaternion3f | Quaternion used locally by InterpMotion |
fcl::RevoluteJoint | |
fcl::RSS | A class for rectangle sphere-swept bounding volume |
fcl::SaPCollisionManager::SaPAABB | SAP interval for one object |
fcl::SaPCollisionManager | Rigorous SAP collision manager |
fcl::IntervalTreeCollisionManager::SAPInterval | Extention interval tree's interval to SAP interval, adding more information |
fcl::SaPCollisionManager::SaPPair | A pair of objects that are not culling away and should further check collision |
fcl::tools::Profiler::ScopedBlock | This instance will call Profiler::begin() when constructed and Profiler::end() when it goes out of scope |
fcl::tools::Profiler::ScopedStart | This instance will call Profiler::start() when constructed and Profiler::stop() when it goes out of scope. If the profiler was already started, this block's constructor and destructor take no action |
fcl::ScrewMotion< BV > | |
fcl::ShapeBase | Base class for all basic geometric shapes |
fcl::ShapeBVHCollisionTraversalNode< S, BV > | Traversal node for collision between shape and BVH |
fcl::ShapeBVHDistanceTraversalNode< S, BV > | Traversal node for distance computation between shape and BVH |
fcl::ShapeCollisionTraversalNode< S1, S2, NarrowPhaseSolver > | Traversal node for collision between two shapes |
fcl::ShapeDistanceTraversalNode< S1, S2, NarrowPhaseSolver > | Traversal node for distance between two shapes |
fcl::ShapeMeshCollisionTraversalNode< S, BV, NarrowPhaseSolver > | Traversal node for collision between shape and mesh |
fcl::ShapeMeshCollisionTraversalNodekIOS< S, NarrowPhaseSolver > | |
fcl::ShapeMeshCollisionTraversalNodeOBB< S, NarrowPhaseSolver > | Traversal node for shape and mesh, when mesh BVH is one of the oriented node (OBB, RSS, OBBRSS, kIOS) |
fcl::ShapeMeshCollisionTraversalNodeOBBRSS< S, NarrowPhaseSolver > | |
fcl::ShapeMeshCollisionTraversalNodeRSS< S, NarrowPhaseSolver > | |
fcl::ShapeMeshDistanceTraversalNode< S, BV, NarrowPhaseSolver > | Traversal node for distance between shape and mesh |
fcl::ShapeMeshDistanceTraversalNodekIOS< S, NarrowPhaseSolver > | |
fcl::ShapeMeshDistanceTraversalNodeOBBRSS< S, NarrowPhaseSolver > | |
fcl::ShapeMeshDistanceTraversalNodeRSS< S, NarrowPhaseSolver > | |
fcl::ShapeOcTreeCollisionTraversalNode< S, NarrowPhaseSolver > | Traversal node for shape-octree collision |
fcl::ShapeOcTreeDistanceTraversalNode< S, NarrowPhaseSolver > | Traversal node for shape-octree distance |
fcl::SimpleHashTable< Key, Data, HashFnc > | A simple hash table implemented as multiple buckets. HashFnc is any extended hash function: HashFnc(key) = {index1, index2, ..., } |
fcl::SimpleInterval | Interval trees implemented using red-black-trees as described in the book Introduction_To_Algorithms_ by Cormen, Leisserson, and Rivest. Can be replaced in part by boost::icl::interval_set, which is only supported after boost 1.46 and does not support delete node routine |
fcl::details::GJK::Simplex | |
fcl::details::EPA::SimplexF | |
fcl::details::EPA::SimplexHorizon | |
fcl::details::EPA::SimplexList | |
fcl::details::GJK::SimplexV | |
fcl::HierarchyTree< BV >::SortByMorton | |
fcl::implementation_array::HierarchyTree< BV >::SortByMorton | |
fcl::SortByXLow | Functor sorting objects according to the AABB lower x bound |
fcl::SortByYLow | Functor sorting objects according to the AABB lower y bound |
fcl::SortByZLow | Functor sorting objects according to the AABB lower z bound |
fcl::SparseHashTable< Key, Data, HashFnc, TableT > | A hash table implemented using unordered_map |
fcl::SpatialHash | Spatial hash function: hash an AABB to a set of integer values |
fcl::SpatialHashingCollisionManager< HashTable > | Spatial hashing collision mananger |
fcl::Sphere | Center at zero point sphere |
fcl::SplineMotion< BV > | |
fcl::SSaPCollisionManager | Simple SAP collision manager |
fcl::details::sse_meta_d4 | |
fcl::details::sse_meta_f12 | |
fcl::details::sse_meta_f16 | |
fcl::details::sse_meta_f4 | |
fcl::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 |
fcl::tools::Profiler::TimeInfo | Information about time spent in a section of the code |
fcl::TimeInterval | |
fcl::Timer | |
fcl::TMatrix3 | |
fcl::Transform3f | Simple transform class used locally by InterpMotion |
fcl::TraversalNodeBase | Node structure encoding the information required for traversal |
fcl::Triangle | Triangle with 3 indices for points |
fcl::Triangle2 | Triangle stores the points instead of only indices of points |
fcl::TriangleDistance | |
TStruct | |
fcl::TVector3 | |
fcl::unordered_map_hash_table< U, V > | |
fcl::Variance3f | Class for variance matrix in 3d |
fcl::details::Vec3Data< T > | |
fcl::Vec3fX< T > | Vector3 class wrapper. The core data is in the template parameter class |