treejnttojacsolver.hpp
Go to the documentation of this file.
1 /*
2  * TreeJntToJacSolver.hpp
3  *
4  * Created on: Nov 27, 2008
5  * Author: rubensmits
6  */
7 
8 #ifndef TREEJNTTOJACSOLVER_HPP_
9 #define TREEJNTTOJACSOLVER_HPP_
10 
11 #include "tree.hpp"
12 #include "jacobian.hpp"
13 #include "jntarray.hpp"
14 
15 namespace KDL {
16 
18 public:
19  explicit TreeJntToJacSolver(const Tree& tree);
20 
21  virtual ~TreeJntToJacSolver();
22 
23  /*
24  * Calculate the jacobian for a part of the tree: from a certain segment, given by segmentname to the root.
25  * The resulting jacobian is expressed in the baseframe of the tree ("root"), the reference point is in the end-segment
26  */
27 
28  int JntToJac(const JntArray& q_in, Jacobian& jac,
29  const std::string& segmentname);
30 
31 private:
33 
34 };
35 
36 }//End of namespace
37 
38 #endif /* TREEJNTTOJACSOLVER_H_ */
int JntToJac(const JntArray &q_in, Jacobian &jac, const std::string &segmentname)
This class represents an fixed size array containing joint values of a KDL::Chain.
Definition: jntarray.hpp:69
TreeJntToJacSolver(const Tree &tree)
This class encapsulates a tree kinematic interconnection structure. It is built out of segments...
Definition: tree.hpp:99


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