Public Member Functions | Static Public Attributes | Protected Member Functions | Private Attributes
KDL::ChainJntToJacDotSolver Class Reference

Computes the Jacobian time derivative (Jdot) by calculating the partial derivatives regarding to a joint angle, in the Hybrid, Body-fixed or Inertial representation. More...

#include <chainjnttojacdotsolver.hpp>

Inheritance diagram for KDL::ChainJntToJacDotSolver:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 ChainJntToJacDotSolver (const Chain &chain)
virtual int JntToJacDot (const KDL::JntArrayVel &q_in, KDL::Twist &jac_dot_q_dot, int seg_nr=-1)
 Computes $ {}_{bs}\dot{J}^{ee}.\dot{q} $.
virtual int JntToJacDot (const KDL::JntArrayVel &q_in, KDL::Jacobian &jdot, int seg_nr=-1)
 Computes $ {}_{bs}\dot{J}^{ee} $.
void setBodyFixedRepresentation ()
 JntToJacDot() will compute in the Body-fixed representation (ref Frame: end-effector, ref Point: end-effector)
void setHybridRepresentation ()
 JntToJacDot() will compute in the Hybrid representation (ref Frame: base, ref Point: end-effector)
void setInternialRepresentation ()
 JntToJacDot() will compute in the Inertial representation (ref Frame: base, ref Point: base)
int setLockedJoints (const std::vector< bool > locked_joints)
void setRepresentation (const int &representation)
 Sets the internal variable for the representation (with a check on the value)
virtual const char * strError (const int error) const
virtual ~ChainJntToJacDotSolver ()

Static Public Attributes

static const int BODYFIXED = 1
static const int E_JAC_DOT_FAILED = -100
static const int HYBRID = 0
static const int INTERTIAL = 2

Protected Member Functions

const TwistgetPartialDerivative (const Jacobian &J, const unsigned int &joint_idx, const unsigned int &column_idx, const int &representation)
 Computes $ \frac{\partial J^{i,ee}}{\partial q^{j}}.\dot{q}^{j} $.
const TwistgetPartialDerivativeBodyFixed (const Jacobian &ee_J_ee, const unsigned int &joint_idx, const unsigned int &column_idx)
 Computes $ \frac{\partial {}_{ee}J^{i,ee}}{\partial q^{j}}.\dot{q}^{j} $.
const TwistgetPartialDerivativeHybrid (const Jacobian &bs_J_ee, const unsigned int &joint_idx, const unsigned int &column_idx)
 Computes $ \frac{\partial {}_{bs}J^{i,ee}}{\partial q^{j}}.\dot{q}^{j} $.
const TwistgetPartialDerivativeInertial (const Jacobian &bs_J_bs, const unsigned int &joint_idx, const unsigned int &column_idx)
 Computes $ \frac{\partial {}_{bs}J^{i,bs}}{\partial q^{j}}.\dot{q}^{j} $.

Private Attributes

const Chain chain
Frame F_bs_ee_
ChainFkSolverPos_recursive fk_solver_
Jacobian jac_
Jacobian jac_dot_
Twist jac_dot_k_
Twist jac_i_
Twist jac_j_
ChainJntToJacSolver jac_solver_
std::vector< bool > locked_joints_
unsigned int nr_of_unlocked_joints_
int representation_
Twist t_djdq_

Detailed Description

Computes the Jacobian time derivative (Jdot) by calculating the partial derivatives regarding to a joint angle, in the Hybrid, Body-fixed or Inertial representation.

This work is based on : Symbolic differentiation of the velocity mapping for a serial kinematic chain H. Bruyninckx, J. De Schutter doi:10.1016/0094-114X(95)00069-B

url : http://www.sciencedirect.com/science/article/pii/0094114X9500069B

Definition at line 48 of file chainjnttojacdotsolver.hpp.


Constructor & Destructor Documentation

Definition at line 26 of file chainjnttojacdotsolver.cpp.

Definition at line 226 of file chainjnttojacdotsolver.cpp.


Member Function Documentation

const Twist & KDL::ChainJntToJacDotSolver::getPartialDerivative ( const Jacobian J,
const unsigned int &  joint_idx,
const unsigned int &  column_idx,
const int &  representation 
) [protected]

Computes $ \frac{\partial J^{i,ee}}{\partial q^{j}}.\dot{q}^{j} $.

Parameters:
bs_J_bsThe Jacobian expressed in the base frame with the end effector as the reference point
joint_idxThe indice of the current joint (j in the formula)
column_idxThe indice of the current column (i in the formula)
representationThe representation (Hybrid,Body-fixed,Inertial) in which you want to get dJ/dqj .qdotj
Returns:
Twist The twist representing dJi/dqj .qdotj

Definition at line 105 of file chainjnttojacdotsolver.cpp.

const Twist & KDL::ChainJntToJacDotSolver::getPartialDerivativeBodyFixed ( const Jacobian ee_J_ee,
const unsigned int &  joint_idx,
const unsigned int &  column_idx 
) [protected]

Computes $ \frac{\partial {}_{ee}J^{i,ee}}{\partial q^{j}}.\dot{q}^{j} $.

Parameters:
bs_J_eeThe Jacobian expressed in the end effector frame with the end effector as the reference point
joint_idxThe indice of the current joint (j in the formula)
column_idxThe indice of the current column (i in the formula)
Returns:
Twist The twist representing dJi/dqj .qdotj

Definition at line 155 of file chainjnttojacdotsolver.cpp.

const Twist & KDL::ChainJntToJacDotSolver::getPartialDerivativeHybrid ( const Jacobian bs_J_ee,
const unsigned int &  joint_idx,
const unsigned int &  column_idx 
) [protected]

Computes $ \frac{\partial {}_{bs}J^{i,ee}}{\partial q^{j}}.\dot{q}^{j} $.

Parameters:
bs_J_eeThe Jacobian expressed in the base frame with the end effector as the reference point (default in KDL Jacobian Solver)
joint_idxThe index of the current joint (j in the formula)
column_idxThe index of the current column (i in the formula)
Returns:
Twist The twist representing dJi/dqj .qdotj

Definition at line 124 of file chainjnttojacdotsolver.cpp.

const Twist & KDL::ChainJntToJacDotSolver::getPartialDerivativeInertial ( const Jacobian bs_J_bs,
const unsigned int &  joint_idx,
const unsigned int &  column_idx 
) [protected]

Computes $ \frac{\partial {}_{bs}J^{i,bs}}{\partial q^{j}}.\dot{q}^{j} $.

Parameters:
ee_J_eeThe Jacobian expressed in the base frame with the base as the reference point
joint_idxThe indice of the current joint (j in the formula)
column_idxThe indice of the current column (i in the formula)
Returns:
Twist The twist representing dJi/dqj .qdotj

Definition at line 177 of file chainjnttojacdotsolver.cpp.

int KDL::ChainJntToJacDotSolver::JntToJacDot ( const KDL::JntArrayVel q_in,
KDL::Twist jac_dot_q_dot,
int  seg_nr = -1 
) [virtual]

Computes $ {}_{bs}\dot{J}^{ee}.\dot{q} $.

Parameters:
q_inCurrent joint positions and velocities
jac_dot_q_dotThe twist representing Jdot*qdot
seg_nrThe final segment to compute
Returns:
int 0 if no errors happened

Definition at line 38 of file chainjnttojacdotsolver.cpp.

int KDL::ChainJntToJacDotSolver::JntToJacDot ( const KDL::JntArrayVel q_in,
KDL::Jacobian jdot,
int  seg_nr = -1 
) [virtual]

Computes $ {}_{bs}\dot{J}^{ee} $.

Parameters:
q_inCurrent joint positions and velocities
jdotThe jacobian time derivative in the configured representation (HYBRID, BODYFIXED or INERTIAL)
seg_nrThe final segment to compute
Returns:
int 0 if no errors happened

Definition at line 45 of file chainjnttojacdotsolver.cpp.

JntToJacDot() will compute in the Body-fixed representation (ref Frame: end-effector, ref Point: end-effector)

Returns:
void

Definition at line 95 of file chainjnttojacdotsolver.hpp.

JntToJacDot() will compute in the Hybrid representation (ref Frame: base, ref Point: end-effector)

Returns:
void

Definition at line 89 of file chainjnttojacdotsolver.hpp.

JntToJacDot() will compute in the Inertial representation (ref Frame: base, ref Point: base)

Returns:
void

Definition at line 101 of file chainjnttojacdotsolver.hpp.

int KDL::ChainJntToJacDotSolver::setLockedJoints ( const std::vector< bool >  locked_joints)

Definition at line 207 of file chainjnttojacdotsolver.cpp.

void KDL::ChainJntToJacDotSolver::setRepresentation ( const int &  representation)

Sets the internal variable for the representation (with a check on the value)

Parameters:
representationThe representation for Jdot : HYBRID,BODYFIXED or INTERTIAL
Returns:
void

Definition at line 198 of file chainjnttojacdotsolver.cpp.

const char * KDL::ChainJntToJacDotSolver::strError ( const int  error) const [virtual]

Return a description of the latest error

Returns:
if error is known then a description of error, otherwise "UNKNOWN ERROR"

Reimplemented from KDL::SolverI.

Definition at line 220 of file chainjnttojacdotsolver.cpp.


Member Data Documentation

Definition at line 56 of file chainjnttojacdotsolver.hpp.

Definition at line 161 of file chainjnttojacdotsolver.hpp.

Definition at line 51 of file chainjnttojacdotsolver.hpp.

Definition at line 169 of file chainjnttojacdotsolver.hpp.

Definition at line 168 of file chainjnttojacdotsolver.hpp.

const int KDL::ChainJntToJacDotSolver::HYBRID = 0 [static]

Definition at line 54 of file chainjnttojacdotsolver.hpp.

Definition at line 58 of file chainjnttojacdotsolver.hpp.

Definition at line 165 of file chainjnttojacdotsolver.hpp.

Definition at line 166 of file chainjnttojacdotsolver.hpp.

Definition at line 170 of file chainjnttojacdotsolver.hpp.

Definition at line 171 of file chainjnttojacdotsolver.hpp.

Definition at line 171 of file chainjnttojacdotsolver.hpp.

Definition at line 164 of file chainjnttojacdotsolver.hpp.

std::vector<bool> KDL::ChainJntToJacDotSolver::locked_joints_ [private]

Definition at line 162 of file chainjnttojacdotsolver.hpp.

Definition at line 163 of file chainjnttojacdotsolver.hpp.

Definition at line 167 of file chainjnttojacdotsolver.hpp.

Definition at line 172 of file chainjnttojacdotsolver.hpp.


The documentation for this class was generated from the following files:


orocos_kdl
Author(s):
autogenerated on Sat Oct 7 2017 03:04:29