Public Types |
Public Member Functions |
Protected Member Functions |
Protected Attributes |
List of all members
ompl::app::FCLMethodWrapper Class Reference
Wrapper for FCL discrete and continuous collision checking and distance queries. More...
#include <omplapp/geometry/detail/FCLMethodWrapper.h>
Public Types | |
using | Vector3 = fcl::Vec3f |
using | Quaternion = fcl::Quaternion3f |
using | Transform = fcl::Transform3f |
using | BVType = fcl::OBBRSS |
using | Model = fcl::BVHModel< BVType > |
using | MeshDistanceTraversalNodeOBBRSS = fcl::MeshDistanceTraversalNodeOBBRSS |
using | CollisionRequest = fcl::CollisionRequest |
using | CollisionResult = fcl::CollisionResult |
using | ContinuousCollisionRequest = fcl::ContinuousCollisionRequest |
using | ContinuousCollisionResult = fcl::ContinuousCollisionResult |
using | DistanceRequest = fcl::DistanceRequest |
using | DistanceResult = fcl::DistanceResult |
using | FCLPoseFromStateCallback = std::function< void(Transform &, const base::State *)> |
Public Member Functions | |
FCLMethodWrapper (const GeometrySpecification &geom, GeometricStateExtractor se, bool selfCollision, FCLPoseFromStateCallback poseCallback) | |
virtual bool | isValid (const base::State *state) const |
Checks whether the given robot state collides with the environment or itself. | |
virtual bool | isValid (const base::State *s1, const base::State *s2, double &collisionTime) const |
Check the continuous motion between s1 and s2. If there is a collision collisionTime will contain the parameterized time to collision in the range [0,1). | |
virtual double | clearance (const base::State *state) const |
Returns the minimum distance from the given robot state and the environment. | |
Protected Member Functions | |
void | configure (const GeometrySpecification &geom) |
Configures the geometry of the robot and the environment to setup validity checking. | |
std::pair< std::vector< Vector3 >, std::vector< fcl::Triangle > > | getFCLModelFromScene (const aiScene *scene, const aiVector3D ¢er) const |
Convert a mesh to a FCL BVH model. | |
std::pair< std::vector< Vector3 >, std::vector< fcl::Triangle > > | getFCLModelFromScene (const std::vector< const aiScene * > &scenes, const std::vector< aiVector3D > ¢er) const |
Convert a mesh to a FCL BVH model. | |
Protected Attributes | |
Model | environment_ |
Geometric model used for the environment. | |
std::vector< Model * > | robotParts_ |
List of components for the geometric model of the robot. | |
GeometricStateExtractor | extractState_ |
Callback to get the geometric portion of a specific state. | |
bool | selfCollision_ |
Flag indicating whether the geometry is checked for self collisions. | |
FCLPoseFromStateCallback | poseFromStateCallback_ |
Callback to extract translation and rotation from a state. | |
Detailed Description
Wrapper for FCL discrete and continuous collision checking and distance queries.
Definition at line 68 of file FCLMethodWrapper.h.
The documentation for this class was generated from the following file:
- omplapp/geometry/detail/FCLMethodWrapper.h