44 , planning_context_(pc)
45 , group_name_(pc->getGroupName())
46 , tss_(pc->getCompleteInitialRobotState())
49 specs_.clearanceComputationType = ompl::base::StateValidityCheckerSpecs::APPROXIMATE;
50 specs_.hasValidDirectionComputation =
false;
96 for (std::set<collision_detection::CostSource>::const_iterator it = res.
cost_sources.begin();
98 cost += it->cost * it->getVolume();
116 if (!si_->satisfiesBounds(state))
129 if (kset && !kset->decide(*kstate, verbose).satisfied)
146 if (!si_->satisfiesBounds(state))
188 if (!si_->satisfiesBounds(state))
192 const_cast<ob::State*
>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
201 if (kset && !kset->decide(*kstate, verbose).satisfied)
203 const_cast<ob::State*
>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
210 const_cast<ob::State*
>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
220 const_cast<ob::State*
>(state)->as<ModelBasedStateSpace::StateType>()->markValid();
225 const_cast<ob::State*
>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
240 if (!si_->satisfiesBounds(state))
244 const_cast<ob::State*
>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid(0.0);
259 const_cast<ob::State*
>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid(dist);
collision_detection::CollisionRequest collision_request_simple_verbose_
collision_detection::CollisionRequest collision_request_with_cost_
#define ROS_INFO_NAMED(name,...)
bool useStateValidityCache() const
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)
const planning_scene::PlanningSceneConstPtr & getPlanningScene() const
robot_state::RobotState * getStateStorage() const
const ModelBasedPlanningContext * planning_context_
std::set< CostSource > cost_sources
bool isValidWithoutCache(const ompl::base::State *state, bool verbose) const
const kinematic_constraints::KinematicConstraintSetPtr & getPathConstraints() const
virtual double clearance(const ompl::base::State *state) const
bool isMarkedValid() const
const std::string & getGroupName() const
bool isValidityKnown() const
collision_detection::CollisionRequest collision_request_with_distance_verbose_
An interface for a OMPL state validity checker.
double distance(const urdf::Pose &transform)
virtual bool isValid(const ompl::base::State *state) const
const ModelBasedStateSpacePtr & getOMPLStateSpace() const