39#include <ompl/base/spaces/constraint/ConstrainedStateSpace.h>
40#include <rclcpp/logger.hpp>
41#include <rclcpp/logging.hpp>
56 , planning_context_(pc)
57 , group_name_(pc->getGroupName())
58 , tss_(pc->getCompleteInitialRobotState())
61 specs_.clearanceComputationType = ompl::base::StateValidityCheckerSpecs::APPROXIMATE;
62 specs_.hasValidDirectionComputation =
false;
85 assert(state !=
nullptr);
92 if (!si_->satisfiesBounds(state))
96 RCLCPP_INFO(getLogger(),
"State outside bounds");
98 const_cast<ob::State*
>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
107 if (kset && !kset->decide(*robot_state, verbose).satisfied)
109 const_cast<ob::State*
>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
116 const_cast<ob::State*
>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
126 const_cast<ob::State*
>(state)->as<ModelBasedStateSpace::StateType>()->markValid();
130 const_cast<ob::State*
>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
137 assert(state !=
nullptr);
146 if (!si_->satisfiesBounds(state))
150 RCLCPP_INFO(getLogger(),
"State outside bounds");
152 const_cast<ob::State*
>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid(0.0);
167 const_cast<ob::State*
>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid(dist);
189 assert(state !=
nullptr);
201 cost += cost_source.cost * cost_source.getVolume();
209 assert(state !=
nullptr);
223 assert(wrapped_state !=
nullptr);
225 auto state = wrapped_state->as<ompl::base::ConstrainedStateSpace::StateType>()->
getState();
234 if (!si_->satisfiesBounds(wrapped_state))
236 RCLCPP_DEBUG(getLogger(),
"State outside bounds");
237 const_cast<ob::State*
>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
247 if (kset && !kset->decide(*robot_state, verbose).satisfied)
249 const_cast<ob::State*
>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
256 const_cast<ob::State*
>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
266 const_cast<ob::State*
>(state)->as<ModelBasedStateSpace::StateType>()->markValid();
270 const_cast<ob::State*
>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
278 assert(wrapped_state !=
nullptr);
280 auto state = wrapped_state->as<ompl::base::ConstrainedStateSpace::StateType>()->
getState();
291 if (!si_->satisfiesBounds(wrapped_state))
293 RCLCPP_DEBUG(getLogger(),
"State outside bounds");
294 const_cast<ob::State*
>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid(0.0);
305 if (kset && !kset->decide(*robot_state, verbose).satisfied)
307 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 *wrapped_state, bool verbose) const override
Check validity for states of type ompl::base::ConstrainedStateSpace.
const ModelBasedStateSpacePtr & getOMPLStateSpace() const
const kinematic_constraints::KinematicConstraintSetPtr & getPathConstraints() 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 planning_scene::PlanningSceneConstPtr & getPlanningScene() const
Get the planning scene associated to this planning context.
const std::string & getGroupName() const
Get the name of the group this planning context is for.
rclcpp::Logger getLogger()
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
The MoveIt interface to OMPL.
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...
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)