chainiksolverpos_nr_jl_coupling.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 // Modified by Juan A. Corrales (ISIR, UPMC) in order to include coupling
11 
12 // This library is free software; you can redistribute it and/or
13 // modify it under the terms of the GNU Lesser General Public
14 // License as published by the Free Software Foundation; either
15 // version 2.1 of the License, or (at your option) any later version.
16 
17 // This library is distributed in the hope that it will be useful,
18 // but WITHOUT ANY WARRANTY; without even the implied warranty of
19 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
20 // Lesser General Public License for more details.
21 
22 // You should have received a copy of the GNU Lesser General Public
23 // License along with this library; if not, write to the Free Software
24 // Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
25 
26 #ifndef KDLChainIkSolverPos_NR_JL_COUPLING_HPP
27 #define KDLChainIkSolverPos_NR_JL_COUPLING_HPP
28 
29 #include <kdl/chainiksolver.hpp>
30 #include <kdl/chainfksolver.hpp>
32 
33 namespace KDL
34 {
35 /*
36 * Implementation of a general inverse position kinematics
37 * algorithm based on Newton-Raphson iterations to calculate the
38 * position transformation from Cartesian to joint space of a general
39 * KDL::Chain. Takes joint limits into account.
40 *
41 * @ingroup KinematicFamily
42 */
44  public ChainIkSolverPos
45 {
46 public:
47  /*
48  * Constructor of the solver, it needs the chain, a forward
49  * position kinematics solver and an inverse velocity
50  * kinematics solver for that chain.
51  *
52  * @param chain the chain to calculate the inverse position for
53  * @param q_max the maximum joint positions
54  * @param q_min the minimum joint positions
55  * @param fksolver a forward position kinematics solver
56  * @param iksolver an inverse velocity kinematics solver
57  * @param maxiter the maximum Newton-Raphson iterations,
58  * default: 100
59  * @param eps the precision for the position, used to end the
60  * iterations, default: epsilon (defined in kdl.hpp)
61  *
62  * @return
63  */
66  double eps = 1e-6);
67 
69 
70  virtual int CartToJnt(const JntArray &q_init, const Frame &p_in, JntArray &q_out);
71 
72 private:
81 
82  unsigned int maxiter;
83  double eps;
84 };
85 } // namespace KDL
86 
87 #endif
ChainIkSolverPos_NR_JL_coupling(const Chain_coupling &chain, const JntArray &q_min, const JntArray &q_max, ChainFkSolverPos &fksolver, ChainIkSolverVel &iksolver, unsigned int maxiter=100, double eps=1e-6)
virtual int CartToJnt(const JntArray &q_init, const Frame &p_in, JntArray &q_out)


kdl_coupling
Author(s): Juan Antonio Corrales Ramon (UPMC)
autogenerated on Wed Oct 14 2020 04:05:04