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>
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 
43 {
44 public:
46 
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:
67 };
68 } // namespace KDL
69 
70 #endif
71 
int JntToJac(const JntArray &q_in, Jacobian &jac)
ChainJntToJacSolver_coupling(const Chain_coupling &chain)


kdl_coupling
Author(s): Juan Antonio Corrales Ramon (UPMC)
autogenerated on Wed Oct 14 2020 04:05:04