21 #ifndef KDL_CHAINJNTTOJACDOTSOLVER_HPP 22 #define KDL_CHAINJNTTOJACDOTSOLVER_HPP 129 const unsigned int& joint_idx,
130 const unsigned int& column_idx);
140 const unsigned int& joint_idx,
141 const unsigned int& column_idx);
151 const unsigned int& joint_idx,
152 const unsigned int& column_idx);
163 const unsigned int& joint_idx,
164 const unsigned int& column_idx,
165 const int& representation);
void setRepresentation(const int &representation)
Sets the internal variable for the representation (with a check on the value)
static const int BODYFIXED
int setLockedJoints(const std::vector< bool > &locked_joints)
static const int E_JAC_DOT_FAILED
Computes the Jacobian time derivative (Jdot) by calculating the partial derivatives regarding to a jo...
unsigned int nr_of_unlocked_joints_
const Twist & getPartialDerivativeHybrid(const Jacobian &bs_J_ee, const unsigned int &joint_idx, const unsigned int &column_idx)
Computes .
This class encapsulates a serial kinematic interconnection structure. It is built out of segments...
static const int E_JACSOLVER_FAILED
const Twist & getPartialDerivativeBodyFixed(const Jacobian &ee_J_ee, const unsigned int &joint_idx, const unsigned int &column_idx)
Computes .
virtual ~ChainJntToJacDotSolver()
ChainFkSolverPos_recursive fk_solver_
virtual const char * strError(const int error) const
void setBodyFixedRepresentation()
JntToJacDot() will compute in the Body-fixed representation (ref Frame: end-effector, ref Point: end-effector)
Class to calculate the jacobian of a general KDL::Chain, it is used by other solvers.
represents both translational and rotational velocities.
void setInertialRepresentation()
JntToJacDot() will compute in the Inertial representation (ref Frame: base, ref Point: base) ...
ChainJntToJacSolver jac_solver_
static const int INERTIAL
void setHybridRepresentation()
JntToJacDot() will compute in the Hybrid representation (ref Frame: base, ref Point: end-effector) ...
static const int E_FKSOLVERPOS_FAILED
std::vector< bool > locked_joints_
ChainJntToJacDotSolver(const Chain &chain)
virtual int JntToJacDot(const KDL::JntArrayVel &q_in, KDL::Twist &jac_dot_q_dot, int seg_nr=-1)
Computes .
represents a frame transformation in 3D space (rotation + translation)
virtual void updateInternalDataStructures()
const Twist & getPartialDerivative(const Jacobian &J, const unsigned int &joint_idx, const unsigned int &column_idx, const int &representation)
Computes .
int error
Latest error, initialized to E_NOERROR in constructor.
const Twist & getPartialDerivativeInertial(const Jacobian &bs_J_bs, const unsigned int &joint_idx, const unsigned int &column_idx)
Computes .