52 validity_service_ =
context_->moveit_cpp_->getNode()->create_service<moveit_msgs::srv::GetStateValidity>(
53 STATE_VALIDITY_SERVICE_NAME, [
this](
const std::shared_ptr<rmw_request_id_t>& request_header,
54 const std::shared_ptr<moveit_msgs::srv::GetStateValidity::Request>& req,
55 const std::shared_ptr<moveit_msgs::srv::GetStateValidity::Response>& res) {
56 return computeService(request_header, req, res);
62 const std::string& group_name,
const moveit_msgs::msg::Constraints& constraints,
63 std::vector<moveit_msgs::msg::ContactInformation>& contacts,
64 std::vector<moveit_msgs::msg::CostSource>& cost_sources,
65 std::vector<moveit_msgs::msg::ConstraintEvalResult>& constraint_result)
74 creq.
max_contacts = ls->getWorld()->size() + ls->getRobotModel()->getLinkModelsWithCollisionGeometry().size();
80 ls->checkCollision(creq, cres, rs);
85 rclcpp::Time time_now =
context_->moveit_cpp_->getNode()->get_clock()->now();
88 for (collision_detection::CollisionResult::ContactMap::const_iterator it = cres.
contacts.begin();
93 contacts.resize(contacts.size() + 1);
95 contacts.back().header.frame_id = ls->getPlanningFrame();
96 contacts.back().header.stamp = time_now;
105 cost_sources.resize(cost_sources.size() + 1);
113 kset.
add(constraints, ls->getTransforms());
114 std::vector<kinematic_constraints::ConstraintEvaluationResult> kres;
122 constraint_result.resize(kres.size());
123 for (std::size_t k = 0; k < kres.size(); ++k)
125 constraint_result[k].result = kres[k].
satisfied;
126 constraint_result[k].distance = kres[k].distance;
133bool MoveGroupStateValidationService::computeService(
134 const std::shared_ptr<rmw_request_id_t>& ,
135 const std::shared_ptr<moveit_msgs::srv::GetStateValidity::Request>& req,
136 const std::shared_ptr<moveit_msgs::srv::GetStateValidity::Response>& res)
142 isStateValid(ls, rs, req->group_name, req->constraints, res->contacts, res->cost_sources, res->constraint_result);
147#include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
A class that contains many different constraints, and can check RobotState *versus the full set....
bool add(const moveit_msgs::msg::Constraints &c, const moveit::core::Transforms &tf)
Add all known constraints.
ConstraintEvaluationResult decide(const moveit::core::RobotState &state, bool verbose=false) const
Determines whether all constraints are satisfied by state, returning a single evaluation result.
MoveGroupContextPtr context_
MoveGroupStateValidationService()
void initialize() override
bool isStateValid(const planning_scene_monitor::LockedPlanningSceneRO &ls, const moveit::core::RobotState &rs, const std::string &group_name, const moveit_msgs::msg::Constraints &constraints, std::vector< moveit_msgs::msg::ContactInformation > &contacts, std::vector< moveit_msgs::msg::CostSource > &cost_sources, std::vector< moveit_msgs::msg::ConstraintEvalResult > &constraint_result)
Representation of a robot's state. This includes position, velocity, acceleration and effort.
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
void contactToMsg(const Contact &contact, moveit_msgs::msg::ContactInformation &msg)
void costSourceToMsg(const CostSource &cost_source, moveit_msgs::msg::CostSource &msg)
bool isEmpty(const moveit_msgs::msg::PlanningScene &msg)
Check if a message includes any information about a planning scene, or whether it is empty.
bool robotStateMsgToRobotState(const Transforms &tf, const moveit_msgs::msg::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
Convert a robot state msg (with accompanying extra transforms) to a MoveIt robot state.
Representation of a collision checking request.
std::string group_name
The group name to check collisions for (optional; if empty, assume the complete robot)....
std::size_t max_cost_sources
When costs are computed, this value defines how many of the top cost sources should be returned.
bool contacts
If true, compute contacts. Otherwise only a binary collision yes/no is reported.
bool cost
If true, a collision cost is computed.
std::size_t max_contacts
Overall maximum number of contacts to compute.
Representation of a collision checking result.
std::set< CostSource > cost_sources
These are the individual cost sources when costs are computed.
bool collision
True if collision was found, false otherwise.
std::size_t contact_count
Number of contacts returned.
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.