blob: 72cdab0b28ba2473353016170e9f2f81be04f349 (
plain)
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
|
// Copyright (C) 2007 Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
// Version: 1.0
// Author: Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
// Maintainer: Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
// URL: http://www.orocos.org/kdl
// This library is free software; you can redistribute it and/or
// modify it under the terms of the GNU Lesser General Public
// License as published by the Free Software Foundation; either
// version 2.1 of the License, or (at your option) any later version.
// This library is distributed in the hope that it will be useful,
// but WITHOUT ANY WARRANTY; without even the implied warranty of
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
// Lesser General Public License for more details.
// You should have received a copy of the GNU Lesser General Public
// License along with this library; if not, write to the Free Software
// Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
#ifndef KDLCHAINFKSOLVERPOS_RECURSIVE_HPP
#define KDLCHAINFKSOLVERPOS_RECURSIVE_HPP
#include "chainfksolver.hpp"
namespace KDL {
/**
* Implementation of a recursive forward position kinematics
* algorithm to calculate the position transformation from joint
* space to Cartesian space of a general kinematic chain (KDL::Chain).
*
* @ingroup KinematicFamily
*/
class ChainFkSolverPos_recursive : public ChainFkSolverPos
{
public:
ChainFkSolverPos_recursive(const Chain& chain);
~ChainFkSolverPos_recursive();
virtual int JntToCart(const JntArray& q_in, Frame& p_out, int segmentNr=-1);
private:
const Chain chain;
};
}
#endif
|