52 #include <ompl/base/StateValidityChecker.h> 
   56 class ModelBasedPlanningContext;
 
   65   bool isValid(
const ompl::base::State* state)
 const override 
   70   bool isValid(
const ompl::base::State* state, 
double& dist)
 const override 
   75   bool isValid(
const ompl::base::State* state, 
double& dist, ompl::base::State* ,
 
   76                bool& )
 const override 
   81   virtual bool isValid(
const ompl::base::State* state, 
bool verbose) 
const;
 
   82   virtual bool isValid(
const ompl::base::State* state, 
double& dist, 
bool verbose) 
const;
 
   84   virtual double cost(
const ompl::base::State* state) 
const;
 
   85   double clearance(
const ompl::base::State* state) 
const override;
 
  154   bool isValid(
const ompl::base::State* wrapped_state, 
bool verbose) 
const override;
 
  155   bool isValid(
const ompl::base::State* wrapped_state, 
double& dist, 
bool verbose) 
const override;
 
A StateValidityChecker that can handle states of type ompl::base::ConstraintStateSpace::StateType.
 
ConstrainedPlanningStateValidityChecker(const ModelBasedPlanningContext *planning_context)
 
bool isValid(const ompl::base::State *state) const override
 
An interface for a OMPL state validity checker.
 
collision_detection::CollisionRequest collision_request_simple_
 
StateValidityChecker(const ModelBasedPlanningContext *planning_context)
 
const ModelBasedPlanningContext * planning_context_
 
double clearance(const ompl::base::State *state) const override
 
void setVerbose(bool flag)
 
bool isValid(const ompl::base::State *state, double &dist, ompl::base::State *, bool &) const override
 
virtual double cost(const ompl::base::State *state) const
 
bool isValid(const ompl::base::State *state) const override
 
collision_detection::CollisionRequest collision_request_with_distance_
 
collision_detection::CollisionRequest collision_request_with_cost_
 
collision_detection::CollisionRequest collision_request_with_distance_verbose_
 
bool isValid(const ompl::base::State *state, double &dist) const override
 
collision_detection::CollisionRequest collision_request_simple_verbose_
 
The MoveIt interface to OMPL.
 
Representation of a collision checking request.