moveit2
The MoveIt Motion Planning Framework for ROS 2.
pr2_arm_ik.hpp
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 #pragma once
38 
39 #include <urdf_model/model.h>
40 #if __has_include(<urdf/model.hpp>)
41 #include <urdf/model.hpp>
42 #else
43 #include <urdf/model.h>
44 #endif
45 #include <Eigen/Geometry>
46 #include <Eigen/LU> // provides LU decomposition
47 #include <kdl/chainiksolver.hpp>
48 #include <moveit_msgs/srv/get_position_fk.hpp>
49 #include <moveit_msgs/srv/get_position_ik.hpp>
50 #include <moveit_msgs/msg/kinematic_solver_info.hpp>
51 #include <rclcpp/rclcpp.hpp>
52 
53 namespace pr2_arm_kinematics
54 {
55 static const int NUM_JOINTS_ARM7DOF = 7;
56 
57 static const double IK_EPS = 1e-5;
58 
59 inline double distance(const urdf::Pose& transform)
60 {
61  return sqrt(transform.position.x * transform.position.x + transform.position.y * transform.position.y +
62  transform.position.z * transform.position.z);
63 }
64 
65 inline bool solveQuadratic(double a, double b, double c, double* x1, double* x2)
66 {
67  double discriminant = b * b - 4 * a * c;
68  if (fabs(a) < IK_EPS)
69  {
70  *x1 = -c / b;
71  *x2 = *x1;
72  return true;
73  }
74  // ROS_DEBUG("Discriminant: %f\n",discriminant);
75  if (discriminant >= 0)
76  {
77  *x1 = (-b + sqrt(discriminant)) / (2 * a);
78  *x2 = (-b - sqrt(discriminant)) / (2 * a);
79  return true;
80  }
81  else if (fabs(discriminant) < IK_EPS)
82  {
83  *x1 = -b / (2 * a);
84  *x2 = -b / (2 * a);
85  return true;
86  }
87  else
88  {
89  *x1 = -b / (2 * a);
90  *x2 = -b / (2 * a);
91  return false;
92  }
93 }
94 
95 inline bool solveCosineEqn(double a, double b, double c, double& soln1, double& soln2)
96 {
97  double theta1 = atan2(b, a);
98  double denom = sqrt(a * a + b * b);
99 
100  if (fabs(denom) < IK_EPS) // should never happen, wouldn't make sense but make sure it is checked nonetheless
101  {
102 #ifdef DEBUG
103  std::cout << "denom: " << denom << '\n';
104 #endif
105  return false;
106  }
107  double rhs_ratio = c / denom;
108  if (rhs_ratio < -1 || rhs_ratio > 1)
109  {
110 #ifdef DEBUG
111  std::cout << "rhs_ratio: " << rhs_ratio << '\n';
112 #endif
113  return false;
114  }
115  double acos_term = acos(rhs_ratio);
116  soln1 = theta1 + acos_term;
117  soln2 = theta1 - acos_term;
118 
119  return true;
120 }
121 
122 class PR2ArmIK
123 {
124 public:
130  PR2ArmIK();
132 
140  bool init(const urdf::ModelInterface& robot_model, const std::string& root_name, const std::string& tip_name);
141 
147  void computeIKShoulderPan(const Eigen::Isometry3f& g_in, double shoulder_pan_initial_guess,
148  std::vector<std::vector<double> >& solution) const;
149 
155  void computeIKShoulderRoll(const Eigen::Isometry3f& g_in, double shoulder_roll_initial_guess,
156  std::vector<std::vector<double> >& solution) const;
157 
158  // std::vector<std::vector<double> > solution_ik_;/// a vector of ik solutions
159 
165  void getSolverInfo(moveit_msgs::msg::KinematicSolverInfo& info);
166 
170  moveit_msgs::msg::KinematicSolverInfo solver_info_;
171 
173 
174 private:
175  void addJointToChainInfo(const urdf::JointConstSharedPtr& joint, moveit_msgs::msg::KinematicSolverInfo& info);
176 
177  bool checkJointLimits(const std::vector<double>& joint_values) const;
178 
179  bool checkJointLimits(double joint_value, int joint_num) const;
180 
181  Eigen::Isometry3f grhs_, gf_, home_inv_;
182 
183  std::vector<double> angle_multipliers_;
184 
185  std::vector<double> solution_;
186 
187  double shoulder_upperarm_offset_, upperarm_elbow_offset_, elbow_wrist_offset_, shoulder_wrist_offset_,
188  shoulder_elbow_offset_, torso_shoulder_offset_x_, torso_shoulder_offset_y_, torso_shoulder_offset_z_;
189 
190  std::vector<double> min_angles_;
191 
192  std::vector<double> max_angles_;
193 
194  std::vector<bool> continuous_joint_;
195 };
196 } // namespace pr2_arm_kinematics
ROS/KDL based interface for the inverse kinematics of the PR2 arm.
void computeIKShoulderRoll(const Eigen::Isometry3f &g_in, 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:475
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:65
void computeIKShoulderPan(const Eigen::Isometry3f &g_in, 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:210
moveit_msgs::msg::KinematicSolverInfo solver_info_
get chain information about the arm.
Definition: pr2_arm_ik.hpp:170
void getSolverInfo(moveit_msgs::msg::KinematicSolverInfo &info)
get chain information about the arm. This populates the IK query response, filling in joint level inf...
Definition: pr2_arm_ik.cpp:205
double distance(const urdf::Pose &transform)
Definition: pr2_arm_ik.hpp:59
bool solveQuadratic(double a, double b, double c, double *x1, double *x2)
Definition: pr2_arm_ik.hpp:65
bool solveCosineEqn(double a, double b, double c, double &soln1, double &soln2)
Definition: pr2_arm_ik.hpp:95