KDL  1.4.0
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_ */
KDL::Jacobian::columns
unsigned int columns() const
Definition: jacobian.cpp:75
KDL::Tree::getNrOfJoints
unsigned int getNrOfJoints() const
Request the total number of joints in the tree.
Definition: tree.hpp:159
KDL::Frame::Identity
static Frame Identity()
Definition: frames.inl:695
KDL::Jacobian::setColumn
void setColumn(unsigned int i, const Twist &t)
Definition: jacobian.cpp:149
kinfam_io.hpp
KDL::JntArray
Definition: jntarray.hpp:69
KDL::Tree::getRootSegment
SegmentMap::const_iterator getRootSegment() const
Request the root segment of the tree.
Definition: tree.hpp:186
KDL::TreeJntToJacSolver::tree
KDL::Tree tree
Definition: treejnttojacsolver.hpp:32
jntarray.hpp
KDL::Frame::p
Vector p
origine of the Frame
Definition: frames.hpp:572
KDL::TreeJntToJacSolver::JntToJac
int JntToJac(const JntArray &q_in, Jacobian &jac, const std::string &segmentname)
Definition: treejnttojacsolver.cpp:21
GetTreeElementParent
#define GetTreeElementParent(tree_element)
Definition: tree.hpp:60
KDL
Definition: articulatedbodyinertia.cpp:28
KDL::Twist
represents both translational and rotational velocities.
Definition: frames.hpp:720
KDL::Tree::getSegments
const SegmentMap & getSegments() const
Definition: tree.hpp:205
KDL::JntArray::rows
unsigned int rows() const
Returns the number of rows (size) of the array.
Definition: jntarray.cpp:72
KDL::Frame
Definition: frames.hpp:570
tree.hpp
KDL::TreeJntToJacSolver::~TreeJntToJacSolver
virtual ~TreeJntToJacSolver()
Definition: treejnttojacsolver.cpp:18
KDL::Tree
This class encapsulates a tree kinematic interconnection structure.
Definition: tree.hpp:99
KDL::Joint::None
@ None
Definition: joint.hpp:47
KDL::changeBase
bool changeBase(const Jacobian &src1, const Rotation &rot, Jacobian &dest)
Definition: jacobian.cpp:104
KDL::Twist::RefPoint
Twist RefPoint(const Vector &v_base_AB) const
Changes the reference point of the twist.
Definition: frames.inl:302
KDL::Frame::M
Rotation M
Orientation of the Frame.
Definition: frames.hpp:573
treejnttojacsolver.hpp
GetTreeElementSegment
#define GetTreeElementSegment(tree_element)
Definition: tree.hpp:62
KDL::SetToZero
void SetToZero(Jacobian &jac)
Definition: jacobian.cpp:80
jacobian.hpp
KDL::TreeJntToJacSolver
Definition: treejnttojacsolver.hpp:17
KDL::TreeJntToJacSolver::TreeJntToJacSolver
TreeJntToJacSolver(const Tree &tree)
Definition: treejnttojacsolver.cpp:14
GetTreeElementQNr
#define GetTreeElementQNr(tree_element)
Definition: tree.hpp:61
KDL::Jacobian
Definition: jacobian.hpp:36