moveit2
The MoveIt Motion Planning Framework for ROS 2.
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>
43 
44 namespace move_group
45 {
46 static const rclcpp::Logger LOGGER =
47  rclcpp::get_logger("moveit_move_group_default_capabilities.kinematics_service_capability");
48 
50 {
51 }
52 
54 {
55  fk_service_ = context_->moveit_cpp_->getNode()->create_service<moveit_msgs::srv::GetPositionFK>(
56  FK_SERVICE_NAME, [this](const std::shared_ptr<rmw_request_id_t>& req_header,
57  const std::shared_ptr<moveit_msgs::srv::GetPositionFK::Request>& req,
58  const std::shared_ptr<moveit_msgs::srv::GetPositionFK::Response>& res) {
59  return computeFKService(req_header, req, res);
60  });
61  ik_service_ = context_->moveit_cpp_->getNode()->create_service<moveit_msgs::srv::GetPositionIK>(
62  IK_SERVICE_NAME, [this](const std::shared_ptr<rmw_request_id_t>& req_header,
63  const std::shared_ptr<moveit_msgs::srv::GetPositionIK::Request>& req,
64  const std::shared_ptr<moveit_msgs::srv::GetPositionIK::Response>& res) {
65  return computeIKService(req_header, req, res);
66  });
67 }
68 
69 namespace
70 {
71 bool isIKSolutionValid(const planning_scene::PlanningScene* planning_scene,
74  const double* ik_solution)
75 {
76  state->setJointGroupPositions(jmg, ik_solution);
77  state->update();
78  return (!planning_scene || !planning_scene->isStateColliding(*state, jmg->getName())) &&
79  (!constraint_set || constraint_set->decide(*state).satisfied);
80 }
81 } // namespace
82 
83 void MoveGroupKinematicsService::computeIK(moveit_msgs::msg::PositionIKRequest& req,
84  moveit_msgs::msg::RobotState& solution,
85  moveit_msgs::msg::MoveItErrorCodes& error_code, moveit::core::RobotState& rs,
86  const moveit::core::GroupStateValidityCallbackFn& constraint) const
87 {
88  const moveit::core::JointModelGroup* jmg = rs.getJointModelGroup(req.group_name);
89  if (jmg)
90  {
91  if (!moveit::core::isEmpty(req.robot_state))
92  {
93  moveit::core::robotStateMsgToRobotState(req.robot_state, rs);
94  }
95  const std::string& default_frame = context_->planning_scene_monitor_->getRobotModel()->getModelFrame();
96 
97  if (req.pose_stamped_vector.empty() || req.pose_stamped_vector.size() == 1)
98  {
99  geometry_msgs::msg::PoseStamped req_pose =
100  req.pose_stamped_vector.empty() ? req.pose_stamped : req.pose_stamped_vector[0];
101  std::string ik_link = (!req.pose_stamped_vector.empty()) ?
102  (req.ik_link_names.empty() ? "" : req.ik_link_names[0]) :
103  req.ik_link_name;
104 
105  if (performTransform(req_pose, default_frame))
106  {
107  bool result_ik = false;
108  if (ik_link.empty())
109  result_ik = rs.setFromIK(jmg, req_pose.pose, req.timeout.sec, constraint);
110  else
111  result_ik = rs.setFromIK(jmg, req_pose.pose, ik_link, req.timeout.sec, constraint);
112 
113  if (result_ik)
114  {
115  moveit::core::robotStateToRobotStateMsg(rs, solution, false);
116  error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
117  }
118  else
119  error_code.val = moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION;
120  }
121  else
122  error_code.val = moveit_msgs::msg::MoveItErrorCodes::FRAME_TRANSFORM_FAILURE;
123  }
124  else
125  {
126  if (req.pose_stamped_vector.size() != req.ik_link_names.size())
127  error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_LINK_NAME;
128  else
129  {
130  bool ok = true;
131  EigenSTL::vector_Isometry3d req_poses(req.pose_stamped_vector.size());
132  for (std::size_t k = 0; k < req.pose_stamped_vector.size(); ++k)
133  {
134  geometry_msgs::msg::PoseStamped msg = req.pose_stamped_vector[k];
135  if (performTransform(msg, default_frame))
136  tf2::fromMsg(msg.pose, req_poses[k]);
137  else
138  {
139  error_code.val = moveit_msgs::msg::MoveItErrorCodes::FRAME_TRANSFORM_FAILURE;
140  ok = false;
141  break;
142  }
143  }
144  if (ok)
145  {
146  if (rs.setFromIK(jmg, req_poses, req.ik_link_names, req.timeout.sec, constraint))
147  {
148  moveit::core::robotStateToRobotStateMsg(rs, solution, false);
149  error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
150  }
151  else
152  error_code.val = moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION;
153  }
154  }
155  }
156  }
157  else
158  error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_GROUP_NAME;
159 }
160 
161 bool MoveGroupKinematicsService::computeIKService(const std::shared_ptr<rmw_request_id_t>& /* unused */,
162  const std::shared_ptr<moveit_msgs::srv::GetPositionIK::Request>& req,
163  const std::shared_ptr<moveit_msgs::srv::GetPositionIK::Response>& res)
164 {
165  context_->planning_scene_monitor_->updateFrameTransforms();
166 
167  // check if the planning scene needs to be kept locked; if so, call computeIK() in the scope of the lock
168  if (req->ik_request.avoid_collisions || !moveit::core::isEmpty(req->ik_request.constraints))
169  {
170  planning_scene_monitor::LockedPlanningSceneRO ls(context_->planning_scene_monitor_);
171  kinematic_constraints::KinematicConstraintSet kset(ls->getRobotModel());
172  moveit::core::RobotState rs = ls->getCurrentState();
173  kset.add(req->ik_request.constraints, ls->getTransforms());
174  computeIK(req->ik_request, res->solution, res->error_code, rs,
175  [scene = req->ik_request.avoid_collisions ?
176  static_cast<const planning_scene::PlanningSceneConstPtr&>(ls).get() :
177  nullptr,
178  kset_ptr = kset.empty() ? nullptr : &kset](moveit::core::RobotState* robot_state,
179  const moveit::core::JointModelGroup* joint_group,
180  const double* joint_group_variable_values) {
181  return isIKSolutionValid(scene, kset_ptr, robot_state, joint_group, joint_group_variable_values);
182  });
183  }
184  else
185  {
186  // compute unconstrained IK, no lock to planning scene maintained
188  planning_scene_monitor::LockedPlanningSceneRO(context_->planning_scene_monitor_)->getCurrentState();
189  computeIK(req->ik_request, res->solution, res->error_code, rs);
190  }
191 
192  return true;
193 }
194 
195 bool MoveGroupKinematicsService::computeFKService(const std::shared_ptr<rmw_request_id_t>& /* unused */,
196  const std::shared_ptr<moveit_msgs::srv::GetPositionFK::Request>& req,
197  const std::shared_ptr<moveit_msgs::srv::GetPositionFK::Response>& res)
198 {
199  if (req->fk_link_names.empty())
200  {
201  RCLCPP_ERROR(LOGGER, "No links specified for FK request");
202  res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_LINK_NAME;
203  return true;
204  }
205 
206  context_->planning_scene_monitor_->updateFrameTransforms();
207 
208  const std::string& default_frame = context_->planning_scene_monitor_->getRobotModel()->getModelFrame();
209  bool do_transform = !req->header.frame_id.empty() &&
210  !moveit::core::Transforms::sameFrame(req->header.frame_id, default_frame) &&
211  context_->planning_scene_monitor_->getTFClient();
212  bool tf_problem = false;
213 
215  planning_scene_monitor::LockedPlanningSceneRO(context_->planning_scene_monitor_)->getCurrentState();
216  moveit::core::robotStateMsgToRobotState(req->robot_state, rs);
217  for (std::size_t i = 0; i < req->fk_link_names.size(); ++i)
218  if (rs.getRobotModel()->hasLinkModel(req->fk_link_names[i]))
219  {
220  res->pose_stamped.resize(res->pose_stamped.size() + 1);
221  res->pose_stamped.back().pose = tf2::toMsg(rs.getGlobalLinkTransform(req->fk_link_names[i]));
222  res->pose_stamped.back().header.frame_id = default_frame;
223  res->pose_stamped.back().header.stamp = context_->moveit_cpp_->getNode()->get_clock()->now();
224  if (do_transform)
225  if (!performTransform(res->pose_stamped.back(), req->header.frame_id))
226  tf_problem = true;
227  res->fk_link_names.push_back(req->fk_link_names[i]);
228  }
229  if (tf_problem)
230  res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::FRAME_TRANSFORM_FAILURE;
231  else if (res->fk_link_names.size() == req->fk_link_names.size())
232  res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
233  else
234  res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_LINK_NAME;
235  return true;
236 }
237 } // namespace move_group
238 
239 #include <pluginlib/class_list_macros.hpp>
240 
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
const Eigen::Isometry3d & getGlobalLinkTransform(const std::string &link_name)
Get the link transform w.r.t. the root link (model frame) of the RobotModel. This is typically the ro...
Definition: robot_state.h:1339
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...
Definition: robot_state.h:605
const RobotModelConstPtr & getRobotModel() const
Get the robot model this state is constructed for.
Definition: robot_state.h:104
const JointModelGroup * getJointModelGroup(const std::string &group) const
Get the model of a particular joint group.
Definition: robot_state.h:134
void update(bool force=false)
Update all transforms.
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...
Definition: transforms.cpp:64
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.
scene
Definition: pick.py:52
This namespace includes the central class for representing planning contexts.
const rclcpp::Logger LOGGER
Definition: async_test.h:31
bool satisfied
Whether or not the constraint or constraints were satisfied.