ompl::app::FCLStateValidityChecker< T > Class Template Reference

Wrapper for FCL collision and distance checking. More...

#include <omplapp/geometry/detail/FCLStateValidityChecker.h>

Inheritance diagram for ompl::app::FCLStateValidityChecker< T >:

Public Member Functions

 FCLStateValidityChecker (const ob::SpaceInformationPtr &si, const GeometrySpecification &geom, const GeometricStateExtractor &se, bool selfCollision)
 
bool isValid (const ob::State *state) const override
 Checks whether the given robot state collides with the environment or itself.
 
double clearance (const ob::State *state) const override
 Returns the minimum distance from the given robot state and the environment.
 
const FCLMethodWrapperPtr & getFCLWrapper () const
 
- Public Member Functions inherited from ompl::base::StateValidityChecker
 StateValidityChecker (SpaceInformation *si)
 Constructor.
 
 StateValidityChecker (const SpaceInformationPtr &si)
 Constructor.
 
virtual bool isValid (const State *state, double &dist) const
 Return true if the state state is valid. In addition, set dist to the distance to the nearest invalid state.
 
virtual bool isValid (const State *state, double &dist, State *validState, bool &validStateAvailable) const
 Return true if the state state is valid. In addition, set dist to the distance to the nearest invalid state (using clearance()). If a direction that moves state away from being invalid is available, a valid state in that direction is also set (validState). validStateAvailable is set to true if validState is updated.
 
virtual double clearance (const State *state, State *, bool &validStateAvailable) const
 Report the distance to the nearest invalid state when starting from state, and if possible, also specify a valid state validState in the direction that moves away from the colliding state. The validStateAvailable flag is set to true if validState is updated.
 
const StateValidityCheckerSpecsgetSpecs () const
 Return the specifications (capabilities of this state validity checker)
 
virtual bool operator== (const StateValidityChecker &) const
 Checks for equivalence between two Statevaliditycheckers.
 
bool operator!= (const StateValidityChecker &rhs) const
 

Protected Attributes

OMPL_FCL_StateType< T > stateConvertor_
 Object to convert a configuration of the robot to a type desirable for FCL.
 
FCLMethodWrapperPtr fclWrapper_
 Wrapper for FCL collision and distance methods.
 
- Protected Attributes inherited from ompl::base::StateValidityChecker
SpaceInformationsi_
 The instance of space information this state validity checker operates on.
 
StateValidityCheckerSpecs specs_
 The specifications of the state validity checker (its capabilities)
 

Detailed Description

template<MotionModel T>
class ompl::app::FCLStateValidityChecker< T >

Wrapper for FCL collision and distance checking.

Definition at line 98 of file FCLStateValidityChecker.h.


The documentation for this class was generated from the following file: