37 #ifndef MOVEIT_OMPL_INTERFACE_DETAIL_STATE_VALIDITY_CHECKER_ 38 #define MOVEIT_OMPL_INTERFACE_DETAIL_STATE_VALIDITY_CHECKER_ 41 #include <moveit/collision_detection/collision_common.h> 42 #include <ompl/base/StateValidityChecker.h> 46 class ModelBasedPlanningContext;
55 virtual bool isValid(
const ompl::base::State* state)
const 60 virtual bool isValid(
const ompl::base::State* state,
double& dist)
const 66 bool isValid(
const ompl::base::State* state,
double& dist,
bool verbose)
const;
68 virtual double cost(
const ompl::base::State* state)
const;
69 virtual double clearance(
const ompl::base::State* state)
const;
78 bool isValidWithCache(
const ompl::base::State* state,
double& dist,
bool verbose)
const;
collision_detection::CollisionRequest collision_request_simple_verbose_
collision_detection::CollisionRequest collision_request_with_cost_
bool isValidWithCache(const ompl::base::State *state, bool verbose) const
collision_detection::CollisionRequest collision_request_simple_
virtual double cost(const ompl::base::State *state) const
void setVerbose(bool flag)
collision_detection::CollisionRequest collision_request_with_distance_
StateValidityChecker(const ModelBasedPlanningContext *planning_context)
The MoveIt! interface to OMPL.
const ModelBasedPlanningContext * planning_context_
bool isValidWithoutCache(const ompl::base::State *state, bool verbose) const
virtual bool isValid(const ompl::base::State *state, double &dist) const
virtual double clearance(const ompl::base::State *state) const
collision_detection::CollisionRequest collision_request_with_distance_verbose_
An interface for a OMPL state validity checker.
virtual bool isValid(const ompl::base::State *state) const