Go to the documentation of this file.
22 #ifndef KDL_CHAINJNTTOJACSOLVER_HPP
23 #define KDL_CHAINJNTTOJACSOLVER_HPP
ChainJntToJacSolver(const Chain &chain)
Definition: chainjnttojacsolver.cpp:26
unsigned int columns() const
Definition: jacobian.cpp:75
static Frame Identity()
Definition: frames.inl:695
void setColumn(unsigned int i, const Twist &t)
Definition: jacobian.cpp:149
const Chain & chain
Definition: chainjnttojacsolver.hpp:71
Definition: jntarray.hpp:69
const Joint & getJoint() const
Request the joint of the segment.
Definition: segment.hpp:118
Vector p
origine of the Frame
Definition: frames.hpp:572
@ E_NOT_UP_TO_DATE
Chain size changed.
Definition: solveri.hpp:97
Definition: articulatedbodyinertia.cpp:28
unsigned int getNrOfSegments() const
Request the total number of segments in the chain.
Definition: chain.hpp:76
represents both translational and rotational velocities.
Definition: frames.hpp:720
Frame T_tmp
Definition: chainjnttojacsolver.hpp:73
@ E_OUT_OF_RANGE
Requested index out of range.
Definition: solveri.hpp:103
unsigned int rows() const
Returns the number of rows (size) of the array.
Definition: jntarray.cpp:72
virtual int JntToJac(const JntArray &q_in, Jacobian &jac, int segmentNR=-1)
Calculate the jacobian expressed in the base frame of the chain, with reference point at the end effe...
Definition: chainjnttojacsolver.cpp:48
const Segment & getSegment(unsigned int nr) const
Request the nr'd segment of the chain.
Definition: chain.cpp:68
@ E_SIZE_MISMATCH
Input size does not match internal state.
Definition: solveri.hpp:99
virtual ~ChainJntToJacSolver()
Definition: chainjnttojacsolver.cpp:34
Frame pose(const double &q) const
Request the pose of the segment, given the joint position q.
Definition: segment.cpp:57
int setLockedJoints(const std::vector< bool > locked_joints)
Definition: chainjnttojacsolver.cpp:38
Definition: frames.hpp:570
Twist twist(const double &q, const double &qdot) const
Request the 6D-velocity of the tip of the segment, given the joint position q and the joint velocity ...
Definition: segment.cpp:62
@ None
Definition: joint.hpp:47
virtual void updateInternalDataStructures()
Update the internal data structures.
Definition: chainjnttojacsolver.cpp:31
Twist t_tmp
Definition: chainjnttojacsolver.hpp:72
std::vector< bool > locked_joints_
Definition: chainjnttojacsolver.hpp:74
Solver interface supporting storage and description of the latest error.
Definition: solveri.hpp:84
Rotation M
Orientation of the Frame.
Definition: frames.hpp:573
bool changeRefPoint(const Jacobian &src1, const Vector &base_AB, Jacobian &dest)
Definition: jacobian.cpp:90
const JointType & getType() const
Request the type of the joint.
Definition: joint.hpp:159
Class to calculate the jacobian of a general KDL::Chain, it is used by other solvers.
Definition: chainjnttojacsolver.hpp:41
void SetToZero(Jacobian &jac)
Definition: jacobian.cpp:80
@ E_NOERROR
No error.
Definition: solveri.hpp:91
unsigned int getNrOfJoints() const
Request the total number of joints in the chain.
Definition: chain.hpp:71
int error
Latest error, initialized to E_NOERROR in constructor.
Definition: solveri.hpp:149
Definition: jacobian.hpp:36