moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
state_validation_service_capability.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2012, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35/* Author: Ioan Sucan */
36
43
44namespace move_group
45{
49
51{
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);
57 });
58}
59
60bool MoveGroupStateValidationService::computeService(
61 const std::shared_ptr<rmw_request_id_t>& /* unused */,
62 const std::shared_ptr<moveit_msgs::srv::GetStateValidity::Request>& req,
63 const std::shared_ptr<moveit_msgs::srv::GetStateValidity::Response>& res)
64{
66 moveit::core::RobotState rs = ls->getCurrentState();
67 moveit::core::robotStateMsgToRobotState(req->robot_state, rs);
68
69 res->valid = true;
70
71 // configure collision request
73 creq.group_name = req->group_name;
74 creq.cost = true;
75 creq.contacts = true;
76 creq.max_contacts = ls->getWorld()->size() + ls->getRobotModel()->getLinkModelsWithCollisionGeometry().size();
78 creq.max_contacts *= creq.max_contacts;
80
81 // check collision
82 ls->checkCollision(creq, cres, rs);
83
84 // copy contacts if any
85 if (cres.collision)
86 {
87 rclcpp::Time time_now = context_->moveit_cpp_->getNode()->get_clock()->now();
88 res->contacts.reserve(cres.contact_count);
89 res->valid = false;
90 for (collision_detection::CollisionResult::ContactMap::const_iterator it = cres.contacts.begin();
91 it != cres.contacts.end(); ++it)
92 {
93 for (const collision_detection::Contact& contact : it->second)
94 {
95 res->contacts.resize(res->contacts.size() + 1);
96 collision_detection::contactToMsg(contact, res->contacts.back());
97 res->contacts.back().header.frame_id = ls->getPlanningFrame();
98 res->contacts.back().header.stamp = time_now;
99 }
100 }
101 }
102
103 // copy cost sources
104 res->cost_sources.reserve(cres.cost_sources.size());
105 for (const collision_detection::CostSource& cost_source : cres.cost_sources)
106 {
107 res->cost_sources.resize(res->cost_sources.size() + 1);
108 collision_detection::costSourceToMsg(cost_source, res->cost_sources.back());
109 }
110
111 // evaluate constraints
112 if (!moveit::core::isEmpty(req->constraints))
113 {
114 kinematic_constraints::KinematicConstraintSet kset(ls->getRobotModel());
115 kset.add(req->constraints, ls->getTransforms());
116 std::vector<kinematic_constraints::ConstraintEvaluationResult> kres;
117 kinematic_constraints::ConstraintEvaluationResult total_result = kset.decide(rs, kres);
118 if (!total_result.satisfied)
119 res->valid = false;
120
121 // copy constraint results
122 res->constraint_result.resize(kres.size());
123 for (std::size_t k = 0; k < kres.size(); ++k)
124 {
125 res->constraint_result[k].result = kres[k].satisfied;
126 res->constraint_result[k].distance = kres[k].distance;
127 }
128 }
129
130 return true;
131}
132} // namespace move_group
133
134#include <pluginlib/class_list_macros.hpp>
135
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....
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition robot_state.h:90
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.
Definition of a contact point.
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.