40 #include <moveit/collision_detection/collision_common.h>
41 #include <ompl/base/StateValidityChecker.h>
45 class ModelBasedPlanningContext;
48 class StateValidityChecker :
public ompl::base::StateValidityChecker
53 bool isValid(
const ompl::base::State* state)
const override
58 bool isValid(
const ompl::base::State* state,
double& dist)
const override
63 bool isValid(
const ompl::base::State* state,
double& dist, ompl::base::State* ,
64 bool& )
const override
69 bool isValid(
const ompl::base::State* state,
bool verbose)
const;
70 bool isValid(
const ompl::base::State* state,
double& dist,
bool verbose)
const;
72 virtual double cost(
const ompl::base::State* state)
const;
73 double clearance(
const ompl::base::State* state)
const override;