KDL  1.3.0
chainiksolverpos_nr_jl.hpp
Go to the documentation of this file.
1 // Copyright (C) 2007-2008 Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
2 // Copyright (C) 2008 Mikael Mayer
3 // Copyright (C) 2008 Julia Jesse
4 
5 // Version: 1.0
6 // Author: Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
7 // Maintainer: Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
8 // URL: http://www.orocos.org/kdl
9 
10 // This library is free software; you can redistribute it and/or
11 // modify it under the terms of the GNU Lesser General Public
12 // License as published by the Free Software Foundation; either
13 // version 2.1 of the License, or (at your option) any later version.
14 
15 // This library is distributed in the hope that it will be useful,
16 // but WITHOUT ANY WARRANTY; without even the implied warranty of
17 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
18 // Lesser General Public License for more details.
19 
20 // You should have received a copy of the GNU Lesser General Public
21 // License along with this library; if not, write to the Free Software
22 // Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
23 
24 #ifndef KDLCHAINIKSOLVERPOS_NR_JL_HPP
25 #define KDLCHAINIKSOLVERPOS_NR_JL_HPP
26 
27 #include "chainiksolver.hpp"
28 #include "chainfksolver.hpp"
29 
30 namespace KDL {
31 
41  {
42  public:
60  ChainIkSolverPos_NR_JL(const Chain& chain,const JntArray& q_min, const JntArray& q_max, ChainFkSolverPos& fksolver,ChainIkSolverVel& iksolver,unsigned int maxiter=100,double eps=1e-6);
62 
63  virtual int CartToJnt(const JntArray& q_init, const Frame& p_in, JntArray& q_out);
64 
65  private:
66  const Chain chain;
67  JntArray q_min;
68  JntArray q_max;
71  JntArray delta_q;
72  unsigned int maxiter;
73  double eps;
74 
77 
78  };
79 
80 }
81 
82 #endif
This abstract class encapsulates the inverse position solver for a KDL::Chain.
Definition: chainiksolver.hpp:42
Twist delta_twist
Definition: chainiksolverpos_nr_jl.hpp:76
This class encapsulates a serial kinematic interconnection structure.
Definition: chain.hpp:35
ChainIkSolverPos_NR_JL(const Chain &chain, const JntArray &q_min, const JntArray &q_max, ChainFkSolverPos &fksolver, ChainIkSolverVel &iksolver, unsigned int maxiter=100, double eps=1e-6)
Constructor of the solver, it needs the chain, a forward position kinematics solver and an inverse ve...
Definition: chainiksolverpos_nr_jl.cpp:28
Frame f
Definition: chainiksolverpos_nr_jl.hpp:75
represents both translational and rotational velocities.
Definition: frames.hpp:720
JntArray q_min
Definition: chainiksolverpos_nr_jl.hpp:67
Definition: articulatedbodyinertia.cpp:28
JntArray delta_q
Definition: chainiksolverpos_nr_jl.hpp:71
Implementation of a general inverse position kinematics algorithm based on Newton-Raphson iterations ...
Definition: chainiksolverpos_nr_jl.hpp:40
ChainIkSolverVel & iksolver
Definition: chainiksolverpos_nr_jl.hpp:69
unsigned int maxiter
Definition: chainiksolverpos_nr_jl.hpp:72
double eps
Definition: chainiksolverpos_nr_jl.hpp:73
represents a frame transformation in 3D space (rotation + translation)
Definition: frames.hpp:570
~ChainIkSolverPos_NR_JL()
Definition: chainiksolverpos_nr_jl.cpp:69
const Chain chain
Definition: chainiksolverpos_nr_jl.hpp:66
ChainFkSolverPos & fksolver
Definition: chainiksolverpos_nr_jl.hpp:70
JntArray q_max
Definition: chainiksolverpos_nr_jl.hpp:68
virtual int CartToJnt(const JntArray &q_init, const Frame &p_in, JntArray &q_out)
Calculate inverse position kinematics, from cartesian coordinates to joint coordinates.
Definition: chainiksolverpos_nr_jl.cpp:36
This abstract class encapsulates the inverse velocity solver for a KDL::Chain.
Definition: chainiksolver.hpp:65
This abstract class encapsulates a solver for the forward position kinematics for a KDL::Chain...
Definition: chainfksolver.hpp:43