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:
43 
44  static const int E_IKSOLVERVEL_FAILED = -100;
45  static const int E_FKSOLVERPOS_FAILED = -101;
46 
65 
82 
84 
85 
95  virtual int CartToJnt(const JntArray& q_init, const Frame& p_in, JntArray& q_out);
96 
103  int setJointLimits(const JntArray& q_min, const JntArray& q_max);
104 
106  virtual void updateInternalDataStructures();
107 
109  const char* strError(const int error) const;
110 
111  private:
112  const Chain& chain;
113  unsigned int nj;
119  unsigned int maxiter;
120  double eps;
121 
124 
125  };
126 
127 }
128 
129 #endif
This abstract class encapsulates the inverse position solver for a KDL::Chain.
int setJointLimits(const JntArray &q_min, const JntArray &q_max)
This class encapsulates a serial kinematic interconnection structure. It is built out of segments...
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)
Child FK solver failed.
This class represents an fixed size array containing joint values of a KDL::Chain.
Definition: jntarray.hpp:69
represents both translational and rotational velocities.
Definition: frames.hpp:720
static const int E_FKSOLVERPOS_FAILED
Child IK solver vel failed.
const char * strError(const int error) const
represents a frame transformation in 3D space (rotation + translation)
Definition: frames.hpp:570
int error
Latest error, initialized to E_NOERROR in constructor.
Definition: solveri.hpp:149
virtual int CartToJnt(const JntArray &q_init, const Frame &p_in, JntArray &q_out)
This abstract class encapsulates the inverse velocity solver for a KDL::Chain.
This abstract class encapsulates a solver for the forward position kinematics for a KDL::Chain...


orocos_kdl
Author(s):
autogenerated on Sat Jun 15 2019 19:07:36