Merge of itasc branch. Project files, scons and cmake should be working. Makefile...
[blender.git] / intern / itasc / kdl / chainfksolver.hpp
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_FKSOLVER_HPP
23 #define KDL_CHAIN_FKSOLVER_HPP
24
25 #include "chain.hpp"
26 #include "framevel.hpp"
27 #include "frameacc.hpp"
28 #include "jntarray.hpp"
29 #include "jntarrayvel.hpp"
30 #include "jntarrayacc.hpp"
31
32 namespace KDL {
33
34     /**
35           * \brief This <strong>abstract</strong> class encapsulates a
36           * solver for the forward position kinematics for a KDL::Chain.
37      *
38      * @ingroup KinematicFamily
39      */
40
41     //Forward definition
42     class ChainFkSolverPos {
43     public:
44         /**
45          * Calculate forward position kinematics for a KDL::Chain,
46          * from joint coordinates to cartesian pose.
47          *
48          * @param q_in input joint coordinates
49          * @param p_out reference to output cartesian pose
50          *
51          * @return if < 0 something went wrong
52          */
53         virtual int JntToCart(const JntArray& q_in, Frame& p_out,int segmentNr=-1)=0;
54         virtual ~ChainFkSolverPos(){};
55     };
56
57     /**
58      * \brief This <strong>abstract</strong> class encapsulates a solver
59      * for the forward velocity kinematics for a KDL::Chain.
60      *
61      * @ingroup KinematicFamily
62      */
63     class ChainFkSolverVel {
64     public:
65         /**
66          * Calculate forward position and velocity kinematics, from
67          * joint coordinates to cartesian coordinates.
68          *
69          * @param q_in input joint coordinates (position and velocity)
70          * @param out output cartesian coordinates (position and velocity)
71          *
72          * @return if < 0 something went wrong
73          */
74         virtual int JntToCart(const JntArrayVel& q_in, FrameVel& out,int segmentNr=-1)=0;
75
76         virtual ~ChainFkSolverVel(){};
77     };
78
79     /**
80      * \brief This <strong>abstract</strong> class encapsulates a solver
81      * for the forward acceleration kinematics for a KDL::Chain.
82      *
83      * @ingroup KinematicFamily
84      */
85
86     class ChainFkSolverAcc {
87     public:
88         /**
89          * Calculate forward position, velocity and accelaration
90          * kinematics, from joint coordinates to cartesian coordinates
91          *
92          * @param q_in input joint coordinates (position, velocity and
93          * acceleration
94          @param out output cartesian coordinates (position, velocity
95          * and acceleration
96          *
97          * @return if < 0 something went wrong
98          */
99     virtual int JntToCart(const JntArrayAcc& q_in, FrameAcc& out,int segmentNr=-1)=0;
100
101         virtual ~ChainFkSolverAcc()=0;
102     };
103
104
105 }//end of namespace KDL
106
107 #endif