trac_ik.cpp
Go to the documentation of this file.
1 /********************************************************************************
2 Copyright (c) 2015, TRACLabs, Inc.
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without modification,
6  are permitted provided that the following conditions are met:
7 
8  1. Redistributions of source code must retain the above copyright notice,
9  this list of conditions and the following disclaimer.
10 
11  2. Redistributions in binary form must reproduce the above copyright notice,
12  this list of conditions and the following disclaimer in the documentation
13  and/or other materials provided with the distribution.
14 
15  3. Neither the name of the copyright holder nor the names of its contributors
16  may be used to endorse or promote products derived from this software
17  without specific prior written permission.
18 
19 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
20 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
21 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
22 IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT,
23 INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
24 BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
25 DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
26 LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
27 OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
28 OF THE POSSIBILITY OF SUCH DAMAGE.
29 ********************************************************************************/
30 
31 
32 #include <trac_ik/trac_ik.hpp>
33 #include <boost/date_time.hpp>
34 #include <Eigen/Geometry>
35 #include <ros/ros.h>
36 #include <limits>
38 #include <urdf/model.h>
39 
40 namespace TRAC_IK
41 {
42 
43 TRAC_IK::TRAC_IK(const std::string& base_link, const std::string& tip_link, const std::string& URDF_param, double _maxtime, double _eps, SolveType _type) :
44  initialized(false),
45  eps(_eps),
46  maxtime(_maxtime),
47  solvetype(_type)
48 {
49 
50  ros::NodeHandle node_handle("~");
51 
52  urdf::Model robot_model;
53  std::string xml_string;
54 
55  std::string urdf_xml, full_urdf_xml;
56  node_handle.param("urdf_xml", urdf_xml, URDF_param);
57  node_handle.searchParam(urdf_xml, full_urdf_xml);
58 
59  ROS_DEBUG_NAMED("trac_ik", "Reading xml file from parameter server");
60  if (!node_handle.getParam(full_urdf_xml, xml_string))
61  {
62  ROS_FATAL_NAMED("trac_ik", "Could not load the xml from parameter server: %s", urdf_xml.c_str());
63  return;
64  }
65 
66  node_handle.param(full_urdf_xml, xml_string, std::string());
67  robot_model.initString(xml_string);
68 
69  ROS_DEBUG_STREAM_NAMED("trac_ik", "Reading joints and links from URDF");
70 
71  KDL::Tree tree;
72 
73  if (!kdl_parser::treeFromUrdfModel(robot_model, tree))
74  ROS_FATAL("Failed to extract kdl tree from xml robot description");
75 
76  if (!tree.getChain(base_link, tip_link, chain))
77  ROS_FATAL("Couldn't find chain %s to %s", base_link.c_str(), tip_link.c_str());
78 
79  std::vector<KDL::Segment> chain_segs = chain.segments;
80 
81  urdf::JointConstSharedPtr joint;
82 
83  std::vector<double> l_bounds, u_bounds;
84 
85  lb.resize(chain.getNrOfJoints());
86  ub.resize(chain.getNrOfJoints());
87 
88  uint joint_num = 0;
89  for (unsigned int i = 0; i < chain_segs.size(); ++i)
90  {
91  joint = robot_model.getJoint(chain_segs[i].getJoint().getName());
92  if (joint->type != urdf::Joint::UNKNOWN && joint->type != urdf::Joint::FIXED)
93  {
94  joint_num++;
95  float lower, upper;
96  int hasLimits;
97  if (joint->type != urdf::Joint::CONTINUOUS)
98  {
99  if (joint->safety)
100  {
101  lower = std::max(joint->limits->lower, joint->safety->soft_lower_limit);
102  upper = std::min(joint->limits->upper, joint->safety->soft_upper_limit);
103  }
104  else
105  {
106  lower = joint->limits->lower;
107  upper = joint->limits->upper;
108  }
109  hasLimits = 1;
110  }
111  else
112  {
113  hasLimits = 0;
114  }
115  if (hasLimits)
116  {
117  lb(joint_num - 1) = lower;
118  ub(joint_num - 1) = upper;
119  }
120  else
121  {
122  lb(joint_num - 1) = std::numeric_limits<float>::lowest();
123  ub(joint_num - 1) = std::numeric_limits<float>::max();
124  }
125  ROS_DEBUG_STREAM_NAMED("trac_ik", "IK Using joint " << joint->name << " " << lb(joint_num - 1) << " " << ub(joint_num - 1));
126  }
127  }
128 
129  initialize();
130 }
131 
132 
133 TRAC_IK::TRAC_IK(const KDL::Chain& _chain, const KDL::JntArray& _q_min, const KDL::JntArray& _q_max, double _maxtime, double _eps, SolveType _type):
134  initialized(false),
135  chain(_chain),
136  lb(_q_min),
137  ub(_q_max),
138  eps(_eps),
139  maxtime(_maxtime),
140  solvetype(_type)
141 {
142  initialize();
143 }
144 
145 void TRAC_IK::initialize()
146 {
147 
148  assert(chain.getNrOfJoints() == lb.data.size());
149  assert(chain.getNrOfJoints() == ub.data.size());
150 
151  jacsolver.reset(new KDL::ChainJntToJacSolver(chain));
152  nl_solver.reset(new NLOPT_IK::NLOPT_IK(chain, lb, ub, maxtime, eps, NLOPT_IK::SumSq));
153  iksolver.reset(new KDL::ChainIkSolverPos_TL(chain, lb, ub, maxtime, eps, true, true));
154 
155  for (uint i = 0; i < chain.segments.size(); i++)
156  {
157  std::string type = chain.segments[i].getJoint().getTypeName();
158  if (type.find("Rot") != std::string::npos)
159  {
160  if (ub(types.size()) >= std::numeric_limits<float>::max() &&
161  lb(types.size()) <= std::numeric_limits<float>::lowest())
162  types.push_back(KDL::BasicJointType::Continuous);
163  else
164  types.push_back(KDL::BasicJointType::RotJoint);
165  }
166  else if (type.find("Trans") != std::string::npos)
167  types.push_back(KDL::BasicJointType::TransJoint);
168  }
169 
170  assert(types.size() == lb.data.size());
171 
172  initialized = true;
173 }
174 
175 bool TRAC_IK::unique_solution(const KDL::JntArray& sol)
176 {
177 
178  for (uint i = 0; i < solutions.size(); i++)
179  if (myEqual(sol, solutions[i]))
180  return false;
181  return true;
182 
183 }
184 
185 inline void normalizeAngle(double& val, const double& min, const double& max)
186 {
187  if (val > max)
188  {
189  //Find actual angle offset
190  double diffangle = fmod(val - max, 2 * M_PI);
191  // Add that to upper bound and go back a full rotation
192  val = max + diffangle - 2 * M_PI;
193  }
194 
195  if (val < min)
196  {
197  //Find actual angle offset
198  double diffangle = fmod(min - val, 2 * M_PI);
199  // Add that to upper bound and go back a full rotation
200  val = min - diffangle + 2 * M_PI;
201  }
202 }
203 
204 inline void normalizeAngle(double& val, const double& target)
205 {
206  if (val > target + M_PI)
207  {
208  //Find actual angle offset
209  double diffangle = fmod(val - target, 2 * M_PI);
210  // Add that to upper bound and go back a full rotation
211  val = target + diffangle - 2 * M_PI;
212  }
213 
214  if (val < target - M_PI)
215  {
216  //Find actual angle offset
217  double diffangle = fmod(target - val, 2 * M_PI);
218  // Add that to upper bound and go back a full rotation
219  val = target - diffangle + 2 * M_PI;
220  }
221 }
222 
223 
224 template<typename T1, typename T2>
225 bool TRAC_IK::runSolver(T1& solver, T2& other_solver,
226  const KDL::JntArray &q_init,
227  const KDL::Frame &p_in)
228 {
229  KDL::JntArray q_out;
230 
231  double fulltime = maxtime;
232  KDL::JntArray seed = q_init;
233 
234  boost::posix_time::time_duration timediff;
235  double time_left;
236 
237  while (true)
238  {
239  timediff = boost::posix_time::microsec_clock::local_time() - start_time;
240  time_left = fulltime - timediff.total_nanoseconds() / 1000000000.0;
241 
242  if (time_left <= 0)
243  break;
244 
245  solver.setMaxtime(time_left);
246 
247  int RC = solver.CartToJnt(seed, p_in, q_out, bounds);
248  if (RC >= 0)
249  {
250  switch (solvetype)
251  {
252  case Manip1:
253  case Manip2:
254  normalize_limits(q_init, q_out);
255  break;
256  default:
257  normalize_seed(q_init, q_out);
258  break;
259  }
260  mtx_.lock();
261  if (unique_solution(q_out))
262  {
263  solutions.push_back(q_out);
264  uint curr_size = solutions.size();
265  errors.resize(curr_size);
266  mtx_.unlock();
267  double err, penalty;
268  switch (solvetype)
269  {
270  case Manip1:
271  penalty = manipPenalty(q_out);
272  err = penalty * TRAC_IK::ManipValue1(q_out);
273  break;
274  case Manip2:
275  penalty = manipPenalty(q_out);
276  err = penalty * TRAC_IK::ManipValue2(q_out);
277  break;
278  default:
279  err = TRAC_IK::JointErr(q_init, q_out);
280  break;
281  }
282  mtx_.lock();
283  errors[curr_size - 1] = std::make_pair(err, curr_size - 1);
284  }
285  mtx_.unlock();
286  }
287 
288  if (!solutions.empty() && solvetype == Speed)
289  break;
290 
291  for (unsigned int j = 0; j < seed.data.size(); j++)
292  if (types[j] == KDL::BasicJointType::Continuous)
293  seed(j) = fRand(q_init(j) - 2 * M_PI, q_init(j) + 2 * M_PI);
294  else
295  seed(j) = fRand(lb(j), ub(j));
296  }
297  other_solver.abort();
298 
299  solver.setMaxtime(fulltime);
300 
301  return true;
302 }
303 
304 
305 void TRAC_IK::normalize_seed(const KDL::JntArray& seed, KDL::JntArray& solution)
306 {
307  // Make sure rotational joint values are within 1 revolution of seed; then
308  // ensure joint limits are met.
309 
310  bool improved = false;
311 
312  for (uint i = 0; i < lb.data.size(); i++)
313  {
314 
315  if (types[i] == KDL::BasicJointType::TransJoint)
316  continue;
317 
318  double target = seed(i);
319  double val = solution(i);
320 
321  normalizeAngle(val, target);
322 
323  if (types[i] == KDL::BasicJointType::Continuous)
324  {
325  solution(i) = val;
326  continue;
327  }
328 
329  normalizeAngle(val, lb(i), ub(i));
330 
331  solution(i) = val;
332  }
333 }
334 
335 void TRAC_IK::normalize_limits(const KDL::JntArray& seed, KDL::JntArray& solution)
336 {
337  // Make sure rotational joint values are within 1 revolution of middle of
338  // limits; then ensure joint limits are met.
339 
340  bool improved = false;
341 
342  for (uint i = 0; i < lb.data.size(); i++)
343  {
344 
345  if (types[i] == KDL::BasicJointType::TransJoint)
346  continue;
347 
348  double target = seed(i);
349 
350  if (types[i] == KDL::BasicJointType::RotJoint && types[i] != KDL::BasicJointType::Continuous)
351  target = (ub(i) + lb(i)) / 2.0;
352 
353  double val = solution(i);
354 
355  normalizeAngle(val, target);
356 
357  if (types[i] == KDL::BasicJointType::Continuous)
358  {
359  solution(i) = val;
360  continue;
361  }
362 
363  normalizeAngle(val, lb(i), ub(i));
364 
365  solution(i) = val;
366  }
367 
368 }
369 
370 
371 double TRAC_IK::manipPenalty(const KDL::JntArray& arr)
372 {
373  double penalty = 1.0;
374  for (uint i = 0; i < arr.data.size(); i++)
375  {
376  if (types[i] == KDL::BasicJointType::Continuous)
377  continue;
378  double range = ub(i) - lb(i);
379  penalty *= ((arr(i) - lb(i)) * (ub(i) - arr(i)) / (range * range));
380  }
381  return std::max(0.0, 1.0 - exp(-1 * penalty));
382 }
383 
384 
385 double TRAC_IK::ManipValue1(const KDL::JntArray& arr)
386 {
387  KDL::Jacobian jac(arr.data.size());
388 
389  jacsolver->JntToJac(arr, jac);
390 
391  Eigen::JacobiSVD<Eigen::MatrixXd> svdsolver(jac.data);
392  Eigen::MatrixXd singular_values = svdsolver.singularValues();
393 
394  double error = 1.0;
395  for (unsigned int i = 0; i < singular_values.rows(); ++i)
396  error *= singular_values(i, 0);
397  return error;
398 }
399 
400 double TRAC_IK::ManipValue2(const KDL::JntArray& arr)
401 {
402  KDL::Jacobian jac(arr.data.size());
403 
404  jacsolver->JntToJac(arr, jac);
405 
406  Eigen::JacobiSVD<Eigen::MatrixXd> svdsolver(jac.data);
407  Eigen::MatrixXd singular_values = svdsolver.singularValues();
408 
409  return singular_values.minCoeff() / singular_values.maxCoeff();
410 }
411 
412 
413 int TRAC_IK::CartToJnt(const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out, const KDL::Twist& _bounds)
414 {
415 
416  if (!initialized)
417  {
418  ROS_ERROR("TRAC-IK was not properly initialized with a valid chain or limits. IK cannot proceed");
419  return -1;
420  }
421 
422 
423  start_time = boost::posix_time::microsec_clock::local_time();
424 
425  nl_solver->reset();
426  iksolver->reset();
427 
428  solutions.clear();
429  errors.clear();
430 
431  bounds = _bounds;
432 
433  task1 = std::thread(&TRAC_IK::runKDL, this, q_init, p_in);
434  task2 = std::thread(&TRAC_IK::runNLOPT, this, q_init, p_in);
435 
436  task1.join();
437  task2.join();
438 
439  if (solutions.empty())
440  {
441  q_out = q_init;
442  return -3;
443  }
444 
445  switch (solvetype)
446  {
447  case Manip1:
448  case Manip2:
449  std::sort(errors.rbegin(), errors.rend()); // rbegin/rend to sort by max
450  break;
451  default:
452  std::sort(errors.begin(), errors.end());
453  break;
454  }
455 
456  q_out = solutions[errors[0].second];
457 
458  return solutions.size();
459 }
460 
461 
462 TRAC_IK::~TRAC_IK()
463 {
464  if (task1.joinable())
465  task1.join();
466  if (task2.joinable())
467  task2.join();
468 }
469 }
#define ROS_FATAL(...)
#define ROS_DEBUG_STREAM_NAMED(name, args)
URDF_EXPORT bool initString(const std::string &xmlstring)
KDL_PARSER_PUBLIC bool treeFromUrdfModel(const urdf::ModelInterface &robot_model, KDL::Tree &tree)
ROSCONSOLE_DECL void initialize()
#define M_PI
Definition: math3d.h:42
std::string getName(void *handle)
#define ROS_DEBUG_NAMED(name,...)
bool searchParam(const std::string &key, std::string &result) const
bool param(const std::string &param_name, T &param_val, const T &default_val) const
Eigen::VectorXd data
bool getChain(const std::string &chain_root, const std::string &chain_tip, Chain &chain) const
bool getParam(const std::string &key, std::string &s) const
#define ROS_FATAL_NAMED(name,...)
#define ROS_ERROR(...)
void normalizeAngle(double &val, const double &min, const double &max)
Definition: trac_ik.cpp:185
dual_quaternion exp(dual_quaternion a)


trac_ik_lib
Author(s): Patrick Beeson, Barrett Ames
autogenerated on Tue Apr 23 2019 02:39:13