kdl_tl.hpp
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 #ifndef KDLCHAINIKSOLVERPOS_TL_HPP
33 #define KDLCHAINIKSOLVERPOS_TL_HPP
34 
35 #include <kdl/chainfksolverpos_recursive.hpp>
36 #include <kdl/chainiksolvervel_pinv.hpp>
37 
38 namespace TRAC_IK
39 {
40 class TRAC_IK;
41 }
42 
43 namespace KDL
44 {
45 
47 
49 {
50  friend class TRAC_IK::TRAC_IK;
51 
52 public:
53  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);
54 
56 
57  int CartToJnt(const KDL::JntArray& q_init, const KDL::Frame& p_in, KDL::JntArray& q_out, const KDL::Twist bounds = KDL::Twist::Zero());
58 
59  inline void setMaxtime(double t)
60  {
61  maxtime = t;
62  }
63 
64 private:
65  const Chain chain;
66  JntArray q_min;
67  JntArray q_max;
68 
69  KDL::Twist bounds;
70 
71  KDL::ChainIkSolverVel_pinv vik_solver;
72  KDL::ChainFkSolverPos_recursive fksolver;
73  JntArray delta_q;
74  double maxtime;
75 
76  double eps;
77 
78  bool rr;
79  bool wrap;
80 
81  std::vector<KDL::BasicJointType> types;
82 
83  inline void abort()
84  {
85  aborted = true;
86  }
87 
88  inline void reset()
89  {
90  aborted = false;
91  }
92 
93  bool aborted;
94 
95  Frame f;
96  Twist delta_twist;
97 
98  inline static double fRand(double min, double max)
99  {
100  double f = (double)rand() / RAND_MAX;
101  return min + f * (max - min);
102  }
103 
104 
105 };
106 
118 IMETHOD Twist diffRelative(const Frame & F_a_b1, const Frame & F_a_b2, double dt = 1)
119 {
120  return Twist(F_a_b1.M.Inverse() * diff(F_a_b1.p, F_a_b2.p, dt),
121  F_a_b1.M.Inverse() * diff(F_a_b1.M, F_a_b2.M, dt));
122 }
123 
124 }
125 
126 #endif
KDL::ChainIkSolverPos_TL::rr
bool rr
Definition: kdl_tl.hpp:78
KDL::ChainIkSolverPos_TL::setMaxtime
void setMaxtime(double t)
Definition: kdl_tl.hpp:59
KDL::ChainIkSolverPos_TL::wrap
bool wrap
Definition: kdl_tl.hpp:79
KDL::ChainIkSolverPos_TL::vik_solver
KDL::ChainIkSolverVel_pinv vik_solver
Definition: kdl_tl.hpp:71
KDL::ChainIkSolverPos_TL::q_min
JntArray q_min
Definition: kdl_tl.hpp:66
KDL::BasicJointType
BasicJointType
Definition: kdl_tl.hpp:46
KDL
Definition: kdl_tl.hpp:43
KDL::ChainIkSolverPos_TL::abort
void abort()
Definition: kdl_tl.hpp:83
KDL::RotJoint
@ RotJoint
Definition: kdl_tl.hpp:46
KDL::ChainIkSolverPos_TL::bounds
KDL::Twist bounds
Definition: kdl_tl.hpp:69
KDL::ChainIkSolverPos_TL::fksolver
KDL::ChainFkSolverPos_recursive fksolver
Definition: kdl_tl.hpp:72
TRAC_IK::TRAC_IK
Definition: trac_ik.hpp:75
KDL::ChainIkSolverPos_TL::eps
double eps
Definition: kdl_tl.hpp:76
KDL::ChainIkSolverPos_TL::types
std::vector< KDL::BasicJointType > types
Definition: kdl_tl.hpp:81
KDL::ChainIkSolverPos_TL::aborted
bool aborted
Definition: kdl_tl.hpp:93
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::ChainIkSolverPos_TL::reset
void reset()
Definition: kdl_tl.hpp:88
KDL::ChainIkSolverPos_TL::delta_q
JntArray delta_q
Definition: kdl_tl.hpp:73
KDL::diffRelative
IMETHOD Twist diffRelative(const Frame &F_a_b1, const Frame &F_a_b2, double dt=1)
Definition: kdl_tl.hpp:118
KDL::ChainIkSolverPos_TL::CartToJnt
int CartToJnt(const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out, const KDL::Twist bounds=KDL::Twist::Zero())
Definition: kdl_tl.cpp:96
KDL::ChainIkSolverPos_TL::q_max
JntArray q_max
Definition: kdl_tl.hpp:67
KDL::ChainIkSolverPos_TL
Definition: kdl_tl.hpp:48
KDL::ChainIkSolverPos_TL::~ChainIkSolverPos_TL
~ChainIkSolverPos_TL()
Definition: kdl_tl.cpp:224
KDL::ChainIkSolverPos_TL::chain
const Chain chain
Definition: kdl_tl.hpp:65
KDL::ChainIkSolverPos_TL::fRand
static double fRand(double min, double max)
Definition: kdl_tl.hpp:98
KDL::ChainIkSolverPos_TL::maxtime
double maxtime
Definition: kdl_tl.hpp:74
TRAC_IK
Definition: kdl_tl.hpp:38
KDL::TransJoint
@ TransJoint
Definition: kdl_tl.hpp:46
KDL::Continuous
@ Continuous
Definition: kdl_tl.hpp:46
KDL::ChainIkSolverPos_TL::delta_twist
Twist delta_twist
Definition: kdl_tl.hpp:96
KDL::ChainIkSolverPos_TL::f
Frame f
Definition: kdl_tl.hpp:95


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