39 #include <ompl/base/spaces/constraint/ConstrainedStateSpace.h> 
   40 #include <rclcpp/logger.hpp> 
   41 #include <rclcpp/logging.hpp> 
   45 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit.ompl_planning.state_validity_checker");
 
   49   , planning_context_(pc)
 
   50   , group_name_(pc->getGroupName())
 
   51   , tss_(pc->getCompleteInitialRobotState())
 
   54   specs_.clearanceComputationType = ompl::base::StateValidityCheckerSpecs::APPROXIMATE;
 
   55   specs_.hasValidDirectionComputation = 
false;
 
   78   assert(state != 
nullptr);
 
   85   if (!si_->satisfiesBounds(state))
 
   89       RCLCPP_INFO(LOGGER, 
"State outside bounds");
 
   91     const_cast<ob::State*
>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
 
  100   if (kset && !kset->decide(*robot_state, verbose).satisfied)
 
  102     const_cast<ob::State*
>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
 
  109     const_cast<ob::State*
>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
 
  119     const_cast<ob::State*
>(state)->as<ModelBasedStateSpace::StateType>()->markValid();
 
  123     const_cast<ob::State*
>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
 
  130   assert(state != 
nullptr);
 
  139   if (!si_->satisfiesBounds(state))
 
  143       RCLCPP_INFO(LOGGER, 
"State outside bounds");
 
  145     const_cast<ob::State*
>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid(0.0);
 
  160       const_cast<ob::State*
>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid(dist);
 
  182   assert(state != 
nullptr);
 
  202   assert(state != 
nullptr);
 
  216   assert(wrapped_state != 
nullptr);
 
  218   auto state = wrapped_state->as<ompl::base::ConstrainedStateSpace::StateType>()->
getState();
 
  227   if (!si_->satisfiesBounds(wrapped_state))  
 
  229     RCLCPP_DEBUG(LOGGER, 
"State outside bounds");
 
  230     const_cast<ob::State*
>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
 
  240   if (kset && !kset->decide(*robot_state, verbose).satisfied)
 
  242     const_cast<ob::State*
>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
 
  249     const_cast<ob::State*
>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
 
  259     const_cast<ob::State*
>(state)->as<ModelBasedStateSpace::StateType>()->markValid();
 
  263     const_cast<ob::State*
>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
 
  271   assert(wrapped_state != 
nullptr);
 
  273   auto state = wrapped_state->as<ompl::base::ConstrainedStateSpace::StateType>()->
getState();
 
  284   if (!si_->satisfiesBounds(wrapped_state))  
 
  286     RCLCPP_DEBUG(LOGGER, 
"State outside bounds");
 
  287     const_cast<ob::State*
>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid(0.0);
 
  298   if (kset && !kset->decide(*robot_state, verbose).satisfied)
 
  300     const_cast<ob::State*
>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
 
Representation of a robot's state. This includes position, velocity, acceleration and effort.
 
bool isValid(const ompl::base::State *state) const override
 
const kinematic_constraints::KinematicConstraintSetPtr & getPathConstraints() const
 
const ModelBasedStateSpacePtr & getOMPLStateSpace() const
 
bool isValidityKnown() const
 
bool isGoalDistanceKnown() const
 
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)
 
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_
 
collision_detection::CollisionRequest collision_request_simple_verbose_
 
moveit::core::RobotState * getStateStorage() const
 
const std::string & getGroupName() const
Get the name of the group this planning context is for.
 
const planning_scene::PlanningSceneConstPtr & getPlanningScene() const
Get the planning scene associated to this planning context.
 
The MoveIt interface to OMPL.
 
double distance(const urdf::Pose &transform)
 
std::string group_name
The group name to check collisions for (optional; if empty, assume the complete robot)
 
bool verbose
Flag indicating whether information about detected collisions should be reported.
 
bool cost
If true, a collision cost is computed.
 
bool distance
If true, compute proximity distance.
 
Representation of a collision checking result.
 
std::set< CostSource > cost_sources
These are the individual cost sources when costs are computed.
 
double distance
Closest distance between two bodies.
 
bool collision
True if collision was found, false otherwise.
 
When collision costs are computed, this structure contains information about the partial cost incurre...
 
double getVolume() const
Get the volume of the AABB around the cost source.
 
double cost
The partial cost (the probability of existence for the object there is a collision with)
 
Struct for containing the results of constraint evaluation.
 
bool satisfied
Whether or not the constraint or constraints were satisfied.
 
double distance
The distance evaluation from the constraint or constraints.
 
bool getState(const std::shared_ptr< moveit_msgs::srv::GetRobotStateFromWarehouse::Request > &request, const std::shared_ptr< moveit_msgs::srv::GetRobotStateFromWarehouse::Response > &response, moveit_warehouse::RobotStateStorage &rs)