moveit2
The MoveIt Motion Planning Framework for ROS 2.
srv_kinematics_plugin.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2014, JSK, The University of Tokyo.
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 JSK, The University of Tokyo 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: Dave Coleman, Masaki Murooka */
36 
37 #include <moveit_msgs/srv/get_position_ik.hpp>
39 #include <class_loader/class_loader.hpp>
41 #include <iterator>
42 
43 // Eigen
44 #include <Eigen/Core>
45 #include <Eigen/Geometry>
46 
47 // register SRVKinematics as a KinematicsBase implementation
49 
50 namespace srv_kinematics_plugin
51 {
52 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_srv_kinematics_plugin.srv_kinematics_plugin");
53 
55 {
56 }
57 
58 bool SrvKinematicsPlugin::initialize(const rclcpp::Node::SharedPtr& node, const moveit::core::RobotModel& robot_model,
59  const std::string& group_name, const std::string& base_frame,
60  const std::vector<std::string>& tip_frames, double search_discretization)
61 {
62  node_ = node;
63  bool debug = false;
64 
65  RCLCPP_INFO(LOGGER, "SrvKinematicsPlugin initializing");
66 
67  storeValues(robot_model, group_name, base_frame, tip_frames, search_discretization);
68  joint_model_group_ = robot_model_->getJointModelGroup(group_name);
69  if (!joint_model_group_)
70  return false;
71 
72  if (debug)
73  {
74  std::cout << "Joint Model Variable Names: ------------------------------------------- \n ";
75  const std::vector<std::string> jm_names = joint_model_group_->getVariableNames();
76  std::copy(jm_names.begin(), jm_names.end(), std::ostream_iterator<std::string>(std::cout, "\n"));
77  std::cout << '\n';
78  }
79 
80  // Get the dimension of the planning group
81  dimension_ = joint_model_group_->getVariableCount();
82  RCLCPP_INFO_STREAM(LOGGER, "Dimension planning group '"
83  << group_name << "': " << dimension_
84  << ". Active Joints Models: " << joint_model_group_->getActiveJointModels().size()
85  << ". Mimic Joint Models: " << joint_model_group_->getMimicJointModels().size());
86 
87  // Copy joint names
88  for (std::size_t i = 0; i < joint_model_group_->getJointModels().size(); ++i)
89  {
90  ik_group_info_.joint_names.push_back(joint_model_group_->getJointModelNames()[i]);
91  }
92 
93  if (debug)
94  {
95  RCLCPP_ERROR(LOGGER, "tip links available:");
96  std::copy(tip_frames_.begin(), tip_frames_.end(), std::ostream_iterator<std::string>(std::cout, "\n"));
97  }
98 
99  // Make sure all the tip links are in the link_names vector
100  for (const std::string& tip_frame : tip_frames_)
101  {
102  if (!joint_model_group_->hasLinkModel(tip_frame))
103  {
104  RCLCPP_ERROR(LOGGER, "Could not find tip name '%s' in joint group '%s'", tip_frame.c_str(), group_name.c_str());
105  return false;
106  }
107  ik_group_info_.link_names.push_back(tip_frame);
108  }
109 
110  // Choose what ROS service to send IK requests to
111  RCLCPP_DEBUG(LOGGER, "Looking for ROS service name on rosparam server with param: "
112  "/kinematics_solver_service_name");
113  std::string ik_service_name;
114  lookupParam(node_, "kinematics_solver_service_name", ik_service_name, std::string("solve_ik"));
115 
116  // Setup the joint state groups that we need
117  robot_state_ = std::make_shared<moveit::core::RobotState>(robot_model_);
118  robot_state_->setToDefaultValues();
119 
120  // Create the ROS2 service client
121  ik_service_client_ = node_->create_client<moveit_msgs::srv::GetPositionIK>(ik_service_name);
122 
123  if (!ik_service_client_->wait_for_service(std::chrono::seconds(1))) // wait 0.1 seconds, blocking
124  RCLCPP_WARN_STREAM(LOGGER,
125  "Unable to connect to ROS service client with name: " << ik_service_client_->get_service_name());
126  else
127  RCLCPP_INFO_STREAM(LOGGER,
128  "Service client started with ROS service name: " << ik_service_client_->get_service_name());
129 
130  active_ = true;
131  RCLCPP_DEBUG(LOGGER, "ROS service-based kinematics solver initialized");
132  return true;
133 }
134 
135 bool SrvKinematicsPlugin::setRedundantJoints(const std::vector<unsigned int>& redundant_joints)
136 {
137  if (num_possible_redundant_joints_ < 0)
138  {
139  RCLCPP_ERROR(LOGGER, "This group cannot have redundant joints");
140  return false;
141  }
142  if (int(redundant_joints.size()) > num_possible_redundant_joints_)
143  {
144  RCLCPP_ERROR(LOGGER, "This group can only have %d redundant joints", num_possible_redundant_joints_);
145  return false;
146  }
147 
148  return true;
149 }
150 
151 bool SrvKinematicsPlugin::isRedundantJoint(unsigned int index) const
152 {
153  for (const unsigned int& redundant_joint_indice : redundant_joint_indices_)
154  if (redundant_joint_indice == index)
155  return true;
156  return false;
157 }
158 
159 int SrvKinematicsPlugin::getJointIndex(const std::string& name) const
160 {
161  for (unsigned int i = 0; i < ik_group_info_.joint_names.size(); ++i)
162  {
163  if (ik_group_info_.joint_names[i] == name)
164  return i;
165  }
166  return -1;
167 }
168 
169 bool SrvKinematicsPlugin::timedOut(const rclcpp::Time& start_time, double duration) const
170 {
171  return ((node_->now() - start_time).seconds() >= duration);
172 }
173 
174 bool SrvKinematicsPlugin::getPositionIK(const geometry_msgs::msg::Pose& ik_pose,
175  const std::vector<double>& ik_seed_state, std::vector<double>& solution,
176  moveit_msgs::msg::MoveItErrorCodes& error_code,
178 {
179  std::vector<double> consistency_limits;
180 
181  return searchPositionIK(ik_pose, ik_seed_state, default_timeout_, consistency_limits, solution, IKCallbackFn(),
182  error_code, options);
183 }
184 
185 bool SrvKinematicsPlugin::searchPositionIK(const geometry_msgs::msg::Pose& ik_pose,
186  const std::vector<double>& ik_seed_state, double timeout,
187  std::vector<double>& solution,
188  moveit_msgs::msg::MoveItErrorCodes& error_code,
190 {
191  std::vector<double> consistency_limits;
192 
193  return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, IKCallbackFn(), error_code,
194  options);
195 }
196 
197 bool SrvKinematicsPlugin::searchPositionIK(const geometry_msgs::msg::Pose& ik_pose,
198  const std::vector<double>& ik_seed_state, double timeout,
199  const std::vector<double>& consistency_limits, std::vector<double>& solution,
200  moveit_msgs::msg::MoveItErrorCodes& error_code,
202 {
203  return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, IKCallbackFn(), error_code,
204  options);
205 }
206 
207 bool SrvKinematicsPlugin::searchPositionIK(const geometry_msgs::msg::Pose& ik_pose,
208  const std::vector<double>& ik_seed_state, double timeout,
209  std::vector<double>& solution, const IKCallbackFn& solution_callback,
210  moveit_msgs::msg::MoveItErrorCodes& error_code,
212 {
213  std::vector<double> consistency_limits;
214  return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code,
215  options);
216 }
217 
218 bool SrvKinematicsPlugin::searchPositionIK(const geometry_msgs::msg::Pose& ik_pose,
219  const std::vector<double>& ik_seed_state, double timeout,
220  const std::vector<double>& consistency_limits, std::vector<double>& solution,
221  const IKCallbackFn& solution_callback,
222  moveit_msgs::msg::MoveItErrorCodes& error_code,
224 {
225  // Convert single pose into a vector of one pose
226  std::vector<geometry_msgs::msg::Pose> ik_poses;
227  ik_poses.push_back(ik_pose);
228 
229  return searchPositionIK(ik_poses, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code,
230  options);
231 }
232 
233 bool SrvKinematicsPlugin::searchPositionIK(const std::vector<geometry_msgs::msg::Pose>& ik_poses,
234  const std::vector<double>& ik_seed_state, double /*timeout*/,
235  const std::vector<double>& /*consistency_limits*/,
236  std::vector<double>& solution, const IKCallbackFn& solution_callback,
237  moveit_msgs::msg::MoveItErrorCodes& error_code,
238  const kinematics::KinematicsQueryOptions& /*options*/,
239  const moveit::core::RobotState* /*context_state*/) const
240 {
241  // Check if active
242  if (!active_)
243  {
244  RCLCPP_ERROR(LOGGER, "kinematics not active");
245  error_code.val = error_code.NO_IK_SOLUTION;
246  return false;
247  }
248 
249  // Check if seed state correct
250  if (ik_seed_state.size() != dimension_)
251  {
252  RCLCPP_ERROR_STREAM(LOGGER,
253  "Seed state must have size " << dimension_ << " instead of size " << ik_seed_state.size());
254  error_code.val = error_code.NO_IK_SOLUTION;
255  return false;
256  }
257 
258  // Check that we have the same number of poses as tips
259  if (tip_frames_.size() != ik_poses.size())
260  {
261  RCLCPP_ERROR_STREAM(LOGGER, "Mismatched number of pose requests (" << ik_poses.size() << ") to tip frames ("
262  << tip_frames_.size()
263  << ") in searchPositionIK");
264  error_code.val = error_code.NO_IK_SOLUTION;
265  return false;
266  }
267 
268  // Create the service message
269  auto ik_srv = std::make_shared<moveit_msgs::srv::GetPositionIK::Request>();
270  ik_srv->ik_request.avoid_collisions = true;
271  ik_srv->ik_request.group_name = getGroupName();
272 
273  // Copy seed state into virtual robot state and convert into moveit_msg
274  robot_state_->setJointGroupPositions(joint_model_group_, ik_seed_state);
275  moveit::core::robotStateToRobotStateMsg(*robot_state_, ik_srv->ik_request.robot_state);
276 
277  // Load the poses into the request in difference places depending if there is more than one or not
278  geometry_msgs::msg::PoseStamped ik_pose_st;
279  ik_pose_st.header.frame_id = base_frame_;
280  if (tip_frames_.size() > 1)
281  {
282  // Load into vector of poses
283  for (std::size_t i = 0; i < tip_frames_.size(); ++i)
284  {
285  ik_pose_st.pose = ik_poses[i];
286  ik_srv->ik_request.pose_stamped_vector.push_back(ik_pose_st);
287  ik_srv->ik_request.ik_link_names.push_back(tip_frames_[i]);
288  }
289  }
290  else
291  {
292  ik_pose_st.pose = ik_poses[0];
293 
294  // Load into single pose value
295  ik_srv->ik_request.pose_stamped = ik_pose_st;
296  ik_srv->ik_request.ik_link_name = getTipFrames()[0];
297  }
298 
299  RCLCPP_DEBUG(LOGGER, "Calling service: %s", ik_service_client_->get_service_name());
300  auto result_future = ik_service_client_->async_send_request(ik_srv);
301  const auto& response = result_future.get();
302  if (rclcpp::spin_until_future_complete(node_, result_future) == rclcpp::FutureReturnCode::SUCCESS)
303  {
304  // Check error code
305  error_code.val = response->error_code.val;
306  if (error_code.val != error_code.SUCCESS)
307  {
308  // TODO (JafarAbdi) Print the entire message for ROS2?
309  // RCLCPP_DEBUG("srv", "An IK that satisifes the constraints and is collision free could not be found."
310  // << "\nRequest was: \n"
311  // << ik_srv.request.ik_request << "\nResponse was: \n"
312  // << ik_srv.response.solution);
313  switch (error_code.val)
314  {
315  case moveit_msgs::msg::MoveItErrorCodes::FAILURE:
316  RCLCPP_ERROR(LOGGER, "Service failed with with error code: FAILURE");
317  break;
318  case moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION:
319  RCLCPP_DEBUG(LOGGER, "Service failed with with error code: NO IK SOLUTION");
320  break;
321  default:
322  RCLCPP_DEBUG_STREAM(LOGGER, "Service failed with with error code: " << error_code.val);
323  }
324  return false;
325  }
326  }
327  else
328  {
329  RCLCPP_DEBUG_STREAM(LOGGER, "Service call failed to connect to service: " << ik_service_client_->get_service_name());
330  error_code.val = error_code.FAILURE;
331  return false;
332  }
333  // Convert the robot state message to our robot_state representation
334  if (!moveit::core::robotStateMsgToRobotState(response->solution, *robot_state_))
335  {
336  RCLCPP_ERROR(LOGGER, "An error occurred converting received robot state message into internal robot state.");
337  error_code.val = error_code.FAILURE;
338  return false;
339  }
340 
341  // Get just the joints we are concerned about in our planning group
342  robot_state_->copyJointGroupPositions(joint_model_group_, solution);
343 
344  // Run the solution callback (i.e. collision checker) if available
345  if (solution_callback)
346  {
347  RCLCPP_DEBUG(LOGGER, "Calling solution callback on IK solution");
348 
349  // hack: should use all poses, not just the 0th
350  solution_callback(ik_poses[0], solution, error_code);
351 
352  if (error_code.val != error_code.SUCCESS)
353  {
354  switch (error_code.val)
355  {
356  case moveit_msgs::msg::MoveItErrorCodes::FAILURE:
357  RCLCPP_ERROR(LOGGER, "IK solution callback failed with with error code: FAILURE");
358  break;
359  case moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION:
360  RCLCPP_ERROR(LOGGER, "IK solution callback failed with with error code: "
361  "NO IK SOLUTION");
362  break;
363  default:
364  RCLCPP_ERROR_STREAM(LOGGER, "IK solution callback failed with with error code: " << error_code.val);
365  }
366  return false;
367  }
368  }
369 
370  RCLCPP_INFO(LOGGER, "IK Solver Succeeded!");
371  return true;
372 }
373 
374 bool SrvKinematicsPlugin::getPositionFK(const std::vector<std::string>& link_names,
375  const std::vector<double>& joint_angles,
376  std::vector<geometry_msgs::msg::Pose>& poses) const
377 {
378  if (!active_)
379  {
380  RCLCPP_ERROR(LOGGER, "kinematics not active");
381  return false;
382  }
383  poses.resize(link_names.size());
384  if (joint_angles.size() != dimension_)
385  {
386  RCLCPP_ERROR(LOGGER, "Joint angles vector must have size: %d", dimension_);
387  return false;
388  }
389 
390  RCLCPP_ERROR(LOGGER, "Forward kinematics not implemented");
391 
392  return false;
393 }
394 
395 const std::vector<std::string>& SrvKinematicsPlugin::getJointNames() const
396 {
397  return ik_group_info_.joint_names;
398 }
399 
400 const std::vector<std::string>& SrvKinematicsPlugin::getLinkNames() const
401 {
402  return ik_group_info_.link_names;
403 }
404 
405 const std::vector<std::string>& SrvKinematicsPlugin::getVariableNames() const
406 {
407  return joint_model_group_->getVariableNames();
408 }
409 
410 } // namespace srv_kinematics_plugin
Provides an interface for kinematics solvers.
void storeValues(const moveit::core::RobotModel &robot_model, const std::string &group_name, const std::string &base_frame, const std::vector< std::string > &tip_frames, double search_discretization)
std::vector< unsigned int > redundant_joint_indices_
static const rclcpp::Logger LOGGER
bool lookupParam(const rclcpp::Node::SharedPtr &node, const std::string &param, T &val, const T &default_val) const
Enables kinematics plugins access to parameters that are defined for the private namespace and inside...
virtual const std::vector< std::string > & getTipFrames() const
Return the names of the tip frames of the kinematic tree on which the solver is operating....
std::vector< std::string > tip_frames_
std::function< void(const geometry_msgs::msg::Pose &, const std::vector< double > &, moveit_msgs::msg::MoveItErrorCodes &)> IKCallbackFn
Signature for a callback to validate an IK solution. Typically used for collision checking.
moveit::core::RobotModelConstPtr robot_model_
virtual const std::string & getGroupName() const
Return the name of the group that the solver is operating on.
const std::vector< const JointModel * > & getActiveJointModels() const
Get the active joints in this group (that have controllable DOF). This does not include mimic joints.
const std::vector< std::string > & getJointModelNames() const
Get the names of the joints in this group. These are the names of the joints returned by getJointMode...
const std::vector< const JointModel * > & getJointModels() const
Get all the joints in this group (including fixed and mimic joints).
bool hasLinkModel(const std::string &link) const
Check if a link is part of this group.
unsigned int getVariableCount() const
Get the number of variables that describe this joint group. This includes variables necessary for mim...
const std::vector< std::string > & getVariableNames() const
Get the names of the variables that make up the joints included in this group. The number of returned...
const std::vector< const JointModel * > & getMimicJointModels() const
Get the mimic joints that are part of this group.
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
Definition: robot_model.h:76
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
Specific implementation of kinematics using ROS service calls to communicate with external IK solvers...
bool setRedundantJoints(const std::vector< unsigned int > &redundant_joint_indices) override
Set a set of redundant joints for the kinematics solver to use. This can fail, depending on the IK so...
const std::vector< std::string > & getJointNames() const override
Return all the joint names in the order they are used internally.
bool searchPositionIK(const geometry_msgs::msg::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, std::vector< double > &solution, moveit_msgs::msg::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const override
Given a desired pose of the end-effector, search for the joint angles required to reach it....
bool getPositionIK(const geometry_msgs::msg::Pose &ik_pose, const std::vector< double > &ik_seed_state, std::vector< double > &solution, moveit_msgs::msg::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const override
Given a desired pose of the end-effector, compute the joint angles to reach it.
const std::vector< std::string > & getVariableNames() const
Return all the variable names in the order they are represented internally.
const std::vector< std::string > & getLinkNames() const override
Return all the link names in the order they are represented internally.
bool getPositionFK(const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::msg::Pose > &poses) const override
Given a set of joint angles and a set of links, compute their pose.
bool initialize(const rclcpp::Node::SharedPtr &node, const moveit::core::RobotModel &robot_model, const std::string &group_name, const std::string &base_name, const std::vector< std::string > &tip_frames, double search_discretization) override
Initialization function for the kinematics, for use with kinematic chain IK solvers.
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.
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.
name
Definition: setup.py:7
A set of options for the kinematics solver.
CLASS_LOADER_REGISTER_CLASS(trajopt_interface::TrajOptPlannerManager, planning_interface::PlannerManager)