moveit2
The MoveIt Motion Planning Framework for ROS 2.
pr2_arm_kinematics_plugin.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, 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: Sachin Chitta */
36 
37 #include <geometry_msgs/msg/pose_stamped.hpp>
38 #include <kdl_parser/kdl_parser.hpp>
39 #include <tf2_kdl/tf2_kdl.hpp>
40 #include <algorithm>
41 #include <cmath>
42 
45 
46 using namespace KDL;
47 using namespace std;
48 
49 namespace pr2_arm_kinematics
50 {
51 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_constraint_samplers.test.pr2_arm_kinematics_plugin");
52 
53 bool PR2ArmIKSolver::getCount(int& count, const int& max_count, const int& min_count)
54 {
55  if (count > 0)
56  {
57  if (-count >= min_count)
58  {
59  count = -count;
60  return true;
61  }
62  else if (count + 1 <= max_count)
63  {
64  count = count + 1;
65  return true;
66  }
67  else
68  {
69  return false;
70  }
71  }
72  else
73  {
74  if (1 - count <= max_count)
75  {
76  count = 1 - count;
77  return true;
78  }
79  else if (count - 1 >= min_count)
80  {
81  count = count - 1;
82  return true;
83  }
84  else
85  return false;
86  }
87 }
88 
89 PR2ArmIKSolver::PR2ArmIKSolver(const urdf::ModelInterface& robot_model, const std::string& root_frame_name,
90  const std::string& tip_frame_name, const double& search_discretization_angle,
91  const int& free_angle)
92  : ChainIkSolverPos()
93 {
94  search_discretization_angle_ = search_discretization_angle;
95  free_angle_ = free_angle;
96  root_frame_name_ = root_frame_name;
97  active_ = pr2_arm_ik_.init(robot_model, root_frame_name, tip_frame_name);
98 }
99 
101 {
102  // TODO: move (re)allocation of any internal data structures here
103  // to react to changes in chain
104 }
105 
106 int PR2ArmIKSolver::CartToJnt(const KDL::JntArray& q_init, const KDL::Frame& p_in, KDL::JntArray& q_out)
107 {
108  const bool verbose = false;
109  Eigen::Isometry3f b = KDLToEigenMatrix(p_in);
110  std::vector<std::vector<double> > solution_ik;
111  if (free_angle_ == 0)
112  {
113  if (verbose)
114  RCLCPP_WARN(LOGGER, "Solving with %f", q_init(0));
115  pr2_arm_ik_.computeIKShoulderPan(b, q_init(0), solution_ik);
116  }
117  else
118  {
119  pr2_arm_ik_.computeIKShoulderRoll(b, q_init(2), solution_ik);
120  }
121 
122  if (solution_ik.empty())
123  return -1;
124 
125  double min_distance = 1e6;
126  int min_index = -1;
127 
128  for (int i = 0; i < static_cast<int>(solution_ik.size()); ++i)
129  {
130  if (verbose)
131  {
132  RCLCPP_WARN(LOGGER, "Solution : %d", static_cast<int>(solution_ik.size()));
133 
134  for (int j = 0; j < static_cast<int>(solution_ik[i].size()); ++j)
135  {
136  RCLCPP_WARN(LOGGER, "%d: %f", j, solution_ik[i][j]);
137  }
138  RCLCPP_WARN(LOGGER, " ");
139  RCLCPP_WARN(LOGGER, " ");
140  }
141  double tmp_distance = computeEuclideanDistance(solution_ik[i], q_init);
142  if (tmp_distance < min_distance)
143  {
144  min_distance = tmp_distance;
145  min_index = i;
146  }
147  }
148 
149  if (min_index > -1)
150  {
151  q_out.resize(static_cast<int>(solution_ik[min_index].size()));
152  for (int i = 0; i < static_cast<int>(solution_ik[min_index].size()); ++i)
153  {
154  q_out(i) = solution_ik[min_index][i];
155  }
156  return 1;
157  }
158  else
159  return -1;
160 }
161 
162 int PR2ArmIKSolver::cartToJntSearch(const KDL::JntArray& q_in, const KDL::Frame& p_in, KDL::JntArray& q_out,
163  const double& timeout)
164 {
165  const bool verbose = false;
166  KDL::JntArray q_init = q_in;
167  double initial_guess = q_init(free_angle_);
168 
169  rclcpp::Time start_time = rclcpp::Clock(RCL_ROS_TIME).now();
170  double loop_time = 0;
171  int count = 0;
172 
173  int num_positive_increments = static_cast<int>(
174  (pr2_arm_ik_.solver_info_.limits[free_angle_].max_position - initial_guess) / search_discretization_angle_);
175  int num_negative_increments = static_cast<int>(
176  (initial_guess - pr2_arm_ik_.solver_info_.limits[free_angle_].min_position) / search_discretization_angle_);
177  if (verbose)
178  RCLCPP_WARN(LOGGER, "%f %f %f %d %d \n\n", initial_guess, pr2_arm_ik_.solver_info_.limits[free_angle_].max_position,
179  pr2_arm_ik_.solver_info_.limits[free_angle_].min_position, num_positive_increments,
180  num_negative_increments);
181  while (loop_time < timeout)
182  {
183  if (CartToJnt(q_init, p_in, q_out) > 0)
184  return 1;
185  if (!getCount(count, num_positive_increments, -num_negative_increments))
186  return -1;
187  q_init(free_angle_) = initial_guess + search_discretization_angle_ * count;
188  if (verbose)
189  RCLCPP_WARN(LOGGER, "%d, %f", count, q_init(free_angle_));
190  loop_time = rclcpp::Clock(RCL_ROS_TIME).now().seconds() - start_time.seconds();
191  }
192  if (loop_time >= timeout)
193  {
194  RCLCPP_WARN(LOGGER, "IK Timed out in %f seconds", timeout);
195  return TIMED_OUT;
196  }
197  else
198  {
199  RCLCPP_WARN(LOGGER, "No IK solution was found");
200  return NO_IK_SOLUTION;
201  }
202  return NO_IK_SOLUTION;
203 }
204 
205 bool getKDLChain(const urdf::ModelInterface& model, const std::string& root_name, const std::string& tip_name,
206  KDL::Chain& kdl_chain)
207 {
208  // create robot chain from root to tip
209  KDL::Tree tree;
210  if (!kdl_parser::treeFromUrdfModel(model, tree))
211  {
212  RCLCPP_ERROR(LOGGER, "Could not initialize tree object");
213  return false;
214  }
215  if (!tree.getChain(root_name, tip_name, kdl_chain))
216  {
217  RCLCPP_ERROR(LOGGER, "Could not initialize chain object for base %s tip %s", root_name.c_str(), tip_name.c_str());
218  return false;
219  }
220  return true;
221 }
222 
223 Eigen::Isometry3f KDLToEigenMatrix(const KDL::Frame& p)
224 {
225  Eigen::Isometry3f b = Eigen::Isometry3f::Identity();
226  for (int i = 0; i < 3; ++i)
227  {
228  for (int j = 0; j < 3; ++j)
229  {
230  b(i, j) = p.M(i, j);
231  }
232  b(i, 3) = p.p(i);
233  }
234  return b;
235 }
236 
237 double computeEuclideanDistance(const std::vector<double>& array_1, const KDL::JntArray& array_2)
238 {
239  double distance = 0.0;
240  for (int i = 0; i < static_cast<int>(array_1.size()); ++i)
241  {
242  distance += (array_1[i] - array_2(i)) * (array_1[i] - array_2(i));
243  }
244  return std::sqrt(distance);
245 }
246 
247 void getKDLChainInfo(const KDL::Chain& chain, moveit_msgs::msg::KinematicSolverInfo& chain_info)
248 {
249  int i = 0; // segment number
250  while (i < static_cast<int>(chain.getNrOfSegments()))
251  {
252  chain_info.link_names.push_back(chain.getSegment(i).getName());
253  i++;
254  }
255 }
256 
258 {
259 }
260 
262 {
263  return active_;
264 }
265 
266 bool PR2ArmKinematicsPlugin::initialize(const rclcpp::Node::SharedPtr& node,
267  const moveit::core::RobotModel& robot_model, const std::string& group_name,
268  const std::string& base_frame, const std::vector<std::string>& tip_frames,
269  double search_discretization)
270 {
271  node_ = node;
272  storeValues(robot_model, group_name, base_frame, tip_frames, search_discretization);
273  const bool verbose = false;
274  std::string xml_string;
275  dimension_ = 7;
276 
277  RCLCPP_WARN(LOGGER, "Loading KDL Tree");
278  if (!getKDLChain(*robot_model.getURDF(), base_frame_, tip_frames_[0], kdl_chain_))
279  {
280  active_ = false;
281  RCLCPP_ERROR(LOGGER, "Could not load kdl tree");
282  }
283  jnt_to_pose_solver_ = std::make_shared<KDL::ChainFkSolverPos_recursive>(kdl_chain_);
284  free_angle_ = 2;
285 
286  pr2_arm_ik_solver_ = std::make_shared<pr2_arm_kinematics::PR2ArmIKSolver>(
287  *robot_model.getURDF(), base_frame_, tip_frames_[0], search_discretization, free_angle_);
288  if (!pr2_arm_ik_solver_->active_)
289  {
290  RCLCPP_ERROR(LOGGER, "Could not load ik");
291  active_ = false;
292  }
293  else
294  {
295  pr2_arm_ik_solver_->getSolverInfo(ik_solver_info_);
297  fk_solver_info_.joint_names = ik_solver_info_.joint_names;
298 
299  if (verbose)
300  {
301  for (const std::string& joint_name : ik_solver_info_.joint_names)
302  {
303  RCLCPP_WARN(LOGGER, "PR2Kinematics:: joint name: %s", joint_name.c_str());
304  }
305  for (const std::string& link_name : ik_solver_info_.link_names)
306  {
307  RCLCPP_WARN(LOGGER, "PR2Kinematics can solve IK for %s", link_name.c_str());
308  }
309  for (const std::string& link_name : fk_solver_info_.link_names)
310  {
311  RCLCPP_WARN(LOGGER, "PR2Kinematics can solve FK for %s", link_name.c_str());
312  }
313  RCLCPP_WARN(LOGGER, "PR2KinematicsPlugin::active for %s", group_name.c_str());
314  }
315  active_ = true;
316  }
317  return active_;
318 }
319 
320 bool PR2ArmKinematicsPlugin::getPositionIK(const geometry_msgs::msg::Pose& /*ik_pose*/,
321  const std::vector<double>& /*ik_seed_state*/,
322  std::vector<double>& /*solution*/,
323  moveit_msgs::msg::MoveItErrorCodes& /*error_code*/,
324  const kinematics::KinematicsQueryOptions& /*options*/) const
325 {
326  return false;
327 }
328 
329 bool PR2ArmKinematicsPlugin::searchPositionIK(const geometry_msgs::msg::Pose& ik_pose,
330  const std::vector<double>& ik_seed_state, double timeout,
331  std::vector<double>& solution,
332  moveit_msgs::msg::MoveItErrorCodes& error_code,
333  const kinematics::KinematicsQueryOptions& /*options*/) const
334 {
335  if (!active_)
336  {
337  RCLCPP_ERROR(LOGGER, "kinematics not active");
338  error_code.val = error_code.PLANNING_FAILED;
339  return false;
340  }
341 
342  geometry_msgs::msg::PoseStamped ik_pose_stamped;
343  ik_pose_stamped.pose = ik_pose;
344 
345  tf2::Stamped<KDL::Frame> pose_desired;
346 
347  tf2::fromMsg(ik_pose_stamped, pose_desired);
348 
349  // Do the IK
350  KDL::JntArray jnt_pos_in;
351  KDL::JntArray jnt_pos_out;
352  jnt_pos_in.resize(dimension_);
353  for (int i = 0; i < dimension_; ++i)
354  {
355  jnt_pos_in(i) = ik_seed_state[i];
356  }
357 
358  int ik_valid = pr2_arm_ik_solver_->cartToJntSearch(jnt_pos_in, pose_desired, jnt_pos_out, timeout);
359  if (ik_valid == pr2_arm_kinematics::NO_IK_SOLUTION)
360  {
361  error_code.val = error_code.NO_IK_SOLUTION;
362  return false;
363  }
364 
365  if (ik_valid >= 0)
366  {
367  solution.resize(dimension_);
368  for (int i = 0; i < dimension_; ++i)
369  {
370  solution[i] = jnt_pos_out(i);
371  }
372  error_code.val = error_code.SUCCESS;
373  return true;
374  }
375  else
376  {
377  RCLCPP_WARN(LOGGER, "An IK solution could not be found");
378  error_code.val = error_code.NO_IK_SOLUTION;
379  return false;
380  }
381 }
382 
383 bool PR2ArmKinematicsPlugin::searchPositionIK(const geometry_msgs::msg::Pose& /*ik_pose*/,
384  const std::vector<double>& /*ik_seed_state*/, double /*timeout*/,
385  const std::vector<double>& /*consistency_limit*/,
386  std::vector<double>& /*solution*/,
387  moveit_msgs::msg::MoveItErrorCodes& /*error_code*/,
388  const kinematics::KinematicsQueryOptions& /*options*/) const
389 {
390  return false;
391 }
392 
393 bool PR2ArmKinematicsPlugin::searchPositionIK(const geometry_msgs::msg::Pose& /*ik_pose*/,
394  const std::vector<double>& /*ik_seed_state*/, double /*timeout*/,
395  std::vector<double>& /*solution*/,
396  const IKCallbackFn& /*solution_callback*/,
397  moveit_msgs::msg::MoveItErrorCodes& /*error_code*/,
398  const kinematics::KinematicsQueryOptions& /*options*/) const
399 {
400  return false;
401 }
402 
403 bool PR2ArmKinematicsPlugin::searchPositionIK(const geometry_msgs::msg::Pose& /*ik_pose*/,
404  const std::vector<double>& /*ik_seed_state*/, double /*timeout*/,
405  const std::vector<double>& /*consistency_limit*/,
406  std::vector<double>& /*solution*/,
407  const IKCallbackFn& /*solution_callback*/,
408  moveit_msgs::msg::MoveItErrorCodes& /*error_code*/,
409  const kinematics::KinematicsQueryOptions& /*options*/) const
410 {
411  return false;
412 }
413 
414 bool PR2ArmKinematicsPlugin::getPositionFK(const std::vector<std::string>& /*link_names*/,
415  const std::vector<double>& /*joint_angles*/,
416  std::vector<geometry_msgs::msg::Pose>& /*poses*/) const
417 {
418  return false;
419 }
420 
421 const std::vector<std::string>& PR2ArmKinematicsPlugin::getJointNames() const
422 {
423  if (!active_)
424  {
425  RCLCPP_ERROR(LOGGER, "kinematics not active");
426  }
427  return ik_solver_info_.joint_names;
428 }
429 
430 const std::vector<std::string>& PR2ArmKinematicsPlugin::getLinkNames() const
431 {
432  if (!active_)
433  {
434  RCLCPP_ERROR(LOGGER, "kinematics not active");
435  }
436  return fk_solver_info_.link_names;
437 }
438 
439 } // namespace pr2_arm_kinematics
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)
static const rclcpp::Logger LOGGER
rclcpp::Node::SharedPtr node_
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.
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
Definition: robot_model.h:76
const urdf::ModelInterfaceSharedPtr & getURDF() const
Get the parsed URDF model.
Definition: robot_model.h:106
int cartToJntSearch(const KDL::JntArray &q_in, const KDL::Frame &p_in, KDL::JntArray &q_out, const double &timeout)
PR2ArmIK pr2_arm_ik_
The PR2 inverse kinematics solver.
int CartToJnt(const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out) override
bool active_
Indicates whether the solver has been successfully initialized.
void computeIKShoulderRoll(const Eigen::Isometry3f &g_in, const double &shoulder_roll_initial_guess, std::vector< std::vector< double > > &solution) const
compute IK based on an initial guess for the shoulder roll angle. h
Definition: pr2_arm_ik.cpp:466
bool init(const urdf::ModelInterface &robot_model, const std::string &root_name, const std::string &tip_name)
Initialize the solver by providing a urdf::Model and a root and tip name.
Definition: pr2_arm_ik.cpp:58
void computeIKShoulderPan(const Eigen::Isometry3f &g_in, const double &shoulder_pan_initial_guess, std::vector< std::vector< double > > &solution) const
compute IK based on an initial guess for the shoulder pan angle.
Definition: pr2_arm_ik.cpp:201
moveit_msgs::msg::KinematicSolverInfo solver_info_
get chain information about the arm.
Definition: pr2_arm_ik.h:166
bool isActive()
Specifies if the node is active or not.
moveit_msgs::msg::KinematicSolverInfo ik_solver_info_
const std::vector< std::string > & getJointNames() const override
Return all the joint names in the order they are used internally.
bool initialize(const rclcpp::Node::SharedPtr &node, 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) override
Initialization function for the kinematics.
const std::vector< std::string > & getLinkNames() const override
Return all the link names in the order they are represented internally.
pr2_arm_kinematics::PR2ArmIKSolverPtr pr2_arm_ik_solver_
moveit_msgs::msg::KinematicSolverInfo fk_solver_info_
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.
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.
std::shared_ptr< KDL::ChainFkSolverPos_recursive > jnt_to_pose_solver_
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....
p
Definition: pick.py:62
Eigen::Isometry3f KDLToEigenMatrix(const KDL::Frame &p)
bool getKDLChain(const urdf::ModelInterface &model, const std::string &root_name, const std::string &tip_name, KDL::Chain &kdl_chain)
double distance(const urdf::Pose &transform)
Definition: pr2_arm_ik.h:55
void getKDLChainInfo(const KDL::Chain &chain, moveit_msgs::msg::KinematicSolverInfo &chain_info)
double computeEuclideanDistance(const std::vector< double > &array_1, const KDL::JntArray &array_2)
A set of options for the kinematics solver.