moveit2
The MoveIt Motion Planning Framework for ROS 2.
kinematics_constraint_aware.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2012, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage, Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: Sachin Chitta
36  *********************************************************************/
37 
38 // // ROS msgs
42 #include <Eigen/Geometry.h>
43 #include <tf2_eigen/tf2_eigen.hpp>
44 #include <functional>
45 
47 {
48 KinematicsConstraintAware::KinematicsConstraintAware(const moveit::core::RobotModelConstPtr& kinematic_model,
49  const std::string& group_name)
50 {
51  if (!kinematic_model->hasJointModelGroup(group_name))
52  {
53  ROS_ERROR_NAMED("kinematics_constraint_aware", "The group %s does not exist", group_name.c_str());
54  joint_model_group_ = nullptr;
55  return;
56  }
57  kinematic_model_ = kinematic_model;
58  group_name_ = group_name;
59  joint_model_group_ = kinematic_model_->getJointModelGroup(group_name);
60  if (joint_model_group_->getSolverInstance())
61  {
62  has_sub_groups_ = false;
63  sub_groups_names_.push_back(group_name_);
64  }
65  else
66  {
67  ROS_DEBUG_NAMED("kinematics_constraint_aware", "No kinematics solver instance defined for group %s",
68  group_name.c_str());
69  bool is_solvable_group = true;
70  if (!(joint_model_group_->getSubgroupNames().empty()))
71  {
72  const std::vector<std::string> sub_groups_names = joint_model_group_->getSubgroupNames();
73  for (std::size_t i = 0; i < sub_groups_names.size(); ++i)
74  {
75  if (!kinematic_model_->getJointModelGroup(sub_groups_names[i])->getSolverInstance())
76  {
77  is_solvable_group = false;
78  break;
79  }
80  }
81  if (is_solvable_group)
82  {
83  ROS_DEBUG_NAMED("kinematics_constraint_aware", "Group %s is a group for which we can solve IK",
84  joint_model_group_->getName().c_str());
85  sub_groups_names_ = sub_groups_names;
86  }
87  else
88  {
89  joint_model_group_ = nullptr;
90  return;
91  }
92  }
93  else
94  {
95  joint_model_group_ = nullptr;
96  ROS_INFO_NAMED("kinematics_constraint_aware", "No solver allocated for group %s", group_name.c_str());
97  }
98  has_sub_groups_ = true;
99  }
100  ik_attempts_ = 10;
101 }
102 
103 bool KinematicsConstraintAware::getIK(const planning_scene::PlanningSceneConstPtr& planning_scene,
106 {
107  if (!joint_model_group_)
108  {
109  ROS_ERROR_NAMED("kinematics_constraint_aware", "This solver has not been constructed properly");
110  return false;
111  }
112 
113  if (!planning_scene)
114  {
115  ROS_ERROR_NAMED("kinematics_constraint_aware", "Planning scene must be allocated");
116  return false;
117  }
118 
119  if (!response.solution_)
120  {
121  response.solution_ = std::make_shared<moveit::core::RobotState>(planning_scene->getCurrentState());
122  }
123 
124  ros::WallTime start_time = ros::WallTime::now();
125  if (request.group_name_ != group_name_)
126  {
127  response.error_code_.val = response.error_code_.INVALID_GROUP_NAME;
128  return false;
129  }
130 
131  // Setup the seed and the values for all other joints in the robot
132  moveit::core::RobotState kinematic_state = *request.robot_state_;
133  std::vector<std::string> ik_link_names = request.ik_link_names_;
134 
135  // Transform request to tip frame if necessary
136  if (!request.ik_link_names_.empty())
137  {
138  for (std::size_t i = 0; i < request.pose_stamped_vector_.size(); ++i)
139  {
140  geometry_msgs::PoseStamped tmp_pose = request.pose_stamped_vector_[i];
141  // The assumption is that this new link is rigidly attached to the tip link for the group
142  if (!kinematic_model_->getJointModelGroup(sub_groups_names_[i])->hasLinkModel(request.ik_link_names_[i]) &&
143  kinematic_model_->getJointModelGroup(sub_groups_names_[i])->isLinkUpdated(request.ik_link_names_[i]))
144  {
145  tmp_pose.pose = getTipFramePose(planning_scene, kinematic_state, request.pose_stamped_vector_[i].pose,
146  request.ik_link_names_[i], i);
147  ik_link_names[i] =
148  kinematic_model_->getJointModelGroup(sub_groups_names_[i])->getSolverInstance()->getTipFrame();
149  }
150  else if (!kinematic_model_->getJointModelGroup(sub_groups_names_[i])->canSetStateFromIK(request.ik_link_names_[i]))
151  {
152  ROS_ERROR_NAMED("kinematics_constraint_aware", "Could not find IK solver for link %s for group %s",
153  request.ik_link_names_[i].c_str(), sub_groups_names_[i].c_str());
154  return false;
155  }
156  }
157  }
158 
159  // Transform the requests to the base frame of the kinematic model
160  EigenSTL::vector_Isometry3d goals =
161  transformPoses(planning_scene, kinematic_state, request.pose_stamped_vector_, kinematic_model_->getModelFrame());
162 
163  moveit::core::StateValidityCallbackFn constraint_callback_fn = [this, &planning_scene, &request,
164  &response](moveit::core::JointStateGroup* jsg,
165  const std::vector<double>& jg_values) {
166  validityCallbackFn(planning_scene, request, response, jsg, jg_values);
167  };
168 
169  bool result = false;
170  if (has_sub_groups_)
171  {
172  result = kinematic_state.getJointStateGroup(group_name_)
173  ->setFromIK(goals, ik_link_names, ik_attempts_, request.timeout_.toSec(), constraint_callback_fn);
174  }
175  else
176  {
177  result =
178  ik_link_names.empty() ?
179  kinematic_state.getJointStateGroup(group_name_)
180  ->setFromIK(goals[0], ik_attempts_, request.timeout_.toSec(), constraint_callback_fn) :
181  kinematic_state.getJointStateGroup(group_name_)
182  ->setFromIK(goals[0], ik_link_names[0], ik_attempts_, request.timeout_.toSec(), constraint_callback_fn);
183  }
184 
185  if (result)
186  {
187  std::vector<double> solution_values;
188  kinematic_state.getJointStateGroup(group_name_)->getVariableValues(solution_values);
189  response.solution_->getJointStateGroup(group_name_)->setVariableValues(solution_values);
190  response.error_code_.val = response.error_code_.SUCCESS;
191  }
192 
193  if (response.error_code_.val == 0)
194  {
195  response.error_code_.val = response.error_code_.NO_IK_SOLUTION;
196  }
197  return result;
198 }
199 
200 bool KinematicsConstraintAware::validityCallbackFn(const planning_scene::PlanningSceneConstPtr& planning_scene,
203  moveit::core::JointStateGroup* joint_state_group,
204  const std::vector<double>& joint_group_variable_values) const
205 {
206  joint_state_group->setVariableValues(joint_group_variable_values);
207 
208  // Now check for collisions
209  if (request.check_for_collisions_)
210  {
211  collision_detection::CollisionRequest collision_request;
212  collision_detection::CollisionResult collision_result;
213  collision_request.group_name = request.group_name_;
214  planning_scene->checkCollision(collision_request, collision_result, *joint_state_group->getRobotState());
215  if (collision_result.collision)
216  {
217  ROS_DEBUG_NAMED("kinematics_constraint_aware", "IK solution is in collision");
218  response.error_code_.val = response.error_code_.GOAL_IN_COLLISION;
219  return false;
220  }
221  }
222 
223  // Now check for constraints
224  if (request.constraints_)
225  {
227  constraint_result =
228  request.constraints_->decide(*joint_state_group->getRobotState(), response.constraint_eval_results_);
229  if (!constraint_result.satisfied)
230  {
231  ROS_DEBUG_NAMED("kinematics_constraint_aware", "IK solution violates constraints");
232  response.error_code_.val = response.error_code_.GOAL_VIOLATES_PATH_CONSTRAINTS;
233  return false;
234  }
235  }
236 
237  // Now check for user specified constraints
238  if (request.constraint_callback_)
239  {
240  if (!request.constraint_callback_(joint_state_group, joint_group_variable_values))
241  {
242  ROS_DEBUG_NAMED("kinematics_constraint_aware", "IK solution violates user specified constraints");
243  response.error_code_.val = response.error_code_.GOAL_VIOLATES_PATH_CONSTRAINTS;
244  return false;
245  }
246  }
247 
248  return true;
249 }
250 
251 bool KinematicsConstraintAware::getIK(const planning_scene::PlanningSceneConstPtr& planning_scene,
252  const moveit_msgs::msg::GetConstraintAwarePositionIK::Request& request,
253  moveit_msgs::msg::GetConstraintAwarePositionIK::Response& response) const
254 {
255  if (!joint_model_group_)
256  {
257  ROS_ERROR_NAMED("kinematics_constraint_aware", "This solver has not been constructed properly");
258  return false;
259  }
260 
261  if (!planning_scene)
262  {
263  ROS_ERROR_NAMED("kinematics_constraint_aware", "Planning scene must be allocated");
264  return false;
265  }
266 
269 
270  if (!convertServiceRequest(planning_scene, request, kinematics_request, kinematics_response))
271  {
272  response.error_code = kinematics_response.error_code_;
273  return false;
274  }
275 
276  bool result = getIK(planning_scene, kinematics_request, kinematics_response);
277  response.error_code = kinematics_response.error_code_;
278  kinematics_response.solution_->getStateValues(response.solution.joint_state);
279  return result;
280 }
281 
282 bool KinematicsConstraintAware::convertServiceRequest(
283  const planning_scene::PlanningSceneConstPtr& planning_scene,
284  const moveit_msgs::msg::GetConstraintAwarePositionIK::Request& request,
286  kinematics_constraint_aware::KinematicsResponse& kinematics_response) const
287 {
288  if (request.ik_request.group_name != group_name_)
289  {
290  ROS_ERROR_NAMED("kinematics_constraint_aware", "This kinematics solver does not support requests for group: %s",
291  request.ik_request.group_name.c_str());
292  kinematics_response.error_code_.val = kinematics_response.error_code_.INVALID_GROUP_NAME;
293  return false;
294  }
295 
296  if (!request.ik_request.pose_stamped_vector.empty() &&
297  request.ik_request.pose_stamped_vector.size() != sub_groups_names_.size())
298  {
299  ROS_ERROR_NAMED("kinematics_constraint_aware",
300  "Number of poses in request: %d must match number of sub groups %d in this group",
301  request.ik_request.pose_stamped_vector.size(), sub_groups_names_.size());
302  kinematics_response.error_code_.val = kinematics_response.error_code_.INVALID_GROUP_NAME;
303  return false;
304  }
305 
306  if (!request.ik_request.ik_link_names.empty() && request.ik_request.ik_link_names.size() != sub_groups_names_.size())
307  {
308  ROS_ERROR_NAMED("kinematics_constraint_aware",
309  "Number of ik_link_names in request: "
310  "%d must match number of sub groups %d in this group or must be zero",
311  request.ik_request.ik_link_names.size(), sub_groups_names_.size());
312  kinematics_response.error_code_.val = kinematics_response.error_code_.INVALID_GROUP_NAME;
313  return false;
314  }
315 
316  if (request.ik_request.ik_link_names.empty() && request.ik_request.ik_link_name != "")
317  kinematics_request.ik_link_names_.push_back(request.ik_request.ik_link_name);
318  else
319  kinematics_request.ik_link_names_ = request.ik_request.ik_link_names;
320 
321  if (request.ik_request.pose_stamped_vector.empty())
322  kinematics_request.pose_stamped_vector_.push_back(request.ik_request.pose_stamped);
323  else
324  kinematics_request.pose_stamped_vector_ = request.ik_request.pose_stamped_vector;
325 
326  kinematics_request.robot_state_ = std::make_shared<moveit::core::RobotState>(planning_scene->getCurrentState());
327  kinematics_request.robot_state_->setStateValues(request.ik_request.robot_state.joint_state);
328  kinematics_request.constraints_ = std::make_shared<kinematic_constraints::KinematicConstraintSet>(
329  kinematic_model_, planning_scene->getTransforms());
330  kinematics_request.constraints_->add(request.constraints);
331  kinematics_request.timeout_ = request.ik_request.timeout;
332  kinematics_request.group_name_ = request.ik_request.group_name;
333  kinematics_request.check_for_collisions_ = true;
334 
335  kinematics_response.solution_ = std::make_shared<moveit::core::RobotState>(planning_scene->getCurrentState());
336 
337  return true;
338 }
339 
340 EigenSTL::vector_Isometry3d KinematicsConstraintAware::transformPoses(
341  const planning_scene::PlanningSceneConstPtr& planning_scene, const moveit::core::RobotState& kinematic_state,
342  const std::vector<geometry_msgs::PoseStamped>& poses, const std::string& target_frame) const
343 {
344  Eigen::Isometry3d eigen_pose, eigen_pose_2;
345  EigenSTL::vector_Isometry3d result(poses.size());
346  bool target_frame_is_root_frame = (target_frame == kinematic_state.getRobotModel()->getModelFrame());
347  for (std::size_t i = 0; i < poses.size(); ++i)
348  {
349  geometry_msgs::Pose pose = poses[i].pose;
350  tf2::fromMsg(pose, eigen_pose_2);
351  planning_scene->getTransforms()->transformPose(kinematic_state, poses[i].header.frame_id, eigen_pose_2, eigen_pose);
352  if (!target_frame_is_root_frame)
353  {
354  eigen_pose_2 = planning_scene->getTransforms()->getTransform(kinematic_state, target_frame);
355  eigen_pose = eigen_pose_2.inverse() * eigen_pose;
356  }
357  result[i] = eigen_pose;
358  }
359  return result;
360 }
361 
362 geometry_msgs::Pose KinematicsConstraintAware::getTipFramePose(
363  const planning_scene::PlanningSceneConstPtr& planning_scene, const moveit::core::RobotState& kinematic_state,
364  const geometry_msgs::Pose& pose, const std::string& link_name, unsigned int sub_group_index) const
365 {
366  geometry_msgs::Pose result;
367  Eigen::Isometry3d eigen_pose_in, eigen_pose_link, eigen_pose_tip;
368  std::string tip_name =
369  kinematic_model_->getJointModelGroup(sub_groups_names_[sub_group_index])->getSolverInstance()->getTipFrame();
370  tf2::fromMsg(pose, eigen_pose_in);
371  eigen_pose_link = planning_scene->getTransforms()->getTransform(kinematic_state, link_name);
372  eigen_pose_tip = planning_scene->getTransforms()->getTransform(kinematic_state, tip_name);
373  eigen_pose_in = eigen_pose_in * (eigen_pose_link.inverse() * eigen_pose_tip);
374  result = tf2::toMsg(eigen_pose_in, result);
375  return result;
376 }
377 } // namespace kinematics_constraint_aware
KinematicsConstraintAware(const moveit::core::RobotModelConstPtr &kinematic_model, const std::string &group_name)
Default constructor.
bool getIK(const planning_scene::PlanningSceneConstPtr &planning_scene, const kinematics_constraint_aware::KinematicsRequest &request, kinematics_constraint_aware::KinematicsResponse &response) const
Solve the planning problem.
kinematic_constraints::KinematicConstraintSetPtr constraints_
moveit::core::StateValidityCallbackFn constraint_callback_
std::vector< geometry_msgs::PoseStamped > pose_stamped_vector_
std::vector< kinematic_constraints::ConstraintEvaluationResult > constraint_eval_results_
const std::string & getName() const
Get the name of the joint group.
const kinematics::KinematicsBaseConstPtr getSolverInstance() const
const std::vector< std::string > & getSubgroupNames() const
Get the names of the groups that are subsets of this one (in terms of joints set)
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
const RobotModelConstPtr & getRobotModel() const
Get the robot model this state is constructed for.
Definition: robot_state.h:104
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...
This namespace includes the central class for representing planning contexts.
Representation of a collision checking request.
std::string group_name
The group name to check collisions for (optional; if empty, assume the complete robot)
Representation of a collision checking result.
bool collision
True if collision was found, false otherwise.
Struct for containing the results of constraint evaluation.
bool satisfied
Whether or not the constraint or constraints were satisfied.