ompl::app::FCLContinuousMotionValidator Class Reference

A motion validator that utilizes FCL's continuous collision checking. More...

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

Inheritance diagram for ompl::app::FCLContinuousMotionValidator:

Public Member Functions

 FCLContinuousMotionValidator (ob::SpaceInformation *si, MotionModel mm)
 Constructor.
 
 FCLContinuousMotionValidator (const ob::SpaceInformationPtr &si, MotionModel mm)
 Constructor.
 
 ~FCLContinuousMotionValidator () override=default
 Destructor.
 
bool checkMotion (const ob::State *s1, const ob::State *s2) const override
 Returns true if motion between s1 and s2 is collision free.
 
bool checkMotion (const ob::State *s1, const ob::State *s2, std::pair< ob::State *, double > &lastValid) const override
 Checks the motion between s1 and s2. If the motion is invalid, lastValid contains the last valid state and the parameterized time [0,1) when this state occurs.
 
- Public Member Functions inherited from ompl::base::MotionValidator
 MotionValidator (SpaceInformation *si)
 Constructor.
 
 MotionValidator (const SpaceInformationPtr &si)
 Constructor.
 
virtual bool checkMotion (const State *s1, const State *s2, std::pair< State *, double > &lastValid) const =0
 Check if the path between two states is valid. Also compute the last state that was valid and the time of that state. The time is used to parametrize the motion from s1 to s2, s1 being at t = 0 and s2 being at t = 1. This function assumes s1 is valid. More...
 
unsigned int getValidMotionCount () const
 Get the number of segments that tested as valid.
 
unsigned int getInvalidMotionCount () const
 Get the number of segments that tested as invalid.
 
unsigned int getCheckedMotionCount () const
 Get the total number of segments tested, regardless of result.
 
double getValidMotionFraction () const
 Get the fraction of segments that tested as valid.
 
void resetMotionCounter ()
 Reset the counters for valid and invalid segments.
 

Protected Member Functions

void defaultSettings (MotionModel mm)
 Restore settings to default values.
 

Protected Attributes

FCLMethodWrapperPtr fclWrapper_
 Wrapper for FCL collision and distance methods.
 
ob::StateSpacestateSpace_
 Handle to the statespace that this motion validator operates in.
 
- Protected Attributes inherited from ompl::base::MotionValidator
SpaceInformationsi_
 The instance of space information this state validity checker operates on.
 
unsigned int valid_
 Number of valid segments.
 
unsigned int invalid_
 Number of invalid segments.
 

Detailed Description

A motion validator that utilizes FCL's continuous collision checking.

Definition at line 46 of file FCLContinuousMotionValidator.h.


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