KDL  1.3.0
chainiksolver.hpp
Go to the documentation of this file.
1 // Copyright (C) 2007 Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
2 
3 // Version: 1.0
4 // Author: Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
5 // Maintainer: Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
6 // URL: http://www.orocos.org/kdl
7 
8 // This library is free software; you can redistribute it and/or
9 // modify it under the terms of the GNU Lesser General Public
10 // License as published by the Free Software Foundation; either
11 // version 2.1 of the License, or (at your option) any later version.
12 
13 // This library is distributed in the hope that it will be useful,
14 // but WITHOUT ANY WARRANTY; without even the implied warranty of
15 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
16 // Lesser General Public License for more details.
17 
18 // You should have received a copy of the GNU Lesser General Public
19 // License along with this library; if not, write to the Free Software
20 // Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
21 
22 #ifndef KDL_CHAIN_IKSOLVER_HPP
23 #define KDL_CHAIN_IKSOLVER_HPP
24 
25 #include "chain.hpp"
26 #include "frames.hpp"
27 #include "framevel.hpp"
28 #include "frameacc.hpp"
29 #include "jntarray.hpp"
30 #include "jntarrayvel.hpp"
31 #include "jntarrayacc.hpp"
32 #include "solveri.hpp"
33 
34 namespace KDL {
35 
42  class ChainIkSolverPos : public KDL::SolverI {
43  public:
54  virtual int CartToJnt(const JntArray& q_init, const Frame& p_in, JntArray& q_out)=0;
55 
56  virtual ~ChainIkSolverPos(){};
57  };
58 
65  class ChainIkSolverVel : public KDL::SolverI {
66  public:
77  virtual int CartToJnt(const JntArray& q_in, const Twist& v_in, JntArray& qdot_out)=0;
88  virtual int CartToJnt(const JntArray& q_init, const FrameVel& v_in, JntArrayVel& q_out)=0;
89 
90  virtual ~ChainIkSolverVel(){};
91 
92  };
93 
102  public:
114  virtual int CartToJnt(const JntArray& q_in, const JntArray& qdot_in, const Twist a_in,
115  JntArray& qdotdot_out)=0;
126  virtual int CartTojnt(const JntArray& q_init, const FrameAcc& a_in,
127  JntArrayAcc& q_out)=0;
128 
142  virtual int CartToJnt(const JntArray& q_in, const Twist& v_in, const Twist& a_in,
143  JntArray& qdot_out, JntArray& qdotdot_out)=0;
158  virtual int CartTojnt(const JntArray& q_init, const Frame& p_in, const JntArray& qdot_in, const Twist& a_in,
159  JntArray& q_out, JntArray& qdotdot_out)=0;
160 
161  virtual ~ChainIkSolverAcc(){};
162  };
163 
164 
165 }//end of namespace KDL
166 
167 #endif
This abstract class encapsulates the inverse position solver for a KDL::Chain.
Definition: chainiksolver.hpp:42
virtual int CartToJnt(const JntArray &q_init, const Frame &p_in, JntArray &q_out)=0
Calculate inverse position kinematics, from cartesian coordinates to joint coordinates.
This class represents an fixed size array containing joint values of a KDL::Chain.
Definition: jntarray.hpp:69
Solver interface supporting storage and description of the latest error.
Definition: solveri.hpp:84
virtual ~ChainIkSolverAcc()
Definition: chainiksolver.hpp:161
virtual int CartToJnt(const JntArray &q_in, const Twist &v_in, JntArray &qdot_out)=0
Calculate inverse velocity kinematics, from joint positions and cartesian velocity to joint velocitie...
Definition: frameacc.hpp:165
represents both translational and rotational velocities.
Definition: frames.hpp:720
virtual int CartTojnt(const JntArray &q_init, const FrameAcc &a_in, JntArrayAcc &q_out)=0
Calculate inverse position, velocity and acceration kinematics from cartesian coordinates to joint co...
virtual int CartToJnt(const JntArray &q_in, const JntArray &qdot_in, const Twist a_in, JntArray &qdotdot_out)=0
Calculate inverse acceleration kinematics from joint positions, joint velocities and cartesian accele...
Definition: articulatedbodyinertia.cpp:28
Definition: jntarrayvel.hpp:45
virtual ~ChainIkSolverPos()
Definition: chainiksolver.hpp:56
represents a frame transformation in 3D space (rotation + translation)
Definition: frames.hpp:570
This abstract class encapsulates the inverse acceleration solver for a KDL::Chain.
Definition: chainiksolver.hpp:101
Definition: framevel.hpp:197
Definition: jntarrayacc.hpp:49
virtual ~ChainIkSolverVel()
Definition: chainiksolver.hpp:90
This abstract class encapsulates the inverse velocity solver for a KDL::Chain.
Definition: chainiksolver.hpp:65