chainidsolver_recursive_newton_euler.hpp
Go to the documentation of this file.
1 // Copyright (C) 2009 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_IKSOLVER_RECURSIVE_NEWTON_EULER_HPP
23 #define KDL_CHAIN_IKSOLVER_RECURSIVE_NEWTON_EULER_HPP
24 
25 #include "chainidsolver.hpp"
26 
27 namespace KDL{
41  public:
47  ChainIdSolver_RNE(const Chain& chain,Vector grav);
49 
60  int CartToJnt(const JntArray &q, const JntArray &q_dot, const JntArray &q_dotdot, const Wrenches& f_ext,JntArray &torques);
61 
63  virtual void updateInternalDataStructures();
64 
65  private:
66  const Chain& chain;
67  unsigned int nj;
68  unsigned int ns;
69  std::vector<Frame> X;
70  std::vector<Twist> S;
71  std::vector<Twist> v;
72  std::vector<Twist> a;
73  std::vector<Wrench> f;
75  };
76 }
77 
78 #endif
This class encapsulates a serial kinematic interconnection structure. It is built out of segments...
Definition: chain.hpp:35
ChainIdSolver_RNE(const Chain &chain, Vector grav)
This class represents an fixed size array containing joint values of a KDL::Chain.
Definition: jntarray.hpp:69
represents both translational and rotational velocities.
Definition: frames.hpp:723
This abstract class encapsulates the inverse dynamics solver for a KDL::Chain.
A concrete implementation of a 3 dimensional vector class.
Definition: frames.hpp:162
Recursive newton euler inverse dynamics solver.
int CartToJnt(const JntArray &q, const JntArray &q_dot, const JntArray &q_dotdot, const Wrenches &f_ext, JntArray &torques)
std::vector< Wrench > Wrenches


orocos_kdl
Author(s):
autogenerated on Thu Apr 13 2023 02:19:14