orocos_kdl
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  virtual void updateInternalDataStructures()=0;
58  };
59 
66  class ChainIkSolverVel : public KDL::SolverI {
67  public:
78  virtual int CartToJnt(const JntArray& q_in, const Twist& v_in, JntArray& qdot_out)=0;
89  virtual int CartToJnt(const JntArray& q_init, const FrameVel& v_in, JntArrayVel& q_out)=0;
90 
91  virtual ~ChainIkSolverVel(){};
92  virtual void updateInternalDataStructures()=0;
93  };
94 
103  public:
115  virtual int CartToJnt(const JntArray& q_in, const JntArray& qdot_in, const Twist a_in,
116  JntArray& qdotdot_out)=0;
127  virtual int CartTojnt(const JntArray& q_init, const FrameAcc& a_in,
128  JntArrayAcc& q_out)=0;
129 
143  virtual int CartToJnt(const JntArray& q_in, const Twist& v_in, const Twist& a_in,
144  JntArray& qdot_out, JntArray& qdotdot_out)=0;
159  virtual int CartTojnt(const JntArray& q_init, const Frame& p_in, const JntArray& qdot_in, const Twist& a_in,
160  JntArray& q_out, JntArray& qdotdot_out)=0;
161 
162  virtual void updateInternalDataStructures()=0;
163  virtual ~ChainIkSolverAcc(){};
164  };
165 
166 
167 }//end of namespace KDL
168 
169 #endif
chain.hpp
frames.hpp
KDL::JntArray
Definition: jntarray.hpp:69
KDL::ChainIkSolverVel::~ChainIkSolverVel
virtual ~ChainIkSolverVel()
Definition: chainiksolver.hpp:91
jntarray.hpp
jntarrayacc.hpp
KDL::FrameAcc
Definition: frameacc.hpp:188
KDL::ChainIkSolverAcc::CartTojnt
virtual int CartTojnt(const JntArray &q_init, const FrameAcc &a_in, JntArrayAcc &q_out)=0
KDL::ChainIkSolverPos::CartToJnt
virtual int CartToJnt(const JntArray &q_init, const Frame &p_in, JntArray &q_out)=0
jntarrayvel.hpp
KDL
Definition: kukaLWR_DHnew.cpp:25
KDL::ChainIkSolverAcc::~ChainIkSolverAcc
virtual ~ChainIkSolverAcc()
Definition: chainiksolver.hpp:163
KDL::Twist
represents both translational and rotational velocities.
Definition: frames.hpp:723
KDL::ChainIkSolverVel::CartToJnt
virtual int CartToJnt(const JntArray &q_in, const Twist &v_in, JntArray &qdot_out)=0
framevel.hpp
KDL::Frame
represents a frame transformation in 3D space (rotation + translation)
Definition: frames.hpp:572
KDL::ChainIkSolverAcc::CartToJnt
virtual int CartToJnt(const JntArray &q_in, const JntArray &qdot_in, const Twist a_in, JntArray &qdotdot_out)=0
solveri.hpp
KDL::ChainIkSolverPos::updateInternalDataStructures
virtual void updateInternalDataStructures()=0
KDL::ChainIkSolverVel::updateInternalDataStructures
virtual void updateInternalDataStructures()=0
KDL::ChainIkSolverAcc
This abstract class encapsulates the inverse acceleration solver for a KDL::Chain.
Definition: chainiksolver.hpp:102
KDL::ChainIkSolverAcc::updateInternalDataStructures
virtual void updateInternalDataStructures()=0
KDL::ChainIkSolverPos::~ChainIkSolverPos
virtual ~ChainIkSolverPos()
Definition: chainiksolver.hpp:56
KDL::JntArrayVel
Definition: jntarrayvel.hpp:45
KDL::SolverI
Definition: solveri.hpp:84
KDL::FrameVel
Definition: framevel.hpp:209
KDL::ChainIkSolverVel
This abstract class encapsulates the inverse velocity solver for a KDL::Chain.
Definition: chainiksolver.hpp:66
frameacc.hpp
KDL::ChainIkSolverPos
This abstract class encapsulates the inverse position solver for a KDL::Chain.
Definition: chainiksolver.hpp:42
KDL::JntArrayAcc
Definition: jntarrayacc.hpp:49