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>
|
enum | {
E_DEGRADED = +1,
E_NOERROR = 0,
E_NO_CONVERGE = -1,
E_UNDEFINED = -2,
E_NOT_UP_TO_DATE = -3,
E_SIZE_MISMATCH = -4,
E_MAX_ITERATIONS_EXCEEDED = -5,
E_OUT_OF_RANGE = -6,
E_NOT_IMPLEMENTED = -7,
E_SVD_FAILED = -8
} |
|
int | error |
| Latest error, initialized to E_NOERROR in constructor. More...
|
|
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.
KDL::ChainJntToJacDotSolver::ChainJntToJacDotSolver |
( |
const Chain & |
chain | ) |
|
|
explicit |
KDL::ChainJntToJacDotSolver::~ChainJntToJacDotSolver |
( |
| ) |
|
|
virtual |
const Twist & KDL::ChainJntToJacDotSolver::getPartialDerivative |
( |
const Jacobian & |
J, |
|
|
const unsigned int & |
joint_idx, |
|
|
const unsigned int & |
column_idx, |
|
|
const int & |
representation |
|
) |
| |
|
protected |
Computes .
- Parameters
-
bs_J_bs | The Jacobian expressed in the base frame with the end effector as the reference point |
joint_idx | The indice of the current joint (j in the formula) |
column_idx | The indice of the current column (i in the formula) |
representation | The 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 125 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 .
- Parameters
-
bs_J_ee | The Jacobian expressed in the end effector frame with the end effector as the reference point |
joint_idx | The indice of the current joint (j in the formula) |
column_idx | The indice of the current column (i in the formula) |
- Returns
- Twist The twist representing dJi/dqj .qdotj
Definition at line 175 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 .
- Parameters
-
bs_J_ee | The Jacobian expressed in the base frame with the end effector as the reference point (default in KDL Jacobian Solver) |
joint_idx | The index of the current joint (j in the formula) |
column_idx | The index of the current column (i in the formula) |
- Returns
- Twist The twist representing dJi/dqj .qdotj
Definition at line 144 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 .
- Parameters
-
ee_J_ee | The Jacobian expressed in the base frame with the base as the reference point |
joint_idx | The indice of the current joint (j in the formula) |
column_idx | The indice of the current column (i in the formula) |
- Returns
- Twist The twist representing dJi/dqj .qdotj
Definition at line 197 of file chainjnttojacdotsolver.cpp.
Computes .
- Parameters
-
q_in | Current joint positions and velocities |
jac_dot_q_dot | The twist representing Jdot*qdot |
seg_nr | The final segment to compute |
- Returns
- int 0 if no errors happened
Definition at line 55 of file chainjnttojacdotsolver.cpp.
Computes .
- Parameters
-
q_in | Current joint positions and velocities |
jdot | The jacobian time derivative in the configured representation (HYBRID, BODYFIXED or INERTIAL) |
seg_nr | The final segment to compute |
- Returns
- int 0 if no errors happened
Definition at line 65 of file chainjnttojacdotsolver.cpp.
void KDL::ChainJntToJacDotSolver::setBodyFixedRepresentation |
( |
| ) |
|
|
inline |
void KDL::ChainJntToJacDotSolver::setHybridRepresentation |
( |
| ) |
|
|
inline |
void KDL::ChainJntToJacDotSolver::setInertialRepresentation |
( |
| ) |
|
|
inline |
int KDL::ChainJntToJacDotSolver::setLockedJoints |
( |
const std::vector< bool > & |
locked_joints | ) |
|
void KDL::ChainJntToJacDotSolver::setRepresentation |
( |
const int & |
representation | ) |
|
Sets the internal variable for the representation (with a check on the value)
- Parameters
-
representation | The representation for Jdot : HYBRID,BODYFIXED or INERTIAL |
- Returns
- void
Definition at line 218 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 241 of file chainjnttojacdotsolver.cpp.
void KDL::ChainJntToJacDotSolver::updateInternalDataStructures |
( |
| ) |
|
|
virtual |
Update the internal data structures. This is required if the number of segments or number of joints of a chain/tree have changed. This provides a single point of contact for solver memory allocations.
Implements KDL::SolverI.
Definition at line 46 of file chainjnttojacdotsolver.cpp.
const int KDL::ChainJntToJacDotSolver::BODYFIXED = 1 |
|
static |
const Chain& KDL::ChainJntToJacDotSolver::chain |
|
private |
const int KDL::ChainJntToJacDotSolver::E_FKSOLVERPOS_FAILED = -102 |
|
static |
const int KDL::ChainJntToJacDotSolver::E_JAC_DOT_FAILED = -100 |
|
static |
const int KDL::ChainJntToJacDotSolver::E_JACSOLVER_FAILED = -101 |
|
static |
Frame KDL::ChainJntToJacDotSolver::F_bs_ee_ |
|
private |
const int KDL::ChainJntToJacDotSolver::HYBRID = 0 |
|
static |
const int KDL::ChainJntToJacDotSolver::INERTIAL = 2 |
|
static |
Jacobian KDL::ChainJntToJacDotSolver::jac_ |
|
private |
Jacobian KDL::ChainJntToJacDotSolver::jac_dot_ |
|
private |
Twist KDL::ChainJntToJacDotSolver::jac_dot_k_ |
|
private |
Twist KDL::ChainJntToJacDotSolver::jac_i_ |
|
private |
Twist KDL::ChainJntToJacDotSolver::jac_j_ |
|
private |
std::vector<bool> KDL::ChainJntToJacDotSolver::locked_joints_ |
|
private |
unsigned int KDL::ChainJntToJacDotSolver::nr_of_unlocked_joints_ |
|
private |
int KDL::ChainJntToJacDotSolver::representation_ |
|
private |
Twist KDL::ChainJntToJacDotSolver::t_djdq_ |
|
private |
The documentation for this class was generated from the following files: