Visual Servoing Platform
version 3.5.1 under development (2023-09-22)
|
#include <visp3/vs/vpServo.h>
Public Types | |
enum | vpServoType { NONE , EYEINHAND_CAMERA , EYEINHAND_L_cVe_eJe , EYETOHAND_L_cVe_eJe , EYETOHAND_L_cVf_fVe_eJe , EYETOHAND_L_cVf_fJe } |
enum | vpServoIteractionMatrixType { CURRENT , DESIRED , MEAN , USER_DEFINED } |
enum | vpServoInversionType { TRANSPOSE , PSEUDO_INVERSE } |
enum | vpServoPrintType { ALL , CONTROLLER , ERROR_VECTOR , FEATURE_CURRENT , FEATURE_DESIRED , GAIN , INTERACTION_MATRIX , MINIMUM } |
Public Attributes | |
vpMatrix | L |
vpColVector | error |
vpMatrix | J1 |
vpMatrix | J1p |
vpColVector | s |
vpColVector | sStar |
vpColVector | e1 |
vpColVector | e |
vpColVector | q_dot |
vpColVector | v |
vpServoType | servoType |
unsigned int | rankJ1 |
std::list< vpBasicFeature * > | featureList |
std::list< vpBasicFeature * > | desiredFeatureList |
std::list< unsigned int > | featureSelectionList |
vpAdaptiveGain | lambda |
int | signInteractionMatrix |
vpServoIteractionMatrixType | interactionMatrixType |
vpServoInversionType | inversionType |
Protected Member Functions | |
void | init () |
void | computeProjectionOperators (const vpMatrix &J1_, const vpMatrix &I_, const vpMatrix &I_WpW_, const vpColVector &error_, vpMatrix &P_) const |
Protected Attributes | |
vpVelocityTwistMatrix | cVe |
bool | init_cVe |
vpVelocityTwistMatrix | cVf |
bool | init_cVf |
vpVelocityTwistMatrix | fVe |
bool | init_fVe |
vpMatrix | eJe |
bool | init_eJe |
vpMatrix | fJe |
bool | init_fJe |
bool | errorComputed |
bool | interactionMatrixComputed |
unsigned int | dim_task |
bool | taskWasKilled |
bool | forceInteractionMatrixComputation |
vpMatrix | I |
vpMatrix | WpW |
vpMatrix | I_WpW |
vpMatrix | P |
vpColVector | sv |
double | mu |
vpColVector | e1_initial |
bool | iscJcIdentity |
vpMatrix | cJc |
bool | m_first_iteration |
double | m_pseudo_inverse_threshold |
Class required to compute the visual servoing control law described in [3] and [4].
To learn how to use this class, we suggest first to follow the Tutorial: Image-based visual servo. The Tutorial: Visual servo simulation on a pioneer-like unicycle robot and Tutorial: How to boost your visual servo control law are also useful for advanced usage of this class.
The example below shows how to build a position-based visual servo from 3D visual features . In that case, we have . Let us denote the angle/axis parametrization of the rotation . Moreover, and represent respectively the translation and the rotation between the desired camera frame and the current one obtained by pose estimation (see vpPose class).
Enumerator | |
---|---|
TRANSPOSE | In the control law (see vpServo::vpServoType), uses the transpose instead of the pseudo inverse. |
PSEUDO_INVERSE | In the control law (see vpServo::vpServoType), uses the pseudo inverse. |
Enumerator | |
---|---|
CURRENT | In the control law (see vpServo::vpServoType), uses the interaction matrix computed using the current features . |
DESIRED | In the control law (see vpServo::vpServoType), uses the interaction matrix computed using the desired features . |
MEAN | In the control law (see vpServo::vpServoType), uses the interaction matrix . |
USER_DEFINED | In the control law (see vpServo::vpServoType), uses an interaction matrix set by the user. |
enum vpServo::vpServoType |
vpServo::vpServo | ( | ) |
Default constructor that initializes the following settings:
Definition at line 67 of file vpServo.cpp.
References cJc, and vpMatrix::eye().
|
explicit |
Constructor that allows to choose the visual servoing control law.
servo_type | : Visual servoing control law. |
The other settings are the following:
Definition at line 93 of file vpServo.cpp.
References cJc, and vpMatrix::eye().
|
virtual |
Destructor.
Since ViSP > 3.3.0 calls kill() to destroy the current and desired feature lists.
Definition at line 111 of file vpServo.cpp.
References kill().
void vpServo::addFeature | ( | vpBasicFeature & | s_cur, |
unsigned int | select = vpBasicFeature::FEATURE_ALL |
||
) |
Add a new features in the task. The desired visual feature denoted is equal to zero.
s_cur | : Current visual feature denoted . |
select | : Feature selector. By default all the features in s are used, but is is possible to specify which one is used in case of multiple features. |
The following sample code explain how to use this method to add a feature:
For example to use only the feature, the previous code becomes:
Definition at line 521 of file vpServo.cpp.
References desiredFeatureList, vpBasicFeature::duplicate(), featureList, featureSelectionList, vpBasicFeature::init(), vpBasicFeature::setDeallocate(), and vpBasicFeature::vpServo.
void vpServo::addFeature | ( | vpBasicFeature & | s_cur, |
vpBasicFeature & | s_star, | ||
unsigned int | select = vpBasicFeature::FEATURE_ALL |
||
) |
Add a new set of 2 features and in the task.
s_cur | : Current visual feature denoted . |
s_star | : Desired visual feature denoted . |
select | : Feature selector. By default all the features in s and s_star are used, but is is possible to specify which one is used in case of multiple features. |
The following sample code explain how to use this method to add a visual feature point :
For example to use only the visual feature, the previous code becomes:
Definition at line 487 of file vpServo.cpp.
References desiredFeatureList, featureList, and featureSelectionList.
vpColVector vpServo::computeControlLaw | ( | ) |
Compute the control law specified using setServo(). See vpServo::vpServoType for more details concerning the control laws that are available. The Tutorial: Image-based visual servo and Tutorial: How to boost your visual servo control law are also useful to illustrate the usage of this function.
The general form of the control law is the following:
where :
To ensure continuous sequencing the computeControlLaw(double) function can be used. It will ensure that the velocities that are computed are continuous.
Definition at line 930 of file vpServo.cpp.
References vpMatrix::AAt(), cJc, computeError(), computeInteractionMatrix(), cVe, cVf, e, e1, eJe, error, vpMatrix::eye(), EYEINHAND_CAMERA, EYEINHAND_L_cVe_eJe, EYETOHAND_L_cVe_eJe, EYETOHAND_L_cVf_fJe, EYETOHAND_L_cVf_fVe_eJe, fJe, fVe, vpArray2D< Type >::getCols(), I, I_WpW, init_cVe, init_eJe, init_fJe, init_fVe, inversionType, iscJcIdentity, J1, J1p, L, lambda, m_first_iteration, m_pseudo_inverse_threshold, NONE, vpMatrix::print(), PSEUDO_INVERSE, vpMatrix::pseudoInverse(), rankJ1, vpServoException::servoError, servoType, signInteractionMatrix, sv, vpMatrix::t(), testInitialization(), testUpdated(), vpERROR_TRACE, and WpW.
vpColVector vpServo::computeControlLaw | ( | double | t | ) |
Compute the control law specified using setServo(). See vpServo::vpServoType for more details concerning the control laws that are available. The Tutorial: How to boost your visual servo control law is also useful to illustrate the usage of this function.
To the general form of the control law given in computeControlLaw(), we add here an additional term that comes from the task sequencing approach described in [30] equation (17). This additional term allows to compute continuous velocities by avoiding abrupt changes in the command.
The form of the control law considered here is the following:
where :
t | : Time in second. When set to zero, is refreshed internally. |
Definition at line 1076 of file vpServo.cpp.
References vpMatrix::AAt(), computeError(), computeInteractionMatrix(), cVe, cVf, e, e1, e1_initial, eJe, error, vpMatrix::eye(), EYEINHAND_CAMERA, EYEINHAND_L_cVe_eJe, EYETOHAND_L_cVe_eJe, EYETOHAND_L_cVf_fJe, EYETOHAND_L_cVf_fVe_eJe, fJe, fVe, vpArray2D< Type >::getCols(), vpArray2D< Type >::getRows(), I, I_WpW, init_cVe, init_eJe, init_fJe, init_fVe, inversionType, J1, J1p, L, lambda, m_first_iteration, m_pseudo_inverse_threshold, mu, NONE, PSEUDO_INVERSE, vpMatrix::pseudoInverse(), rankJ1, vpServoException::servoError, servoType, signInteractionMatrix, sv, vpMatrix::t(), testInitialization(), testUpdated(), vpERROR_TRACE, and WpW.
vpColVector vpServo::computeControlLaw | ( | double | t, |
const vpColVector & | e_dot_init | ||
) |
Compute the control law specified using setServo(). See vpServo::vpServoType for more details concerning the control laws that are available.
To the general form of the control law given in computeControlLaw(), we add here an additional term that comes from the task sequencing approach described in [30] equation (17). This additional term allows to compute continuous velocities by avoiding abrupt changes in the command.
The form of the control law considered here is the following:
where :
t | : Time in second. When set to zero, is refreshed internally. |
e_dot_init | : Initial value of . |
Definition at line 1231 of file vpServo.cpp.
References vpMatrix::AAt(), computeError(), computeInteractionMatrix(), cVe, cVf, e, e1, e1_initial, eJe, error, vpMatrix::eye(), EYEINHAND_CAMERA, EYEINHAND_L_cVe_eJe, EYETOHAND_L_cVe_eJe, EYETOHAND_L_cVf_fJe, EYETOHAND_L_cVf_fVe_eJe, fJe, fVe, vpArray2D< Type >::getCols(), vpArray2D< Type >::getRows(), I, I_WpW, init_cVe, init_eJe, init_fJe, init_fVe, inversionType, J1, J1p, L, lambda, m_first_iteration, m_pseudo_inverse_threshold, mu, NONE, PSEUDO_INVERSE, vpMatrix::pseudoInverse(), rankJ1, vpServoException::servoError, servoType, signInteractionMatrix, sv, vpMatrix::t(), testInitialization(), testUpdated(), vpERROR_TRACE, and WpW.
vpColVector vpServo::computeError | ( | ) |
Compute the error between the current set of visual features and the desired set of visual features .
Definition at line 709 of file vpServo.cpp.
References desiredFeatureList, dim_task, vpBasicFeature::error(), error, errorComputed, featureList, featureSelectionList, vpBasicFeature::get_s(), vpArray2D< Type >::getRows(), vpServoException::noFeatureError, vpColVector::resize(), s, sStar, vpDEBUG_TRACE, and vpERROR_TRACE.
Referenced by computeControlLaw().
vpMatrix vpServo::computeInteractionMatrix | ( | ) |
Compute and return the interaction matrix related to the set of visual features.
Definition at line 644 of file vpServo.cpp.
References CURRENT, DESIRED, desiredFeatureList, dim_task, forceInteractionMatrixComputation, vpArray2D< Type >::getCols(), vpArray2D< Type >::getRows(), interactionMatrixComputed, interactionMatrixType, L, MEAN, and USER_DEFINED.
Referenced by computeControlLaw().
|
protected |
Compute the classic projection operator and the large projection operator.
Definition at line 1351 of file vpServo.cpp.
References vpMatrix::AAt(), vpMatrix::AtA(), vpColVector::frobeniusNorm(), vpArray2D< Type >::getCols(), vpArray2D< Type >::resize(), and vpColVector::t().
Referenced by secondaryTask(), and secondaryTaskJointLimitAvoidance().
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
unsigned int vpServo::getDimension | ( | ) | const |
Return the task dimension.
Definition at line 550 of file vpServo.cpp.
References featureList, and featureSelectionList.
|
inline |
Return the error between the current set of visual features and the desired set of visual features . The error vector is updated after a call of computeError() or computeControlLaw().
Definition at line 276 of file vpServo.h.
Referenced by vpServoData::save().
vpMatrix vpServo::getI_WpW | ( | ) | const |
Return the projection operator . This operator is updated after a call of computeControlLaw().
Definition at line 1735 of file vpServo.cpp.
References I_WpW.
|
inline |
Return the interaction matrix used to compute the task jacobian . The interaction matrix is updated after a call to computeInteractionMatrix() or computeControlLaw().
vpMatrix vpServo::getLargeP | ( | ) | const |
Return the large projection operator. This operator is updated after a call of computeControlLaw().
Definition at line 1749 of file vpServo.cpp.
References P.
double vpServo::getPseudoInverseThreshold | ( | ) | const |
Return pseudo-inverse threshold used to test the singular values. If a singular value is lower than this threshold we consider that the matrix is not full rank.
Definition at line 1822 of file vpServo.cpp.
References m_pseudo_inverse_threshold.
|
inline |
vpMatrix vpServo::getTaskJacobian | ( | ) | const |
Return the task jacobian . The task jacobian is updated after a call of computeControlLaw().
In the general case, the task jacobian is given by .
Definition at line 1765 of file vpServo.cpp.
References J1.
vpMatrix vpServo::getTaskJacobianPseudoInverse | ( | ) | const |
Return the pseudo inverse of the task jacobian .
In the general case, the task jacobian is given by .
The task jacobian and its pseudo inverse are updated after a call of computeControlLaw().
Definition at line 1785 of file vpServo.cpp.
References J1p.
unsigned int vpServo::getTaskRank | ( | ) | const |
Return the rank of the task jacobian. The rank is updated after a call of computeControlLaw().
Definition at line 1796 of file vpServo.cpp.
References rankJ1.
|
inline |
vpMatrix vpServo::getWpW | ( | ) | const |
Return the projection operator . This operator is updated after a call of computeControlLaw().
When the dimension of the task is equal to the number of degrees of freedom available .
Definition at line 1813 of file vpServo.cpp.
References WpW.
|
protected |
Basic initialization.
Initialize the servo with the following settings:
Definition at line 127 of file vpServo.cpp.
References DESIRED, desiredFeatureList, dim_task, errorComputed, featureList, featureSelectionList, forceInteractionMatrixComputation, init_cVe, init_cVf, init_eJe, init_fJe, init_fVe, interactionMatrixComputed, interactionMatrixType, inversionType, m_first_iteration, NONE, PSEUDO_INVERSE, rankJ1, servoType, signInteractionMatrix, and taskWasKilled.
void vpServo::kill | ( | ) |
Task destruction. Kill the current and desired visual feature lists.
This function is called in the destructor. Since ViSP > 3.3.0 it is no more mandatory to call explicitly kill().
Definition at line 179 of file vpServo.cpp.
References desiredFeatureList, featureList, taskWasKilled, and vpBasicFeature::vpServo.
Referenced by ~vpServo().
void vpServo::print | ( | const vpServo::vpServoPrintType | displayLevel = ALL , |
std::ostream & | os = std::cout |
||
) |
Prints on os stream information about the task:
displayLevel | : Indicates which are the task information to print. See vpServo::vpServoPrintType for more details. |
os | : Output stream. |
Definition at line 299 of file vpServo.cpp.
References ALL, CONTROLLER, desiredFeatureList, error, ERROR_VECTOR, errorComputed, EYEINHAND_CAMERA, EYEINHAND_L_cVe_eJe, EYETOHAND_L_cVe_eJe, EYETOHAND_L_cVf_fJe, EYETOHAND_L_cVf_fVe_eJe, FEATURE_CURRENT, FEATURE_DESIRED, featureList, featureSelectionList, GAIN, INTERACTION_MATRIX, interactionMatrixComputed, L, lambda, MINIMUM, NONE, servoType, and vpColVector::t().
vpColVector vpServo::secondaryTask | ( | const vpColVector & | de2dt, |
const bool & | useLargeProjectionOperator = false |
||
) |
Compute and return the secondary task vector according to the classic projection operator (see equation(7) in the paper [33]) or the new large projection operator (see equation(24) in the paper [35]).
de2dt | : Value of the derivative of the secondary task . |
useLargeProjectionOperator | : if true will be use the large projection operator, if false the classic one (default). |
If the classic projection operator is used ( useLargeProjectionOperator = false (default value)) this function return:
Note that the secondary task vector need than to be added to the primary task which can be in the general case written as:
Otherwise if the new large projection operator is used ( useLargeProjectionOperator = true ) this function return:
where
with
The following sample code shows how to use this method to compute a secondary task using the classic projection operator:
The following sample code shows how to use this method to compute a secondary task using the large projection operator:
Definition at line 1454 of file vpServo.cpp.
References computeProjectionOperators(), error, vpArray2D< Type >::getCols(), I, I_WpW, J1, vpServoException::noDofFree, P, rankJ1, vpArray2D< Type >::resize(), vpMatrix::setIdentity(), vpERROR_TRACE, and WpW.
vpColVector vpServo::secondaryTask | ( | const vpColVector & | e2, |
const vpColVector & | de2dt, | ||
const bool & | useLargeProjectionOperator = false |
||
) |
Compute and return the secondary task vector according to the classic projection operator (see equation(7) in the paper [33]) or the new large projection operator (see equation(24) in the paper [35]).
e2 | : Value of the secondary task . |
de2dt | : Value of the derivative of the secondary task . |
useLargeProjectionOperator | if true will be use the large projection operator, if false the classic one (default). |
If the classic projection operator is used ( useLargeProjectionOperator = false (default value)) this function return:
Note that the secondary task vector need than to be added to the primary task which can be in the general case written as:
Otherwise if the new large projection operator is used ( useLargeProjectionOperator = true ) this function return:
where
with
The following sample code shows how to use this method to compute a secondary task using the classical projection operator:
The following sample code shows how to use this method to compute a secondary task using the large projection operator:
Definition at line 1561 of file vpServo.cpp.
References computeProjectionOperators(), e1, error, vpArray2D< Type >::getCols(), I, I_WpW, J1, lambda, vpServoException::noDofFree, P, rankJ1, vpArray2D< Type >::resize(), vpMatrix::setIdentity(), vpERROR_TRACE, and WpW.
vpColVector vpServo::secondaryTaskJointLimitAvoidance | ( | const vpColVector & | q, |
const vpColVector & | dq, | ||
const vpColVector & | qmin, | ||
const vpColVector & | qmax, | ||
const double & | rho = 0.1 , |
||
const double & | rho1 = 0.3 , |
||
const double & | lambda_tune = 0.7 |
||
) |
Compute and return the secondary task vector for joint limit avoidance [36] using the new large projection operator (see equation(24) in the paper [35]). The robot avoids the joint limits very smoothly even when the main task constrains all the robot degrees of freedom.
q | : Actual joint positions vector |
dq | : Actual joint velocities vector |
qmin | : Vector containing the low limit value of each joint in the chain. |
qmax | : Vector containing the high limit value of each joint in the chain. |
rho | : tuning paramenter used to define the safe configuration for the joint. When the joint angle value cross the max or min boundaries ( and ) the secondary task is actived gradually. |
rho1 | : tuning paramenter to compute the external boundaries ( and ) for the joint limits. Here the secondary task it completely activated with the highest gain. |
lambda_tune | : value used to tune the difference in magnitude between the absolute value of the elements of the primary task and the elements of the secondary task. (See equation (17) [36] ) |
Definition at line 1641 of file vpServo.cpp.
References vpMath::abs(), computeProjectionOperators(), vpException::dimensionError, error, vpMatrix::getCol(), vpArray2D< Type >::getCols(), I, I_WpW, J1, P, vpArray2D< Type >::size(), and vpERROR_TRACE.
|
inline |
|
inline |
Set the velocity twist matrix used to transform a velocity skew vector from end-effector frame into the camera frame.
Definition at line 448 of file vpServo.h.
Referenced by setServo().
|
inline |
|
inline |
|
inline |
Set the robot jacobian expressed in the end-effector frame.
Definition at line 506 of file vpServo.h.
Referenced by setServo().
|
inline |
|
inline |
|
inline |
void vpServo::setCameraDoF | ( | const vpColVector & | dof | ) |
Set a 6-dim column vector representing the degrees of freedom that are controlled in the camera frame. When set to 1, all the 6 dof are controlled.
dof | : Degrees of freedom to control in the camera frame. Below we give the correspondance between the index of the vector and the considered dof:
|
The following example shows how to use this function to control only wx, wy like a pan/tilt:
Definition at line 274 of file vpServo.cpp.
References cJc, iscJcIdentity, and vpArray2D< Type >::size().
|
inline |
Set a variable which enables to compute the interaction matrix at each iteration.
When the interaction matrix is computed from the desired features which are in general constant, the interaction matrix is computed just at the first iteration of the servo loop. Sometimes, when the desired features are time dependent or varying, the interaction matrix need to be computed at each iteration of the servo loop. This method allows to force the computation of in this particular case.
force_computation | : If true it forces the interaction matrix computation even if it is already done. |
void vpServo::setInteractionMatrixType | ( | const vpServoIteractionMatrixType & | interactionMatrixType, |
const vpServoInversionType & | interactionMatrixInversion = PSEUDO_INVERSE |
||
) |
Set the interaction matrix type (current, desired, mean or user defined) and how its inverse is computed.
interactionMatrixType | : The interaction matrix type. See vpServo::vpServoIteractionMatrixType for more details. |
interactionMatrixInversion | : How is the inverse computed. See vpServo::vpServoInversionType for more details. |
Definition at line 564 of file vpServo.cpp.
References interactionMatrixType, and inversionType.
|
inline |
Set the gain used in the control law (see vpServo::vpServoType) as adaptive. Value of that is used in computeControlLaw() depend on the infinity norm of the task Jacobian.
The usage of an adaptive gain rather than a constant gain allows to reduce the convergence time.
|
inline |
Set the gain used in the control law (see vpServo::vpServoType) as constant.
The usage of an adaptive gain allows to reduce the convergence time, see setLambda(const vpAdaptiveGain&).
c | : Constant gain. Values are in general between 0.1 and 1. Higher is the gain, higher are the velocities that may be applied to the robot. |
|
inline |
Set the gain used in the control law (see vpServo::vpServoType) as adaptive. Value of that is used in computeControlLaw() depend on the infinity norm of the task Jacobian.
The usage of an adaptive gain rather than a constant gain allows to reduce the convergence time.
gain_at_zero | : the expected gain when : . |
gain_at_infinity | : the expected gain when : . |
slope_at_zero | : the expected slope of when : . |
For more details on these parameters see vpAdaptiveGain class.
|
inline |
Set the value of the parameter used to ensure the continuity of the velocities computed using computeControlLaw(double).
A recommended value is 4.
void vpServo::setPseudoInverseThreshold | ( | double | pseudo_inverse_threshold | ) |
Set the pseudo-inverse threshold used to test the singular values. If a singular value is lower than this threshold we consider that the matrix is not full rank.
pseudo_inverse_threshold | : Value to use. Default value is set to 1e-6. |
Definition at line 1831 of file vpServo.cpp.
References m_pseudo_inverse_threshold.
void vpServo::setServo | ( | const vpServoType & | servo_type | ) |
Set the visual servoing control law.
servo_type | : Control law that will be considered. See vpServo::vpServoType to see the possible values. |
Definition at line 210 of file vpServo.cpp.
References vpMatrix::eye(), EYEINHAND_CAMERA, EYEINHAND_L_cVe_eJe, servoType, set_cVe(), set_eJe(), and signInteractionMatrix.
bool vpServo::testInitialization | ( | ) |
Test if all the initialization are correct. If true, the control law can be computed.
Definition at line 826 of file vpServo.cpp.
References EYEINHAND_CAMERA, EYEINHAND_L_cVe_eJe, EYETOHAND_L_cVe_eJe, EYETOHAND_L_cVf_fJe, EYETOHAND_L_cVf_fVe_eJe, init_cVe, init_cVf, init_eJe, init_fJe, init_fVe, NONE, vpServoException::servoError, servoType, and vpERROR_TRACE.
Referenced by computeControlLaw().
bool vpServo::testUpdated | ( | ) |
Test if all the update are correct. If true control law can be computed.
Definition at line 866 of file vpServo.cpp.
References EYEINHAND_CAMERA, EYEINHAND_L_cVe_eJe, EYETOHAND_L_cVe_eJe, EYETOHAND_L_cVf_fJe, EYETOHAND_L_cVf_fVe_eJe, init_cVe, init_eJe, init_fJe, init_fVe, NONE, vpServoException::servoError, servoType, and vpERROR_TRACE.
Referenced by computeControlLaw().
|
protected |
A diag matrix used to determine which are the degrees of freedom that are controlled in the camera frame
Definition at line 679 of file vpServo.h.
Referenced by computeControlLaw(), setCameraDoF(), and vpServo().
|
protected |
Twist transformation matrix between Re and Rc.
Definition at line 607 of file vpServo.h.
Referenced by computeControlLaw().
|
protected |
Twist transformation matrix between Rf and Rc.
Definition at line 610 of file vpServo.h.
Referenced by computeControlLaw().
std::list<vpBasicFeature *> vpServo::desiredFeatureList |
List of desired visual features .
Definition at line 584 of file vpServo.h.
Referenced by addFeature(), computeError(), computeInteractionMatrix(), vpServoDisplay::display(), init(), kill(), and print().
|
protected |
Dimension of the task updated during computeControlLaw().
Definition at line 636 of file vpServo.h.
Referenced by computeError(), computeInteractionMatrix(), and init().
vpColVector vpServo::e |
vpColVector vpServo::e1 |
Primary task .
Definition at line 566 of file vpServo.h.
Referenced by computeControlLaw(), and secondaryTask().
|
protected |
Definition at line 672 of file vpServo.h.
Referenced by computeControlLaw().
|
protected |
Jacobian expressed in the end-effector frame.
Definition at line 621 of file vpServo.h.
Referenced by computeControlLaw().
vpColVector vpServo::error |
Error between the current set of visual features and the desired set of visual features . This vector is updated after a call of computeError() or computeControlLaw().
Definition at line 550 of file vpServo.h.
Referenced by computeControlLaw(), computeError(), print(), secondaryTask(), and secondaryTaskJointLimitAvoidance().
|
protected |
true if the error has been computed.
Definition at line 632 of file vpServo.h.
Referenced by computeError(), init(), and print().
std::list<vpBasicFeature *> vpServo::featureList |
List of current visual features .
Definition at line 582 of file vpServo.h.
Referenced by addFeature(), computeError(), vpServoDisplay::display(), getDimension(), init(), kill(), and print().
std::list<unsigned int> vpServo::featureSelectionList |
List of selection among visual features used for selection of a subset of each visual feature if required.
Definition at line 587 of file vpServo.h.
Referenced by addFeature(), computeError(), getDimension(), init(), and print().
|
protected |
Jacobian expressed in the robot reference frame.
Definition at line 624 of file vpServo.h.
Referenced by computeControlLaw().
|
protected |
Force the interaction matrix computation even if it is already done.
Definition at line 640 of file vpServo.h.
Referenced by computeInteractionMatrix(), and init().
|
protected |
Twist transformation matrix between Re and Rf.
Definition at line 613 of file vpServo.h.
Referenced by computeControlLaw().
|
protected |
Identity matrix.
Definition at line 643 of file vpServo.h.
Referenced by computeControlLaw(), secondaryTask(), and secondaryTaskJointLimitAvoidance().
|
protected |
Projection operators .
Definition at line 647 of file vpServo.h.
Referenced by computeControlLaw(), getI_WpW(), secondaryTask(), and secondaryTaskJointLimitAvoidance().
|
protected |
Definition at line 608 of file vpServo.h.
Referenced by computeControlLaw(), init(), testInitialization(), and testUpdated().
|
protected |
Definition at line 611 of file vpServo.h.
Referenced by init(), and testInitialization().
|
protected |
Definition at line 622 of file vpServo.h.
Referenced by computeControlLaw(), init(), testInitialization(), and testUpdated().
|
protected |
Definition at line 625 of file vpServo.h.
Referenced by computeControlLaw(), init(), testInitialization(), and testUpdated().
|
protected |
Definition at line 614 of file vpServo.h.
Referenced by computeControlLaw(), init(), testInitialization(), and testUpdated().
|
protected |
true if the interaction matrix has been computed.
Definition at line 634 of file vpServo.h.
Referenced by computeInteractionMatrix(), init(), and print().
vpServoIteractionMatrixType vpServo::interactionMatrixType |
Type of the interaction matrix (current, mean, desired, user)
Definition at line 596 of file vpServo.h.
Referenced by computeInteractionMatrix(), init(), and setInteractionMatrixType().
vpServoInversionType vpServo::inversionType |
Indicates if the transpose or the pseudo inverse of the interaction matrix should be used to compute the task.
Definition at line 599 of file vpServo.h.
Referenced by computeControlLaw(), init(), and setInteractionMatrixType().
|
protected |
Boolean to know if cJc is identity (for fast computation)
Definition at line 675 of file vpServo.h.
Referenced by computeControlLaw(), and setCameraDoF().
vpMatrix vpServo::J1 |
Task Jacobian .
Definition at line 552 of file vpServo.h.
Referenced by computeControlLaw(), getTaskJacobian(), secondaryTask(), and secondaryTaskJointLimitAvoidance().
vpMatrix vpServo::J1p |
Pseudo inverse of the task Jacobian.
Definition at line 554 of file vpServo.h.
Referenced by computeControlLaw(), and getTaskJacobianPseudoInverse().
vpMatrix vpServo::L |
Interaction matrix.
Definition at line 545 of file vpServo.h.
Referenced by computeControlLaw(), computeInteractionMatrix(), and print().
vpAdaptiveGain vpServo::lambda |
Gain used in the control law.
Definition at line 590 of file vpServo.h.
Referenced by computeControlLaw(), print(), and secondaryTask().
|
protected |
True until first call of computeControlLaw() is achieved.
Definition at line 681 of file vpServo.h.
Referenced by computeControlLaw(), and init().
|
protected |
Threshold used in the pseudo inverse.
Definition at line 683 of file vpServo.h.
Referenced by computeControlLaw(), getPseudoInverseThreshold(), and setPseudoInverseThreshold().
|
protected |
Definition at line 670 of file vpServo.h.
Referenced by computeControlLaw().
|
protected |
New Large projection operator (see equation(24) in the paper [35]). This projection operator allows performing secondary task even when the main task is full rank.
with
Definition at line 665 of file vpServo.h.
Referenced by getLargeP(), secondaryTask(), and secondaryTaskJointLimitAvoidance().
vpColVector vpServo::q_dot |
unsigned int vpServo::rankJ1 |
Rank of the task Jacobian.
Definition at line 579 of file vpServo.h.
Referenced by computeControlLaw(), getTaskRank(), init(), and secondaryTask().
vpColVector vpServo::s |
Current state of visual features . This vector is updated after a call of computeError() or computeControlLaw().
Definition at line 559 of file vpServo.h.
Referenced by computeError(), and vpServoData::save().
vpServoType vpServo::servoType |
Chosen visual servoing control law.
Definition at line 576 of file vpServo.h.
Referenced by computeControlLaw(), init(), print(), setServo(), testInitialization(), and testUpdated().
int vpServo::signInteractionMatrix |
Sign of the interaction +/- 1 (1 for eye-in-hand, -1 for eye-to-hand configuration)
Definition at line 594 of file vpServo.h.
Referenced by computeControlLaw(), init(), and setServo().
vpColVector vpServo::sStar |
Desired state of visual features . This vector is updated after a call of computeError() or computeControlLaw().
Definition at line 563 of file vpServo.h.
Referenced by computeError(), and vpServoData::save().
|
protected |
Singular values from the pseudo inverse.
Definition at line 668 of file vpServo.h.
Referenced by computeControlLaw().
|
protected |
vpColVector vpServo::v |
|
protected |
Projection operators .
Definition at line 645 of file vpServo.h.
Referenced by computeControlLaw(), getWpW(), and secondaryTask().