pr2_arm_kinematics_utils.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 
39 
40 namespace pr2_arm_kinematics
41 {
42 static const double IK_DEFAULT_TIMEOUT = 10.0;
43 bool loadRobotModel(ros::NodeHandle node_handle, urdf::Model& robot_model, std::string& xml_string)
44 {
45  std::string urdf_xml, full_urdf_xml;
46  node_handle.param("urdf_xml", urdf_xml, std::string("robot_description"));
47  node_handle.searchParam(urdf_xml, full_urdf_xml);
48  TiXmlDocument xml;
49  ROS_DEBUG("Reading xml file from parameter server\n");
50  std::string result;
51  if (node_handle.getParam(full_urdf_xml, result))
52  xml.Parse(result.c_str());
53  else
54  {
55  ROS_FATAL("Could not load the xml from parameter server: %s\n", urdf_xml.c_str());
56  return false;
57  }
58  xml_string = result;
59  TiXmlElement* root_element = xml.RootElement();
60  TiXmlElement* root = xml.FirstChildElement("robot");
61  if (!root || !root_element)
62  {
63  ROS_FATAL("Could not parse the xml from %s\n", urdf_xml.c_str());
64  exit(1);
65  }
66  robot_model.initXml(root);
67  return true;
68 }
69 
70 bool getKDLChain(const std::string& xml_string, const std::string& root_name, const std::string& tip_name,
71  KDL::Chain& kdl_chain)
72 {
73  // create robot chain from root to tip
74  KDL::Tree tree;
75  if (!kdl_parser::treeFromString(xml_string, tree))
76  {
77  ROS_ERROR("Could not initialize tree object");
78  return false;
79  }
80  if (!tree.getChain(root_name, tip_name, kdl_chain))
81  {
82  ROS_ERROR_STREAM("Could not initialize chain object for base " << root_name << " tip " << tip_name);
83  return false;
84  }
85  return true;
86 }
87 
88 bool getKDLTree(const std::string& xml_string, const std::string& root_name, const std::string& tip_name,
89  KDL::Tree& kdl_tree)
90 {
91  // create robot chain from root to tip
92  if (!kdl_parser::treeFromString(xml_string, kdl_tree))
93  {
94  ROS_ERROR("Could not initialize tree object");
95  return false;
96  }
97  return true;
98 }
99 
100 Eigen::Matrix4f KDLToEigenMatrix(const KDL::Frame& p)
101 {
102  Eigen::Matrix4f b = Eigen::Matrix4f::Identity();
103  for (int i = 0; i < 3; i++)
104  {
105  for (int j = 0; j < 3; j++)
106  {
107  b(i, j) = p.M(i, j);
108  }
109  b(i, 3) = p.p(i);
110  }
111  return b;
112 }
113 
114 double computeEuclideanDistance(const std::vector<double>& array_1, const KDL::JntArray& array_2)
115 {
116  double distance = 0.0;
117  for (int i = 0; i < (int)array_1.size(); i++)
118  {
119  distance += (array_1[i] - array_2(i)) * (array_1[i] - array_2(i));
120  }
121  return sqrt(distance);
122 }
123 
124 double distance(const urdf::Pose& transform)
125 {
126  return sqrt(transform.position.x * transform.position.x + transform.position.y * transform.position.y +
127  transform.position.z * transform.position.z);
128 }
129 
130 bool solveQuadratic(const double& a, const double& b, const double& c, double* x1, double* x2)
131 {
132  double discriminant = b * b - 4 * a * c;
133  if (fabs(a) < IK_EPS)
134  {
135  *x1 = -c / b;
136  *x2 = *x1;
137  return true;
138  }
139  // ROS_DEBUG("Discriminant: %f\n",discriminant);
140  if (discriminant >= 0)
141  {
142  *x1 = (-b + sqrt(discriminant)) / (2 * a);
143  *x2 = (-b - sqrt(discriminant)) / (2 * a);
144  return true;
145  }
146  else if (fabs(discriminant) < IK_EPS)
147  {
148  *x1 = -b / (2 * a);
149  *x2 = -b / (2 * a);
150  return true;
151  }
152  else
153  {
154  *x1 = -b / (2 * a);
155  *x2 = -b / (2 * a);
156  return false;
157  }
158 }
159 
160 Eigen::Matrix4f matrixInverse(const Eigen::Matrix4f& g)
161 {
162  Eigen::Matrix4f result = g;
163  Eigen::Matrix3f Rt = Eigen::Matrix3f::Identity();
164 
165  Eigen::Vector3f p = Eigen::Vector3f::Zero(3);
166  Eigen::Vector3f pinv = Eigen::Vector3f::Zero(3);
167 
168  Rt(0, 0) = g(0, 0);
169  Rt(1, 1) = g(1, 1);
170  Rt(2, 2) = g(2, 2);
171 
172  Rt(0, 1) = g(1, 0);
173  Rt(1, 0) = g(0, 1);
174 
175  Rt(0, 2) = g(2, 0);
176  Rt(2, 0) = g(0, 2);
177 
178  Rt(1, 2) = g(2, 1);
179  Rt(2, 1) = g(1, 2);
180 
181  p(0) = g(0, 3);
182  p(1) = g(1, 3);
183  p(2) = g(2, 3);
184 
185  pinv = -Rt * p;
186 
187  result(0, 0) = g(0, 0);
188  result(1, 1) = g(1, 1);
189  result(2, 2) = g(2, 2);
190 
191  result(0, 1) = g(1, 0);
192  result(1, 0) = g(0, 1);
193 
194  result(0, 2) = g(2, 0);
195  result(2, 0) = g(0, 2);
196 
197  result(1, 2) = g(2, 1);
198  result(2, 1) = g(1, 2);
199 
200  result(0, 3) = pinv(0);
201  result(1, 3) = pinv(1);
202  result(2, 3) = pinv(2);
203 
204  return result;
205 }
206 
207 bool solveCosineEqn(const double& a, const double& b, const double& c, double& soln1, double& soln2)
208 {
209  double theta1 = atan2(b, a);
210  double denom = sqrt(a * a + b * b);
211 
212  if (fabs(denom) < IK_EPS) // should never happen, wouldn't make sense but make sure it is checked nonetheless
213  {
214 #ifdef DEBUG
215  std::cout << "denom: " << denom << std::endl;
216 #endif
217  return false;
218  }
219  double rhs_ratio = c / denom;
220  if (rhs_ratio < -1 || rhs_ratio > 1)
221  {
222 #ifdef DEBUG
223  std::cout << "rhs_ratio: " << rhs_ratio << std::endl;
224 #endif
225  return false;
226  }
227  double acos_term = acos(rhs_ratio);
228  soln1 = theta1 + acos_term;
229  soln2 = theta1 - acos_term;
230 
231  return true;
232 }
233 
234 bool checkJointNames(const std::vector<std::string>& joint_names, const moveit_msgs::KinematicSolverInfo& chain_info)
235 {
236  for (unsigned int i = 0; i < chain_info.joint_names.size(); i++)
237  {
238  int index = -1;
239  for (unsigned int j = 0; j < joint_names.size(); j++)
240  {
241  if (chain_info.joint_names[i] == joint_names[j])
242  {
243  index = j;
244  break;
245  }
246  }
247  if (index < 0)
248  {
249  ROS_ERROR("Joint state does not contain joint state for %s.", chain_info.joint_names[i].c_str());
250  return false;
251  }
252  }
253  return true;
254 }
255 
256 bool checkLinkNames(const std::vector<std::string>& link_names, const moveit_msgs::KinematicSolverInfo& chain_info)
257 {
258  if (link_names.empty())
259  return false;
260  for (unsigned int i = 0; i < link_names.size(); i++)
261  {
262  if (!checkLinkName(link_names[i], chain_info))
263  return false;
264  }
265  return true;
266 }
267 
268 bool checkLinkName(const std::string& link_name, const moveit_msgs::KinematicSolverInfo& chain_info)
269 {
270  for (unsigned int i = 0; i < chain_info.link_names.size(); i++)
271  {
272  if (link_name == chain_info.link_names[i])
273  return true;
274  }
275  return false;
276 }
277 
278 bool checkRobotState(moveit_msgs::RobotState& robot_state, const moveit_msgs::KinematicSolverInfo& chain_info)
279 {
280  if ((int)robot_state.joint_state.position.size() != (int)robot_state.joint_state.name.size())
281  {
282  ROS_ERROR(
283  "Number of joints in robot_state.joint_state does not match number of positions in robot_state.joint_state");
284  return false;
285  }
286  if (!checkJointNames(robot_state.joint_state.name, chain_info))
287  {
288  ROS_ERROR("Robot state must contain joint state for every joint in the kinematic chain");
289  return false;
290  }
291  return true;
292 }
293 
294 bool checkFKService(moveit_msgs::GetPositionFK::Request& request, moveit_msgs::GetPositionFK::Response& response,
295  const moveit_msgs::KinematicSolverInfo& chain_info)
296 {
297  if (!checkLinkNames(request.fk_link_names, chain_info))
298  {
299  ROS_ERROR("Link name in service request does not match links that kinematics can provide solutions for.");
300  response.error_code.val = response.error_code.INVALID_LINK_NAME;
301  return false;
302  }
303  if (!checkRobotState(request.robot_state, chain_info))
304  {
305  response.error_code.val = response.error_code.INVALID_ROBOT_STATE;
306  return false;
307  }
308  return true;
309 }
310 
311 bool checkIKService(moveit_msgs::GetPositionIK::Request& request, moveit_msgs::GetPositionIK::Response& response,
312  const moveit_msgs::KinematicSolverInfo& chain_info)
313 {
314  if (!checkLinkName(request.ik_request.ik_link_name, chain_info))
315  {
316  ROS_ERROR("Link name in service request does not match links that kinematics can provide solutions for.");
317  response.error_code.val = response.error_code.INVALID_LINK_NAME;
318  return false;
319  }
320  if (!checkRobotState(request.ik_request.robot_state, chain_info))
321  {
322  response.error_code.val = response.error_code.INVALID_ROBOT_STATE;
323  return false;
324  }
325  if (request.ik_request.timeout <= ros::Duration(0.0))
326  {
327  response.error_code.val = response.error_code.TIMED_OUT;
328  return false;
329  }
330  return true;
331 }
332 
333 bool convertPoseToRootFrame(const geometry_msgs::PoseStamped& pose_msg, KDL::Frame& pose_kdl,
334  const std::string& root_frame, tf::TransformListener& tf)
335 {
336  geometry_msgs::PoseStamped pose_stamped;
337  if (!convertPoseToRootFrame(pose_msg, pose_stamped, root_frame, tf))
338  return false;
339  tf::poseMsgToKDL(pose_stamped.pose, pose_kdl);
340  return true;
341 }
342 
343 bool convertPoseToRootFrame(const geometry_msgs::PoseStamped& pose_msg, geometry_msgs::PoseStamped& pose_msg_out,
344  const std::string& root_frame, tf::TransformListener& tf)
345 {
346  geometry_msgs::PoseStamped pose_msg_in = pose_msg;
347  ROS_DEBUG("Request:\nframe_id: %s\nPosition: %f %f %f\n:Orientation: %f %f %f %f\n",
348  pose_msg_in.header.frame_id.c_str(), pose_msg_in.pose.position.x, pose_msg_in.pose.position.y,
349  pose_msg_in.pose.position.z, pose_msg_in.pose.orientation.x, pose_msg_in.pose.orientation.y,
350  pose_msg_in.pose.orientation.z, pose_msg_in.pose.orientation.w);
351  pose_msg_out = pose_msg;
352  tf::Stamped<tf::Pose> pose_stamped;
353  poseStampedMsgToTF(pose_msg_in, pose_stamped);
354 
355  if (!tf.canTransform(root_frame, pose_stamped.frame_id_, pose_stamped.stamp_))
356  {
357  std::string err;
358  if (tf.getLatestCommonTime(pose_stamped.frame_id_, root_frame, pose_stamped.stamp_, &err) != tf::NO_ERROR)
359  {
360  ROS_ERROR("pr2_arm_ik:: Cannot transform from '%s' to '%s'. TF said: %s", pose_stamped.frame_id_.c_str(),
361  root_frame.c_str(), err.c_str());
362  return false;
363  }
364  }
365  try
366  {
367  tf.transformPose(root_frame, pose_stamped, pose_stamped);
368  }
369  catch (...)
370  {
371  ROS_ERROR("pr2_arm_ik:: Cannot transform from '%s' to '%s'", pose_stamped.frame_id_.c_str(), root_frame.c_str());
372  return false;
373  }
374  tf::poseStampedTFToMsg(pose_stamped, pose_msg_out);
375  return true;
376 }
377 
378 int getJointIndex(const std::string& name, const moveit_msgs::KinematicSolverInfo& chain_info)
379 {
380  for (unsigned int i = 0; i < chain_info.joint_names.size(); i++)
381  {
382  if (chain_info.joint_names[i] == name)
383  {
384  return i;
385  }
386  }
387  return -1;
388 }
389 
390 void getKDLChainInfo(const KDL::Chain& chain, moveit_msgs::KinematicSolverInfo& chain_info)
391 {
392  int i = 0; // segment number
393  while (i < (int)chain.getNrOfSegments())
394  {
395  chain_info.link_names.push_back(chain.getSegment(i).getName());
396  i++;
397  }
398 }
399 
400 int getKDLSegmentIndex(const KDL::Chain& chain, const std::string& name)
401 {
402  int i = 0; // segment number
403  while (i < (int)chain.getNrOfSegments())
404  {
405  if (chain.getSegment(i).getName() == name)
406  {
407  return i + 1;
408  }
409  i++;
410  }
411  return -1;
412 }
413 }
static const double IK_DEFAULT_TIMEOUT
#define ROS_FATAL(...)
bool canTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, std::string *error_msg=NULL) const
void transformPose(const std::string &target_frame, const geometry_msgs::PoseStamped &stamped_in, geometry_msgs::PoseStamped &stamped_out) const
static void poseStampedTFToMsg(const Stamped< Pose > &bt, geometry_msgs::PoseStamped &msg)
Namespace for the PR2ArmKinematics.
unsigned int getNrOfSegments() const
bool getKDLChain(const urdf::ModelInterface &model, const std::string &root_name, const std::string &tip_name, KDL::Chain &kdl_chain)
bool solveQuadratic(const double &a, const double &b, const double &c, double *x1, double *x2)
const Segment & getSegment(unsigned int nr) const
#define ROS_ERROR(...)
bool checkJointNames(const std::vector< std::string > &joint_names, const moveit_msgs::KinematicSolverInfo &chain_info)
void getKDLChainInfo(const KDL::Chain &chain, moveit_msgs::KinematicSolverInfo &chain_info)
#define ROS_DEBUG(...)
Rotation M
unsigned int index
bool param(const std::string &param_name, T &param_val, const T &default_val) const
bool convertPoseToRootFrame(const geometry_msgs::PoseStamped &pose_msg, KDL::Frame &pose_kdl, const std::string &root_frame, tf::TransformListener &tf)
bool checkIKService(moveit_msgs::GetPositionIK::Request &request, moveit_msgs::GetPositionIK::Response &response, const moveit_msgs::KinematicSolverInfo &chain_info)
bool checkLinkName(const std::string &link_name, const moveit_msgs::KinematicSolverInfo &chain_info)
bool getParam(const std::string &key, std::string &s) const
bool checkRobotState(moveit_msgs::RobotState &robot_state, const moveit_msgs::KinematicSolverInfo &chain_info)
void poseMsgToKDL(const geometry_msgs::Pose &m, KDL::Frame &k)
int getJointIndex(const std::string &name, const moveit_msgs::KinematicSolverInfo &chain_info)
bool getChain(const std::string &chain_root, const std::string &chain_tip, Chain &chain) const
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
KDL_PARSER_PUBLIC bool treeFromString(const std::string &xml, KDL::Tree &tree)
URDF_EXPORT bool initXml(const tinyxml2::XMLElement *xml)
bool searchParam(const std::string &key, std::string &result) const
ros::Time stamp_
int getLatestCommonTime(const std::string &source_frame, const std::string &target_frame, ros::Time &time, std::string *error_string) const
INLINE Rall1d< T, V, S > acos(const Rall1d< T, V, S > &x)
std::string frame_id_
const std::string & getName() const
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
bool checkFKService(moveit_msgs::GetPositionFK::Request &request, moveit_msgs::GetPositionFK::Response &response, const moveit_msgs::KinematicSolverInfo &chain_info)
static const double IK_EPS
#define ROS_ERROR_STREAM(args)
bool checkLinkNames(const std::vector< std::string > &link_names, const moveit_msgs::KinematicSolverInfo &chain_info)
bool loadRobotModel(ros::NodeHandle node_handle, urdf::Model &robot_model, std::string &xml_string)
double distance(const urdf::Pose &transform)
Eigen::Matrix4f matrixInverse(const Eigen::Matrix4f &g)
bool getKDLTree(const std::string &xml_string, const std::string &root_name, const std::string &tip_name, KDL::Tree &kdl_chain)
bool solveCosineEqn(const double &a, const double &b, const double &c, double &soln1, double &soln2)
int getKDLSegmentIndex(const KDL::Chain &chain, const std::string &name)
double computeEuclideanDistance(const std::vector< double > &array_1, const KDL::JntArray &array_2)
NO_ERROR
Eigen::Isometry3f KDLToEigenMatrix(const KDL::Frame &p)


pr2_moveit_plugins
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Mon Feb 28 2022 22:51:25