orocos_kdl
chainjnttojacsolver.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_CHAINJNTTOJACSOLVER_HPP
23 #define KDL_CHAINJNTTOJACSOLVER_HPP
24 
25 #include "solveri.hpp"
26 #include "frames.hpp"
27 #include "jacobian.hpp"
28 #include "jntarray.hpp"
29 #include "chain.hpp"
30 
31 namespace KDL
32 {
39  {
40  public:
41 
42  explicit ChainJntToJacSolver(const Chain& chain);
43  virtual ~ChainJntToJacSolver();
55  virtual int JntToJac(const JntArray& q_in, Jacobian& jac, int seg_nr=-1);
56 
62  int setLockedJoints(const std::vector<bool> locked_joints);
63 
65  virtual void updateInternalDataStructures();
66 
67  private:
68  const Chain& chain;
72  };
73 }
74 #endif
KDL::ChainJntToJacSolver::ChainJntToJacSolver
ChainJntToJacSolver(const Chain &chain)
Definition: chainjnttojacsolver.cpp:26
chain.hpp
frames.hpp
KDL::ChainJntToJacSolver::chain
const Chain & chain
Definition: chainjnttojacsolver.hpp:68
KDL::JntArray
Definition: jntarray.hpp:69
std::vector< bool >
jntarray.hpp
KDL::ChainJntToJacSolver::JntToJac
virtual int JntToJac(const JntArray &q_in, Jacobian &jac, int seg_nr=-1)
Definition: chainjnttojacsolver.cpp:48
KDL
Definition: kukaLWR_DHnew.cpp:25
KDL::Twist
represents both translational and rotational velocities.
Definition: frames.hpp:723
KDL::ChainJntToJacSolver::T_tmp
Frame T_tmp
Definition: chainjnttojacsolver.hpp:70
KDL::ChainJntToJacSolver::~ChainJntToJacSolver
virtual ~ChainJntToJacSolver()
Definition: chainjnttojacsolver.cpp:34
KDL::ChainJntToJacSolver::setLockedJoints
int setLockedJoints(const std::vector< bool > locked_joints)
Definition: chainjnttojacsolver.cpp:38
KDL::Frame
represents a frame transformation in 3D space (rotation + translation)
Definition: frames.hpp:572
solveri.hpp
KDL::ChainJntToJacSolver::updateInternalDataStructures
virtual void updateInternalDataStructures()
Definition: chainjnttojacsolver.cpp:31
KDL::ChainJntToJacSolver::t_tmp
Twist t_tmp
Definition: chainjnttojacsolver.hpp:69
KDL::ChainJntToJacSolver::locked_joints_
std::vector< bool > locked_joints_
Definition: chainjnttojacsolver.hpp:71
KDL::SolverI
Definition: solveri.hpp:84
KDL::ChainJntToJacSolver
Class to calculate the jacobian of a general KDL::Chain, it is used by other solvers.
Definition: chainjnttojacsolver.hpp:38
jacobian.hpp
KDL::Chain
This class encapsulates a serial kinematic interconnection structure. It is built out of segments.
Definition: chain.hpp:35
KDL::Jacobian
Definition: jacobian.hpp:36