Go to the documentation of this file.
8 #ifndef TREEJNTTOJACSOLVER_HPP_
9 #define TREEJNTTOJACSOLVER_HPP_
29 const std::string& segmentname);
unsigned int columns() const
Definition: jacobian.cpp:75
unsigned int getNrOfJoints() const
Request the total number of joints in the tree.
Definition: tree.hpp:159
static Frame Identity()
Definition: frames.inl:695
void setColumn(unsigned int i, const Twist &t)
Definition: jacobian.cpp:149
Definition: jntarray.hpp:70
SegmentMap::const_iterator getRootSegment() const
Request the root segment of the tree.
Definition: tree.hpp:186
KDL::Tree tree
Definition: treejnttojacsolver.hpp:32
Vector p
origine of the Frame
Definition: frames.hpp:572
int JntToJac(const JntArray &q_in, Jacobian &jac, const std::string &segmentname)
Definition: treejnttojacsolver.cpp:21
#define GetTreeElementParent(tree_element)
Definition: tree.hpp:60
Definition: articulatedbodyinertia.cpp:28
represents both translational and rotational velocities.
Definition: frames.hpp:720
const SegmentMap & getSegments() const
Definition: tree.hpp:205
unsigned int rows() const
Returns the number of rows (size) of the array.
Definition: jntarray.cpp:72
Definition: frames.hpp:570
virtual ~TreeJntToJacSolver()
Definition: treejnttojacsolver.cpp:18
This class encapsulates a tree kinematic interconnection structure.
Definition: tree.hpp:100
@ None
Definition: joint.hpp:47
bool changeBase(const Jacobian &src1, const Rotation &rot, Jacobian &dest)
Definition: jacobian.cpp:104
Twist RefPoint(const Vector &v_base_AB) const
Changes the reference point of the twist.
Definition: frames.inl:302
Rotation M
Orientation of the Frame.
Definition: frames.hpp:573
#define GetTreeElementSegment(tree_element)
Definition: tree.hpp:62
void SetToZero(Jacobian &jac)
Definition: jacobian.cpp:80
Definition: treejnttojacsolver.hpp:17
TreeJntToJacSolver(const Tree &tree)
Definition: treejnttojacsolver.cpp:14
#define GetTreeElementQNr(tree_element)
Definition: tree.hpp:61
Definition: jacobian.hpp:37