kdl_tl.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 #include <trac_ik/kdl_tl.hpp>
32 #include <boost/date_time.hpp>
33 #include <ros/ros.h>
34 #include <limits>
35 
36 namespace KDL
37 {
38 ChainIkSolverPos_TL::ChainIkSolverPos_TL(const Chain& _chain, const JntArray& _q_min, const JntArray& _q_max, double _maxtime, double _eps, bool _random_restart, bool _try_jl_wrap):
39  chain(_chain), q_min(_q_min), q_max(_q_max), vik_solver(chain), fksolver(chain), delta_q(chain.getNrOfJoints()),
40  maxtime(_maxtime), eps(_eps), rr(_random_restart), wrap(_try_jl_wrap)
41 {
42 
43  assert(chain.getNrOfJoints() == _q_min.data.size());
44  assert(chain.getNrOfJoints() == _q_max.data.size());
45 
46  reset();
47 
48  for (uint i = 0; i < chain.segments.size(); i++)
49  {
50  std::string type = chain.segments[i].getJoint().getTypeName();
51  if (type.find("Rot") != std::string::npos)
52  {
53  if (_q_max(types.size()) >= std::numeric_limits<float>::max() &&
54  _q_min(types.size()) <= std::numeric_limits<float>::lowest())
55  types.push_back(KDL::BasicJointType::Continuous);
56  else types.push_back(KDL::BasicJointType::RotJoint);
57  }
58  else if (type.find("Trans") != std::string::npos)
59  types.push_back(KDL::BasicJointType::TransJoint);
60 
61  }
62 
63  assert(types.size() == _q_max.data.size());
64 }
65 
66 
67 
68 int ChainIkSolverPos_TL::CartToJnt(const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out, const KDL::Twist _bounds)
69 {
70 
71  if (aborted)
72  return -3;
73 
74  boost::posix_time::ptime start_time = boost::posix_time::microsec_clock::local_time();
75  boost::posix_time::time_duration timediff;
76  q_out = q_init;
77  bounds = _bounds;
78 
79 
80  double time_left;
81 
82  do
83  {
84  fksolver.JntToCart(q_out, f);
85  delta_twist = diffRelative(p_in, f);
86 
87  if (std::abs(delta_twist.vel.x()) <= std::abs(bounds.vel.x()))
88  delta_twist.vel.x(0);
89 
90  if (std::abs(delta_twist.vel.y()) <= std::abs(bounds.vel.y()))
91  delta_twist.vel.y(0);
92 
93  if (std::abs(delta_twist.vel.z()) <= std::abs(bounds.vel.z()))
94  delta_twist.vel.z(0);
95 
96  if (std::abs(delta_twist.rot.x()) <= std::abs(bounds.rot.x()))
97  delta_twist.rot.x(0);
98 
99  if (std::abs(delta_twist.rot.y()) <= std::abs(bounds.rot.y()))
100  delta_twist.rot.y(0);
101 
102  if (std::abs(delta_twist.rot.z()) <= std::abs(bounds.rot.z()))
103  delta_twist.rot.z(0);
104 
105  if (Equal(delta_twist, Twist::Zero(), eps))
106  return 1;
107 
108  delta_twist = diff(f, p_in);
109 
110  vik_solver.CartToJnt(q_out, delta_twist, delta_q);
111  KDL::JntArray q_curr;
112 
113  Add(q_out, delta_q, q_curr);
114 
115  for (unsigned int j = 0; j < q_min.data.size(); j++)
116  {
117  if (types[j] == KDL::BasicJointType::Continuous)
118  continue;
119  if (q_curr(j) < q_min(j))
120  {
121  if (!wrap || types[j] == KDL::BasicJointType::TransJoint)
122  // KDL's default
123  q_curr(j) = q_min(j);
124  else
125  {
126  // Find actual wrapped angle between limit and joint
127  double diffangle = fmod(q_min(j) - q_curr(j), 2 * M_PI);
128  // Subtract that angle from limit and go into the range by a
129  // revolution
130  double curr_angle = q_min(j) - diffangle + 2 * M_PI;
131  if (curr_angle > q_max(j))
132  q_curr(j) = q_min(j);
133  else
134  q_curr(j) = curr_angle;
135  }
136  }
137  }
138 
139  for (unsigned int j = 0; j < q_max.data.size(); j++)
140  {
141  if (types[j] == KDL::BasicJointType::Continuous)
142  continue;
143 
144  if (q_curr(j) > q_max(j))
145  {
146  if (!wrap || types[j] == KDL::BasicJointType::TransJoint)
147  // KDL's default
148  q_curr(j) = q_max(j);
149  else
150  {
151  // Find actual wrapped angle between limit and joint
152  double diffangle = fmod(q_curr(j) - q_max(j), 2 * M_PI);
153  // Add that angle to limit and go into the range by a revolution
154  double curr_angle = q_max(j) + diffangle - 2 * M_PI;
155  if (curr_angle < q_min(j))
156  q_curr(j) = q_max(j);
157  else
158  q_curr(j) = curr_angle;
159  }
160  }
161  }
162 
163  Subtract(q_out, q_curr, q_out);
164 
165  if (q_out.data.isZero(boost::math::tools::epsilon<float>()))
166  {
167  if (rr)
168  {
169  for (unsigned int j = 0; j < q_out.data.size(); j++)
170  if (types[j] == KDL::BasicJointType::Continuous)
171  q_curr(j) = fRand(q_curr(j) - 2 * M_PI, q_curr(j) + 2 * M_PI);
172  else
173  q_curr(j) = fRand(q_min(j), q_max(j));
174  }
175 
176  // Below would be an optimization to the normal KDL, where when it
177  // gets stuck, it returns immediately. Don't use to compare KDL with
178  // random restarts or TRAC-IK to plain KDL.
179 
180  // else {
181  // q_out=q_curr;
182  // return -3;
183  // }
184  }
185 
186  q_out = q_curr;
187 
188  timediff = boost::posix_time::microsec_clock::local_time() - start_time;
189  time_left = maxtime - timediff.total_nanoseconds() / 1000000000.0;
190  }
191  while (time_left > 0 && !aborted);
192 
193  return -3;
194 }
195 
196 ChainIkSolverPos_TL::~ChainIkSolverPos_TL()
197 {
198 }
199 
200 
201 }
202 
M_PI
#define M_PI
Definition: math3d.h:42
ros.h
kdl_tl.hpp
KDL
Definition: kdl_tl.hpp:43
f
f
KDL::RotJoint
@ RotJoint
Definition: kdl_tl.hpp:46
KDL::ChainIkSolverPos_TL::ChainIkSolverPos_TL
ChainIkSolverPos_TL(const Chain &chain, const JntArray &q_min, const JntArray &q_max, double maxtime=0.005, double eps=1e-3, bool random_restart=false, bool try_jl_wrap=false)
Definition: kdl_tl.cpp:66
KDL::diffRelative
IMETHOD Twist diffRelative(const Frame &F_a_b1, const Frame &F_a_b2, double dt=1)
Definition: kdl_tl.hpp:118
KDL::TransJoint
@ TransJoint
Definition: kdl_tl.hpp:46
KDL::Continuous
@ Continuous
Definition: kdl_tl.hpp:46


trac_ik_lib
Author(s): Patrick Beeson, Barrett Ames
autogenerated on Thu May 22 2025 02:28:51