Main Page
Namespaces
Classes
Files
File List
include
kdl_coupling
chainjnttojacsolver_coupling.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
// Modified by Juan A. Corrales (ISIR, UPMC) in order to include coupling
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 KDL_CHAINJNTTOJACSOLVER_COUPLING_HPP
25
#define KDL_CHAINJNTTOJACSOLVER_COUPLING_HPP
26
27
#include <kdl/frames.hpp>
28
#include <kdl/jacobian.hpp>
29
#include <kdl/jntarray.hpp>
30
#include <
kdl_coupling/chain_coupling.hpp
>
31
32
namespace
KDL
33
{
34
/*
35
* @brief Class to calculate the jacobian of a general
36
* KDL::Chain, it is used by other solvers. It should not be used
37
* outside of KDL.
38
*
39
*
40
*/
41
42
class
ChainJntToJacSolver_coupling
43
{
44
public
:
45
explicit
ChainJntToJacSolver_coupling
(
const
Chain_coupling
&
chain
);
46
47
~ChainJntToJacSolver_coupling
();
48
49
/*
50
* Calculate the jacobian expressed in the base frame of the
51
* chain, with reference point at the end effector of the
52
* *chain. The alghoritm is similar to the one used in
53
* KDL::ChainFkSolverVel_recursive
54
*
55
* @param q_in input joint positions
56
* @param jac output jacobian
57
*
58
* @return always returns 0
59
*/
60
int
JntToJac
(
const
JntArray
&q_in,
Jacobian
&jac);
61
62
private
:
63
const
Chain_coupling
chain
;
64
Twist
t_tmp
;
65
Frame
T_tmp
;
66
Jacobian
jac_tmp
;
67
};
68
}
// namespace KDL
69
70
#endif
71
KDL::Chain_coupling
Definition:
chain_coupling.hpp:42
KDL::Jacobian
KDL::ChainJntToJacSolver_coupling::T_tmp
Frame T_tmp
Definition:
chainjnttojacsolver_coupling.hpp:65
KDL::JntArray
KDL::ChainJntToJacSolver_coupling::t_tmp
Twist t_tmp
Definition:
chainjnttojacsolver_coupling.hpp:64
KDL::ChainJntToJacSolver_coupling::JntToJac
int JntToJac(const JntArray &q_in, Jacobian &jac)
Definition:
chainjnttojacsolver_coupling.cpp:37
chain_coupling.hpp
KDL::ChainJntToJacSolver_coupling::~ChainJntToJacSolver_coupling
~ChainJntToJacSolver_coupling()
Definition:
chainjnttojacsolver_coupling.cpp:33
KDL::Twist
KDL::ChainJntToJacSolver_coupling::chain
const Chain_coupling chain
Definition:
chainjnttojacsolver_coupling.hpp:63
KDL
KDL::ChainJntToJacSolver_coupling
Definition:
chainjnttojacsolver_coupling.hpp:42
KDL::Frame
KDL::ChainJntToJacSolver_coupling::jac_tmp
Jacobian jac_tmp
Definition:
chainjnttojacsolver_coupling.hpp:66
KDL::ChainJntToJacSolver_coupling::ChainJntToJacSolver_coupling
ChainJntToJacSolver_coupling(const Chain_coupling &chain)
Definition:
chainjnttojacsolver_coupling.cpp:28
kdl_coupling
Author(s): Juan Antonio Corrales Ramon (UPMC)
autogenerated on Wed Oct 14 2020 04:05:04