moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
kinematics_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
41#include <tf2_eigen/tf2_eigen.hpp>
44
45namespace move_group
46{
47
51
53{
54 fk_service_ = context_->moveit_cpp_->getNode()->create_service<moveit_msgs::srv::GetPositionFK>(
55 FK_SERVICE_NAME, [this](const std::shared_ptr<rmw_request_id_t>& req_header,
56 const std::shared_ptr<moveit_msgs::srv::GetPositionFK::Request>& req,
57 const std::shared_ptr<moveit_msgs::srv::GetPositionFK::Response>& res) {
58 return computeFKService(req_header, req, res);
59 });
60 ik_service_ = context_->moveit_cpp_->getNode()->create_service<moveit_msgs::srv::GetPositionIK>(
61 IK_SERVICE_NAME, [this](const std::shared_ptr<rmw_request_id_t>& req_header,
62 const std::shared_ptr<moveit_msgs::srv::GetPositionIK::Request>& req,
63 const std::shared_ptr<moveit_msgs::srv::GetPositionIK::Response>& res) {
64 return computeIKService(req_header, req, res);
65 });
66}
67
68namespace
69{
70bool isIKSolutionValid(const planning_scene::PlanningScene* planning_scene,
73 const double* ik_solution)
74{
75 state->setJointGroupPositions(jmg, ik_solution);
76 state->update();
77 return (!planning_scene || !planning_scene->isStateColliding(*state, jmg->getName())) &&
78 (!constraint_set || constraint_set->decide(*state).satisfied);
79}
80} // namespace
81
82void MoveGroupKinematicsService::computeIK(moveit_msgs::msg::PositionIKRequest& req,
83 moveit_msgs::msg::RobotState& solution,
84 moveit_msgs::msg::MoveItErrorCodes& error_code, moveit::core::RobotState& rs,
85 const moveit::core::GroupStateValidityCallbackFn& constraint) const
86{
87 const moveit::core::JointModelGroup* jmg = rs.getJointModelGroup(req.group_name);
88 if (jmg)
89 {
90 if (!moveit::core::isEmpty(req.robot_state))
91 {
92 moveit::core::robotStateMsgToRobotState(req.robot_state, rs);
93 }
94 const std::string& default_frame = context_->planning_scene_monitor_->getRobotModel()->getModelFrame();
95
96 if (req.pose_stamped_vector.empty() || req.pose_stamped_vector.size() == 1)
97 {
98 geometry_msgs::msg::PoseStamped req_pose =
99 req.pose_stamped_vector.empty() ? req.pose_stamped : req.pose_stamped_vector[0];
100 std::string ik_link = (!req.pose_stamped_vector.empty()) ?
101 (req.ik_link_names.empty() ? "" : req.ik_link_names[0]) :
102 req.ik_link_name;
103
104 if (performTransform(req_pose, default_frame))
105 {
106 bool result_ik = false;
107 if (ik_link.empty())
108 {
109 result_ik = rs.setFromIK(jmg, req_pose.pose, req.timeout.sec, constraint);
110 }
111 else
112 {
113 result_ik = rs.setFromIK(jmg, req_pose.pose, ik_link, req.timeout.sec, constraint);
114 }
115
116 if (result_ik)
117 {
118 moveit::core::robotStateToRobotStateMsg(rs, solution, false);
119 error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
120 }
121 else
122 error_code.val = moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION;
123 }
124 else
125 error_code.val = moveit_msgs::msg::MoveItErrorCodes::FRAME_TRANSFORM_FAILURE;
126 }
127 else
128 {
129 if (req.pose_stamped_vector.size() != req.ik_link_names.size())
130 {
131 error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_LINK_NAME;
132 }
133 else
134 {
135 bool ok = true;
136 EigenSTL::vector_Isometry3d req_poses(req.pose_stamped_vector.size());
137 for (std::size_t k = 0; k < req.pose_stamped_vector.size(); ++k)
138 {
139 geometry_msgs::msg::PoseStamped msg = req.pose_stamped_vector[k];
140 if (performTransform(msg, default_frame))
141 {
142 tf2::fromMsg(msg.pose, req_poses[k]);
143 }
144 else
145 {
146 error_code.val = moveit_msgs::msg::MoveItErrorCodes::FRAME_TRANSFORM_FAILURE;
147 ok = false;
148 break;
149 }
150 }
151 if (ok)
152 {
153 if (rs.setFromIK(jmg, req_poses, req.ik_link_names, req.timeout.sec, constraint))
154 {
155 moveit::core::robotStateToRobotStateMsg(rs, solution, false);
156 error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
157 }
158 else
159 error_code.val = moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION;
160 }
161 }
162 }
163 }
164 else
165 error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_GROUP_NAME;
166}
167
168bool MoveGroupKinematicsService::computeIKService(const std::shared_ptr<rmw_request_id_t>& /* unused */,
169 const std::shared_ptr<moveit_msgs::srv::GetPositionIK::Request>& req,
170 const std::shared_ptr<moveit_msgs::srv::GetPositionIK::Response>& res)
171{
172 context_->planning_scene_monitor_->updateFrameTransforms();
173
174 // check if the planning scene needs to be kept locked; if so, call computeIK() in the scope of the lock
175 if (req->ik_request.avoid_collisions || !moveit::core::isEmpty(req->ik_request.constraints))
176 {
177 planning_scene_monitor::LockedPlanningSceneRO ls(context_->planning_scene_monitor_);
178 kinematic_constraints::KinematicConstraintSet kset(ls->getRobotModel());
179 moveit::core::RobotState rs = ls->getCurrentState();
180 kset.add(req->ik_request.constraints, ls->getTransforms());
181 computeIK(req->ik_request, res->solution, res->error_code, rs,
182 [scene = req->ik_request.avoid_collisions ?
183 static_cast<const planning_scene::PlanningSceneConstPtr&>(ls).get() :
184 nullptr,
185 kset_ptr = kset.empty() ? nullptr : &kset](moveit::core::RobotState* robot_state,
186 const moveit::core::JointModelGroup* joint_group,
187 const double* joint_group_variable_values) {
188 return isIKSolutionValid(scene, kset_ptr, robot_state, joint_group, joint_group_variable_values);
189 });
190 }
191 else
192 {
193 // compute unconstrained IK, no lock to planning scene maintained
195 planning_scene_monitor::LockedPlanningSceneRO(context_->planning_scene_monitor_)->getCurrentState();
196 computeIK(req->ik_request, res->solution, res->error_code, rs);
197 }
198
199 return true;
200}
201
202bool MoveGroupKinematicsService::computeFKService(const std::shared_ptr<rmw_request_id_t>& /* unused */,
203 const std::shared_ptr<moveit_msgs::srv::GetPositionFK::Request>& req,
204 const std::shared_ptr<moveit_msgs::srv::GetPositionFK::Response>& res)
205{
206 if (req->fk_link_names.empty())
207 {
208 RCLCPP_ERROR(moveit::getLogger("moveit.ros.move_group.kinematics_service"), "No links specified for FK request");
209 res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_LINK_NAME;
210 return true;
211 }
212
213 context_->planning_scene_monitor_->updateFrameTransforms();
214
215 const std::string& default_frame = context_->planning_scene_monitor_->getRobotModel()->getModelFrame();
216 bool do_transform = !req->header.frame_id.empty() &&
217 !moveit::core::Transforms::sameFrame(req->header.frame_id, default_frame) &&
218 context_->planning_scene_monitor_->getTFClient();
219 bool tf_problem = false;
220
222 planning_scene_monitor::LockedPlanningSceneRO(context_->planning_scene_monitor_)->getCurrentState();
223 moveit::core::robotStateMsgToRobotState(req->robot_state, rs);
224 for (std::size_t i = 0; i < req->fk_link_names.size(); ++i)
225 {
226 if (rs.knowsFrameTransform(req->fk_link_names[i]))
227 {
228 res->pose_stamped.resize(res->pose_stamped.size() + 1);
229 res->pose_stamped.back().pose = tf2::toMsg(rs.getFrameTransform(req->fk_link_names[i]));
230 res->pose_stamped.back().header.frame_id = default_frame;
231 res->pose_stamped.back().header.stamp = context_->moveit_cpp_->getNode()->get_clock()->now();
232 if (do_transform)
233 {
234 if (!performTransform(res->pose_stamped.back(), req->header.frame_id))
235 tf_problem = true;
236 }
237 res->fk_link_names.push_back(req->fk_link_names[i]);
238 }
239 }
240 if (tf_problem)
241 {
242 res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::FRAME_TRANSFORM_FAILURE;
243 }
244 else if (res->fk_link_names.size() == req->fk_link_names.size())
245 {
246 res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
247 }
248 else
249 {
250 res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_LINK_NAME;
251 }
252 return true;
253}
254} // namespace move_group
255
256#include <pluginlib/class_list_macros.hpp>
257
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....
ConstraintEvaluationResult decide(const moveit::core::RobotState &state, bool verbose=false) const
Determines whether all constraints are satisfied by state, returning a single evaluation result.
bool performTransform(geometry_msgs::msg::PoseStamped &pose_msg, const std::string &target_frame) const
const std::string & getName() const
Get the name of the joint group.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition robot_state.h:90
void setJointGroupPositions(const std::string &joint_group_name, const double *gstate)
Given positions for the variables that make up a group, in the order found in the group (including va...
const JointModelGroup * getJointModelGroup(const std::string &group) const
Get the model of a particular joint group.
const Eigen::Isometry3d & getFrameTransform(const std::string &frame_id, bool *frame_found=nullptr)
Get the transformation matrix from the model frame (root of model) to the frame identified by frame_i...
void update(bool force=false)
Update all transforms.
bool knowsFrameTransform(const std::string &frame_id) const
Check if a transformation matrix from the model frame (root of model) to frame frame_id is known.
bool setFromIK(const JointModelGroup *group, const geometry_msgs::msg::Pose &pose, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn())
If the group this state corresponds to is a chain and a solver is available, then the joint values ca...
static bool sameFrame(const std::string &frame1, const std::string &frame2)
Check if two frames end up being the same once the missing / are added as prefix (if they are missing...
This class maintains the representation of the environment as seen by a planning instance....
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::msg::RobotState &robot_state, bool copy_attached_bodies=true)
Convert a MoveIt robot state to a robot state message.
std::function< bool(RobotState *robot_state, const JointModelGroup *joint_group, const double *joint_group_variable_values)> GroupStateValidityCallbackFn
Signature for functions that can verify that if the group joint_group in robot_state is set to joint_...
Definition robot_state.h:70
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.
Main namespace for MoveIt.
Definition exceptions.h:43
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition logger.cpp:79
This namespace includes the central class for representing planning contexts.
bool satisfied
Whether or not the constraint or constraints were satisfied.