Visual Servoing Platform  version 3.6.1 under development (2024-03-18)

#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 Member Functions

 vpServo ()
 
 vpServo (vpServoType servo_type)
 
virtual ~vpServo ()
 
void addFeature (vpBasicFeature &s_cur, vpBasicFeature &s_star, unsigned int select=vpBasicFeature::FEATURE_ALL)
 
void addFeature (vpBasicFeature &s_cur, unsigned int select=vpBasicFeature::FEATURE_ALL)
 
vpColVector computeControlLaw ()
 
vpColVector computeControlLaw (double t)
 
vpColVector computeControlLaw (double t, const vpColVector &e_dot_init)
 
vpColVector computeError ()
 
vpMatrix computeInteractionMatrix ()
 
unsigned int getDimension () const
 
vpColVector getError () const
 
vpMatrix getInteractionMatrix () const
 
vpMatrix getI_WpW () const
 
vpServoType getServoType () const
 
vpMatrix getLargeP () const
 
vpMatrix getTaskJacobian () const
 
vpMatrix getTaskJacobianPseudoInverse () const
 
unsigned int getTaskRank () const
 
vpColVector getTaskSingularValues () const
 
vpMatrix getWpW () const
 
vpVelocityTwistMatrix get_cVe () const
 
vpVelocityTwistMatrix get_cVf () const
 
vpVelocityTwistMatrix get_fVe () const
 
vpMatrix get_eJe () const
 
vpMatrix get_fJe () const
 
double getPseudoInverseThreshold () const
 
void kill ()
 
void print (const vpServo::vpServoPrintType display_level=ALL, std::ostream &os=std::cout)
 
vpColVector secondaryTask (const vpColVector &de2dt, const bool &useLargeProjectionOperator=false)
 
vpColVector secondaryTask (const vpColVector &e2, const vpColVector &de2dt, const bool &useLargeProjectionOperator=false)
 
vpColVector 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)
 
void setCameraDoF (const vpColVector &dof)
 
void setForceInteractionMatrixComputation (bool force_computation)
 
void setInteractionMatrixType (const vpServoIteractionMatrixType &interactionMatrixType, const vpServoInversionType &interactionMatrixInversion=PSEUDO_INVERSE)
 
void setLambda (double c)
 
void setLambda (double gain_at_zero, double gain_at_infinity, double slope_at_zero)
 
void setLambda (const vpAdaptiveGain &l)
 
void setMu (double mu_)
 
void setServo (const vpServoType &servo_type)
 
void set_cVe (const vpVelocityTwistMatrix &cVe_)
 
void set_cVe (const vpHomogeneousMatrix &cMe)
 
void set_cVf (const vpVelocityTwistMatrix &cVf_)
 
void set_cVf (const vpHomogeneousMatrix &cMf)
 
void set_fVe (const vpVelocityTwistMatrix &fVe_)
 
void set_fVe (const vpHomogeneousMatrix &fMe)
 
void set_eJe (const vpMatrix &eJe_)
 
void set_fJe (const vpMatrix &fJe_)
 
void setPseudoInverseThreshold (double pseudo_inverse_threshold)
 
bool testInitialization ()
 
bool testUpdated ()
 

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
 

Detailed Description

Class required to compute the visual servoing control law described in [3] and [4].

Warning
To avoid potential memory leaks, it is mandatory to call explicitly the kill() function to destroy the task. Otherwise, the destructor ~vpServo() launch an exception vpServoException::notKilledProperly.

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 $s=({^{c^*}}t_c,\theta u)$. In that case, we have $s^* = 0$. Let us denote $\theta u$ the angle/axis parametrization of the rotation ${^{c^*}}R_c$. Moreover, $ {^{c^*}}t_c$ and ${^{c^*}}R_c$ represent respectively the translation and the rotation between the desired camera frame and the current one obtained by pose estimation (see vpPose class).

#include <visp3/core/vpColVector.h>
#include <visp3/core/vpHomogeneousMatrix.h>
#include <visp3/core/vpMatrix.h>
#include <visp3/visual_features/vpFeatureThetaU.h>
#include <visp3/visual_features/vpFeatureTranslation.h>
#include <visp3/vs/vpServo.h>
int main()
{
// Creation of an homogeneous matrix that represent the displacement
// the camera has to achieve to move from the desired camera frame
// and the current one
// ... cdMc is here the result of a pose estimation
// Creation of the current visual feature s = (c*_t_c, ThetaU)
// Set the initial values of the current visual feature s = (c*_t_c, ThetaU)
s_t.buildFrom(cdMc);
s_tu.buildFrom(cdMc);
// Build the desired visual feature s* = (0,0)
vpFeatureTranslation s_star_t(vpFeatureTranslation::cdMc); // Default initialization to zero
vpFeatureThetaU s_star_tu(vpFeatureThetaU::cdRc); // Default initialization to zero
vpColVector v; // Camera velocity
double error; // Task error
// Creation of the visual servo task.
vpServo task;
// Visual servo task initialization
// - Camera is mounted on the robot end-effector and velocities are
// computed in the camera frame
// - Interaction matrix is computed with the current visual features s
// - Set the constant gain to 1
task.setLambda(1);
// - Add current and desired translation feature
task.addFeature(s_t, s_star_t);
// - Add current and desired ThetaU feature for the rotation
task.addFeature(s_tu, s_star_tu);
// Visual servoing loop. The objective is here to update the visual
// features s = (c*_t_c, ThetaU), compute the control law and apply
// it to the robot
do {
// ... cdMc is here the result of a pose estimation
// Update the current visual feature s
s_t.buildFrom(cdMc); // Update translation visual feature
s_tu.buildFrom(cdMc); // Update ThetaU visual feature
v = task.computeControlLaw(); // Compute camera velocity skew
error = ( task.getError() ).sumSquare(); // error = s^2 - s_star^2
} while (error > 0.0001); // Stop the task when current and desired visual features are close
}
Implementation of column vector and the associated operations.
Definition: vpColVector.h:163
Class that defines a 3D visual feature from a axis/angle parametrization that represent the rotatio...
Class that defines the translation visual feature .
Implementation of an homogeneous matrix and operations on such kind of matrices.
void setInteractionMatrixType(const vpServoIteractionMatrixType &interactionMatrixType, const vpServoInversionType &interactionMatrixInversion=PSEUDO_INVERSE)
Definition: vpServo.cpp:378
@ EYEINHAND_CAMERA
Definition: vpServo.h:155
void addFeature(vpBasicFeature &s_cur, vpBasicFeature &s_star, unsigned int select=vpBasicFeature::FEATURE_ALL)
Definition: vpServo.cpp:329
void setLambda(double c)
Definition: vpServo.h:976
void setServo(const vpServoType &servo_type)
Definition: vpServo.cpp:132
vpColVector error
Definition: vpServo.h:1159
vpColVector v
Camera velocity.
Definition: vpServo.h:1182
vpColVector getError() const
Definition: vpServo.h:504
vpColVector computeControlLaw()
Definition: vpServo.cpp:703
@ CURRENT
Definition: vpServo.h:196
Examples
manServo4PointsDisplay.cpp, manServoMomentsSimple.cpp, manSimu4Dots.cpp, manSimu4Points.cpp, mbot-apriltag-2D-half-vs.cpp, mbot-apriltag-ibvs.cpp, mbot-apriltag-pbvs.cpp, photometricVisualServoing.cpp, servoAfma4Point2DArtVelocity.cpp, servoAfma4Point2DCamVelocity.cpp, servoAfma4Point2DCamVelocityKalman.cpp, servoAfma62DhalfCamVelocity.cpp, servoAfma6AprilTagIBVS.cpp, servoAfma6AprilTagPBVS.cpp, servoAfma6Cylinder2DCamVelocity.cpp, servoAfma6Cylinder2DCamVelocitySecondaryTask.cpp, servoAfma6Ellipse2DCamVelocity.cpp, servoAfma6FourPoints2DArtVelocity.cpp, servoAfma6FourPoints2DCamVelocityLs_cur.cpp, servoAfma6FourPoints2DCamVelocityLs_des.cpp, servoAfma6Line2DCamVelocity.cpp, servoAfma6MegaposePBVS.cpp, servoAfma6Point2DArtVelocity.cpp, servoAfma6Point2DCamVelocity.cpp, servoAfma6Points2DCamVelocityEyeToHand.cpp, servoAfma6Segment2DCamVelocity.cpp, servoAfma6SquareLines2DCamVelocity.cpp, servoAfma6TwoLines2DCamVelocity.cpp, servoBebop2.cpp, servoBiclopsPoint2DArtVelocity.cpp, servoFlirPtuIBVS.cpp, servoFrankaIBVS.cpp, servoFrankaPBVS.cpp, servoMomentImage.cpp, servoMomentPoints.cpp, servoMomentPolygon.cpp, servoPioneerPanSegment3D.cpp, servoPioneerPoint2DDepth.cpp, servoPololuPtuPoint2DJointVelocity.cpp, servoPtu46Point2DArtVelocity.cpp, servoSimu3D_cMcd_CamVelocity.cpp, servoSimu3D_cdMc_CamVelocity.cpp, servoSimu4Points.cpp, servoSimuAfma6FourPoints2DCamVelocity.cpp, servoSimuCircle2DCamVelocity.cpp, servoSimuCircle2DCamVelocityDisplay.cpp, servoSimuCylinder.cpp, servoSimuCylinder2DCamVelocityDisplay.cpp, servoSimuCylinder2DCamVelocityDisplaySecondaryTask.cpp, servoSimuFourPoints2DCamVelocity.cpp, servoSimuFourPoints2DCamVelocityDisplay.cpp, servoSimuFourPoints2DPolarCamVelocityDisplay.cpp, servoSimuLine2DCamVelocityDisplay.cpp, servoSimuPoint2DCamVelocity1.cpp, servoSimuPoint2DCamVelocity2.cpp, servoSimuPoint2DCamVelocity3.cpp, servoSimuPoint2DhalfCamVelocity1.cpp, servoSimuPoint2DhalfCamVelocity2.cpp, servoSimuPoint2DhalfCamVelocity3.cpp, servoSimuPoint3DCamVelocity.cpp, servoSimuSphere.cpp, servoSimuSphere2DCamVelocity.cpp, servoSimuSphere2DCamVelocityDisplay.cpp, servoSimuSphere2DCamVelocityDisplaySecondaryTask.cpp, servoSimuSquareLine2DCamVelocityDisplay.cpp, servoSimuThetaUCamVelocity.cpp, servoSimuViper850FourPoints2DCamVelocity.cpp, servoUniversalRobotsIBVS.cpp, servoUniversalRobotsPBVS.cpp, servoViper650FourPoints2DArtVelocityLs_cur.cpp, servoViper650FourPoints2DCamVelocityLs_cur-SR300.cpp, servoViper650FourPoints2DCamVelocityLs_cur.cpp, servoViper650Point2DCamVelocity.cpp, servoViper850FourPoints2DArtVelocityLs_cur.cpp, servoViper850FourPoints2DArtVelocityLs_des.cpp, servoViper850FourPoints2DCamVelocityLs_cur.cpp, servoViper850FourPointsKinect.cpp, servoViper850Point2DArtVelocity-jointAvoidance-basic.cpp, servoViper850Point2DArtVelocity-jointAvoidance-gpa.cpp, servoViper850Point2DArtVelocity-jointAvoidance-large.cpp, servoViper850Point2DArtVelocity.cpp, servoViper850Point2DCamVelocity.cpp, servoViper850Point2DCamVelocityKalman.cpp, simulateCircle2DCamVelocity.cpp, simulateFourPoints2DCartesianCamVelocity.cpp, simulateFourPoints2DPolarCamVelocity.cpp, testFeature.cpp, testFeatureSegment.cpp, tutorial-flir-ptu-ibvs.cpp, tutorial-ibvs-4pts-display.cpp, tutorial-ibvs-4pts-image-tracking.cpp, tutorial-ibvs-4pts-json.cpp, tutorial-ibvs-4pts-ogre-tracking.cpp, tutorial-ibvs-4pts-ogre.cpp, tutorial-ibvs-4pts-plotter-continuous-gain-adaptive.cpp, tutorial-ibvs-4pts-plotter-gain-adaptive.cpp, tutorial-ibvs-4pts-plotter.cpp, tutorial-ibvs-4pts-wireframe-camera.cpp, tutorial-ibvs-4pts-wireframe-robot-afma6.cpp, tutorial-ibvs-4pts-wireframe-robot-viper.cpp, tutorial-ibvs-4pts.cpp, tutorial-simu-pioneer-continuous-gain-adaptive.cpp, tutorial-simu-pioneer-continuous-gain-constant.cpp, tutorial-simu-pioneer-pan.cpp, and tutorial-simu-pioneer.cpp.

Definition at line 137 of file vpServo.h.

Member Enumeration Documentation

◆ vpServoInversionType

Choice of the interaction matrix inversion method.

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.

Definition at line 219 of file vpServo.h.

◆ vpServoIteractionMatrixType

Choice of the interaction matrix type used in the visual servoing control law.

Enumerator
CURRENT 

In the control law (see vpServo::vpServoType), uses the interaction matrix ${\widehat {\bf L}}_s $computed using the current features $\bf s$.

DESIRED 

In the control law (see vpServo::vpServoType), uses the interaction matrix ${\widehat {\bf L}}_{s^*} $computed using the desired features ${\bf s}^*$.

MEAN 

In the control law (see vpServo::vpServoType), uses the interaction matrix ${\widehat {\bf L}} = \left({\widehat {\bf L}}_s + {\widehat {\bf L}}_{s^*}\right)/2 $.

USER_DEFINED 

In the control law (see vpServo::vpServoType), uses an interaction matrix set by the user.

Definition at line 189 of file vpServo.h.

◆ vpServoPrintType

Choice of the information to print.

Enumerator
ALL 

Print all the task information.

CONTROLLER 

Print the type of controller law.

ERROR_VECTOR 

Print the error vector $\bf e = (s-s^*)$.

FEATURE_CURRENT 

Print the current features $\bf s$.

FEATURE_DESIRED 

Print the desired features ${\bf s}^*$.

GAIN 

Print the gain $\lambda$.

INTERACTION_MATRIX 

Print the interaction matrix.

MINIMUM 

Same as vpServo::vpServoPrintType::ERROR_VECTOR.

Definition at line 235 of file vpServo.h.

◆ vpServoType

Choice of the visual servoing control law.

Enumerator
NONE 

No control law is specified.

EYEINHAND_CAMERA 

Eye in hand visual servoing with the following control law

\[{\bf v}_c = -\lambda {\widehat {\bf L}}^{+}_{e} {\bf e}\]

where camera velocities are computed.

EYEINHAND_L_cVe_eJe 

Eye in hand visual servoing with the following control law

\[{\dot {\bf q}} = -\lambda \left( {{\widehat {\bf L}}_{e} {^c}{\bf V}_e {^e}{\bf J}_e} \right)^{+} {\bf e}\]

where joint velocities are computed.

EYETOHAND_L_cVe_eJe 

Eye to hand visual servoing with the following control law

\[{\dot {\bf q}} = \lambda \left( {{\widehat {\bf L}}_{e} {^c}{\bf V}_e {^e}{\bf J}_e} \right)^{+} {\bf e}\]

where joint velocities are computed.

EYETOHAND_L_cVf_fVe_eJe 

Eye to hand visual servoing with the following control law

\[{\dot {\bf q}} = \lambda \left( {{\widehat {\bf L}}_{e} {^c}{\bf V}_f {^f}{\bf V}_e {^e}{\bf J}_e} \right)^{+} {\bf e}\]

where joint velocities are computed.

EYETOHAND_L_cVf_fJe 

Eye to hand visual servoing with the following control law

\[{\dot {\bf q}} = \lambda \left( {{\widehat {\bf L}}_{e} {^c}{\bf V}_f {^f}{\bf J}_e} \right)^{+} {\bf e}\]

where joint velocities are computed.

Definition at line 144 of file vpServo.h.

Constructor & Destructor Documentation

◆ vpServo() [1/2]

vpServo::vpServo ( )

Default constructor that initializes the following settings:

  • No control law is specified. The user has to call setServo() to specify the control law.
  • In the control law, the interaction matrix ${\widehat {\bf L}}_e $ is computed with the desired features ${\bf s}^*$. Using setInteractionMatrixType() you can also compute the interaction matrix with the current visual features, or from the mean $\left({\widehat {\bf L}}_s + {\widehat {\bf L}}_{s^*}\right)/2$.
  • In the control law the pseudo inverse will be used. The method setInteractionMatrixType() allows to use the transpose instead.
Warning
By default the threshold used to compute the pseudo-inverse is set to 1e-6. Advanced user can modify this value using setPseudoInverseThreshold().

Definition at line 45 of file vpServo.cpp.

References cJc, and vpMatrix::eye().

◆ vpServo() [2/2]

vpServo::vpServo ( vpServoType  servo_type)
explicit

Constructor that allows to choose the visual servoing control law.

Parameters
servo_type: Visual servoing control law.

The other settings are the following:

  • In the control law, the interaction matrix ${\widehat {\bf L}}_e $ is computed with the desired features ${\bf s}^*$. Using setInteractionMatrixType() you can also compute the interaction matrix with the current visual features, or from the mean $\left({\widehat {\bf L}}_s + {\widehat {\bf L}}_{s^*}\right)/2$.
  • In the control law the pseudo inverse will be used. The method setInteractionMatrixType() allows to use the transpose instead.

Definition at line 57 of file vpServo.cpp.

References cJc, and vpMatrix::eye().

◆ ~vpServo()

vpServo::~vpServo ( )
virtual

Destructor.

Since ViSP > 3.3.0 calls kill() to destroy the current and desired feature lists.

See also
kill()

Definition at line 68 of file vpServo.cpp.

References kill().

Member Function Documentation

◆ addFeature() [1/2]

void vpServo::addFeature ( vpBasicFeature s_cur,
unsigned int  select = vpBasicFeature::FEATURE_ALL 
)

Add a new features $\bf s$ in the task. The desired visual feature denoted ${\bf s}^*$ is equal to zero.

Parameters
s_cur: Current visual feature denoted $\bf s$.
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 $\theta {\bf u} =(\theta u_x, \theta u_y, \theta u_z)$ feature:

...
vpServo task;
task.addFeature(s);
vpColVector s
Definition: vpServo.h:1168

For example to use only the $\theta u_x$ feature, the previous code becomes:

...
vpServo task;
task.addFeature(s, vpFeatureThetaU::selectTUx);
static unsigned int selectTUx()

Definition at line 336 of file vpServo.cpp.

References desiredFeatureList, vpBasicFeature::duplicate(), featureList, featureSelectionList, vpBasicFeature::init(), vpBasicFeature::setDeallocate(), and vpBasicFeature::vpServo.

◆ addFeature() [2/2]

void vpServo::addFeature ( vpBasicFeature s_cur,
vpBasicFeature s_star,
unsigned int  select = vpBasicFeature::FEATURE_ALL 
)

Add a new set of 2 features $\bf s$ and ${\bf s}^*$ in the task.

Parameters
s_cur: Current visual feature denoted $\bf s$.
s_star: Desired visual feature denoted ${\bf s}^*$.
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 $(x,y)$:

vpFeaturePoint s, s_star;
...
vpServo task;
task.addFeature(s, s_star);
Class that defines a 2D point visual feature which is composed by two parameters that are the cartes...

For example to use only the $x$ visual feature, the previous code becomes:

vpFeaturePoint s, s_star;
...
vpServo task;
task.addFeature(s, s_star, vpFeaturePoint::selectX());
static unsigned int selectX()
Examples
manServo4PointsDisplay.cpp, manServoMomentsSimple.cpp, manSimu4Dots.cpp, manSimu4Points.cpp, mbot-apriltag-2D-half-vs.cpp, mbot-apriltag-ibvs.cpp, mbot-apriltag-pbvs.cpp, photometricVisualServoing.cpp, servoAfma4Point2DArtVelocity.cpp, servoAfma4Point2DCamVelocity.cpp, servoAfma4Point2DCamVelocityKalman.cpp, servoAfma62DhalfCamVelocity.cpp, servoAfma6AprilTagIBVS.cpp, servoAfma6AprilTagPBVS.cpp, servoAfma6Cylinder2DCamVelocity.cpp, servoAfma6Cylinder2DCamVelocitySecondaryTask.cpp, servoAfma6Ellipse2DCamVelocity.cpp, servoAfma6FourPoints2DArtVelocity.cpp, servoAfma6FourPoints2DCamVelocityLs_cur.cpp, servoAfma6FourPoints2DCamVelocityLs_des.cpp, servoAfma6Line2DCamVelocity.cpp, servoAfma6MegaposePBVS.cpp, servoAfma6Point2DArtVelocity.cpp, servoAfma6Point2DCamVelocity.cpp, servoAfma6Points2DCamVelocityEyeToHand.cpp, servoAfma6Segment2DCamVelocity.cpp, servoAfma6SquareLines2DCamVelocity.cpp, servoAfma6TwoLines2DCamVelocity.cpp, servoBebop2.cpp, servoBiclopsPoint2DArtVelocity.cpp, servoFlirPtuIBVS.cpp, servoFrankaIBVS.cpp, servoFrankaPBVS.cpp, servoPioneerPanSegment3D.cpp, servoPioneerPoint2DDepth.cpp, servoPololuPtuPoint2DJointVelocity.cpp, servoPtu46Point2DArtVelocity.cpp, servoSimu3D_cMcd_CamVelocity.cpp, servoSimu3D_cdMc_CamVelocity.cpp, servoSimu4Points.cpp, servoSimuAfma6FourPoints2DCamVelocity.cpp, servoSimuCircle2DCamVelocity.cpp, servoSimuCircle2DCamVelocityDisplay.cpp, servoSimuCylinder.cpp, servoSimuCylinder2DCamVelocityDisplay.cpp, servoSimuCylinder2DCamVelocityDisplaySecondaryTask.cpp, servoSimuFourPoints2DCamVelocity.cpp, servoSimuFourPoints2DCamVelocityDisplay.cpp, servoSimuFourPoints2DPolarCamVelocityDisplay.cpp, servoSimuLine2DCamVelocityDisplay.cpp, servoSimuPoint2DCamVelocity1.cpp, servoSimuPoint2DCamVelocity2.cpp, servoSimuPoint2DCamVelocity3.cpp, servoSimuPoint2DhalfCamVelocity1.cpp, servoSimuPoint2DhalfCamVelocity2.cpp, servoSimuPoint2DhalfCamVelocity3.cpp, servoSimuPoint3DCamVelocity.cpp, servoSimuSphere.cpp, servoSimuSphere2DCamVelocity.cpp, servoSimuSphere2DCamVelocityDisplay.cpp, servoSimuSphere2DCamVelocityDisplaySecondaryTask.cpp, servoSimuSquareLine2DCamVelocityDisplay.cpp, servoSimuThetaUCamVelocity.cpp, servoSimuViper850FourPoints2DCamVelocity.cpp, servoUniversalRobotsIBVS.cpp, servoUniversalRobotsPBVS.cpp, servoViper650FourPoints2DArtVelocityLs_cur.cpp, servoViper650FourPoints2DCamVelocityLs_cur-SR300.cpp, servoViper650FourPoints2DCamVelocityLs_cur.cpp, servoViper650Point2DCamVelocity.cpp, servoViper850FourPoints2DArtVelocityLs_cur.cpp, servoViper850FourPoints2DArtVelocityLs_des.cpp, servoViper850FourPoints2DCamVelocityLs_cur.cpp, servoViper850FourPointsKinect.cpp, servoViper850Point2DArtVelocity-jointAvoidance-basic.cpp, servoViper850Point2DArtVelocity-jointAvoidance-gpa.cpp, servoViper850Point2DArtVelocity-jointAvoidance-large.cpp, servoViper850Point2DArtVelocity.cpp, servoViper850Point2DCamVelocity.cpp, servoViper850Point2DCamVelocityKalman.cpp, simulateCircle2DCamVelocity.cpp, simulateFourPoints2DCartesianCamVelocity.cpp, simulateFourPoints2DPolarCamVelocity.cpp, testFeature.cpp, testFeatureSegment.cpp, tutorial-flir-ptu-ibvs.cpp, tutorial-ibvs-4pts-display.cpp, tutorial-ibvs-4pts-image-tracking.cpp, tutorial-ibvs-4pts-json.cpp, tutorial-ibvs-4pts-ogre-tracking.cpp, tutorial-ibvs-4pts-ogre.cpp, tutorial-ibvs-4pts-plotter-continuous-gain-adaptive.cpp, tutorial-ibvs-4pts-plotter-gain-adaptive.cpp, tutorial-ibvs-4pts-plotter.cpp, tutorial-ibvs-4pts-wireframe-camera.cpp, tutorial-ibvs-4pts-wireframe-robot-afma6.cpp, tutorial-ibvs-4pts-wireframe-robot-viper.cpp, tutorial-ibvs-4pts.cpp, tutorial-simu-pioneer-continuous-gain-adaptive.cpp, tutorial-simu-pioneer-continuous-gain-constant.cpp, tutorial-simu-pioneer-pan.cpp, and tutorial-simu-pioneer.cpp.

Definition at line 329 of file vpServo.cpp.

References desiredFeatureList, featureList, and featureSelectionList.

◆ computeControlLaw() [1/3]

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:

\[ {\bf \dot q} = \pm \lambda {{\bf \widehat J}_e}^+ {\bf e} \]

where :

  • ${\bf \dot q}$ is the resulting velocity command to apply to the robot.
  • the sign of the control law depends on the eye in hand or eye to hand configuration.
  • $\bf J$ is the Jacobian of the task. It is function of the interaction matrix and of the robot Jacobian.
  • $\bf e = (s-s^*)$ is the error to regulate.

To ensure continuous sequencing the computeControlLaw(double) function can be used. It will ensure that the velocities that are computed are continuous.

Examples
manServo4PointsDisplay.cpp, manServoMomentsSimple.cpp, manSimu4Dots.cpp, manSimu4Points.cpp, mbot-apriltag-2D-half-vs.cpp, mbot-apriltag-ibvs.cpp, mbot-apriltag-pbvs.cpp, photometricVisualServoing.cpp, servoAfma4Point2DArtVelocity.cpp, servoAfma4Point2DCamVelocity.cpp, servoAfma4Point2DCamVelocityKalman.cpp, servoAfma62DhalfCamVelocity.cpp, servoAfma6AprilTagIBVS.cpp, servoAfma6AprilTagPBVS.cpp, servoAfma6Cylinder2DCamVelocity.cpp, servoAfma6Cylinder2DCamVelocitySecondaryTask.cpp, servoAfma6Ellipse2DCamVelocity.cpp, servoAfma6FourPoints2DArtVelocity.cpp, servoAfma6FourPoints2DCamVelocityLs_cur.cpp, servoAfma6FourPoints2DCamVelocityLs_des.cpp, servoAfma6Line2DCamVelocity.cpp, servoAfma6MegaposePBVS.cpp, servoAfma6Point2DArtVelocity.cpp, servoAfma6Point2DCamVelocity.cpp, servoAfma6Points2DCamVelocityEyeToHand.cpp, servoAfma6Segment2DCamVelocity.cpp, servoAfma6SquareLines2DCamVelocity.cpp, servoAfma6TwoLines2DCamVelocity.cpp, servoBebop2.cpp, servoBiclopsPoint2DArtVelocity.cpp, servoFlirPtuIBVS.cpp, servoFrankaIBVS.cpp, servoFrankaPBVS.cpp, servoPioneerPanSegment3D.cpp, servoPioneerPoint2DDepth.cpp, servoPololuPtuPoint2DJointVelocity.cpp, servoPtu46Point2DArtVelocity.cpp, servoSimu3D_cMcd_CamVelocity.cpp, servoSimu3D_cdMc_CamVelocity.cpp, servoSimu4Points.cpp, servoSimuAfma6FourPoints2DCamVelocity.cpp, servoSimuCircle2DCamVelocity.cpp, servoSimuCircle2DCamVelocityDisplay.cpp, servoSimuCylinder.cpp, servoSimuCylinder2DCamVelocityDisplay.cpp, servoSimuCylinder2DCamVelocityDisplaySecondaryTask.cpp, servoSimuFourPoints2DCamVelocity.cpp, servoSimuFourPoints2DCamVelocityDisplay.cpp, servoSimuFourPoints2DPolarCamVelocityDisplay.cpp, servoSimuLine2DCamVelocityDisplay.cpp, servoSimuPoint2DCamVelocity1.cpp, servoSimuPoint2DCamVelocity2.cpp, servoSimuPoint2DCamVelocity3.cpp, servoSimuPoint2DhalfCamVelocity1.cpp, servoSimuPoint2DhalfCamVelocity2.cpp, servoSimuPoint2DhalfCamVelocity3.cpp, servoSimuPoint3DCamVelocity.cpp, servoSimuSphere.cpp, servoSimuSphere2DCamVelocity.cpp, servoSimuSphere2DCamVelocityDisplay.cpp, servoSimuSphere2DCamVelocityDisplaySecondaryTask.cpp, servoSimuSquareLine2DCamVelocityDisplay.cpp, servoSimuThetaUCamVelocity.cpp, servoSimuViper850FourPoints2DCamVelocity.cpp, servoUniversalRobotsIBVS.cpp, servoUniversalRobotsPBVS.cpp, servoViper650FourPoints2DArtVelocityLs_cur.cpp, servoViper650FourPoints2DCamVelocityLs_cur-SR300.cpp, servoViper650FourPoints2DCamVelocityLs_cur.cpp, servoViper650Point2DCamVelocity.cpp, servoViper850FourPoints2DArtVelocityLs_cur.cpp, servoViper850FourPoints2DArtVelocityLs_des.cpp, servoViper850FourPoints2DCamVelocityLs_cur.cpp, servoViper850FourPointsKinect.cpp, servoViper850Point2DArtVelocity-jointAvoidance-basic.cpp, servoViper850Point2DArtVelocity-jointAvoidance-gpa.cpp, servoViper850Point2DArtVelocity-jointAvoidance-large.cpp, servoViper850Point2DArtVelocity.cpp, servoViper850Point2DCamVelocity.cpp, servoViper850Point2DCamVelocityKalman.cpp, simulateCircle2DCamVelocity.cpp, simulateFourPoints2DCartesianCamVelocity.cpp, simulateFourPoints2DPolarCamVelocity.cpp, testFeatureSegment.cpp, tutorial-flir-ptu-ibvs.cpp, tutorial-ibvs-4pts-display.cpp, tutorial-ibvs-4pts-image-tracking.cpp, tutorial-ibvs-4pts-json.cpp, tutorial-ibvs-4pts-ogre-tracking.cpp, tutorial-ibvs-4pts-ogre.cpp, tutorial-ibvs-4pts-plotter-continuous-gain-adaptive.cpp, tutorial-ibvs-4pts-plotter-gain-adaptive.cpp, tutorial-ibvs-4pts-plotter.cpp, tutorial-ibvs-4pts-wireframe-camera.cpp, tutorial-ibvs-4pts-wireframe-robot-afma6.cpp, tutorial-ibvs-4pts-wireframe-robot-viper.cpp, tutorial-ibvs-4pts.cpp, tutorial-simu-pioneer-continuous-gain-adaptive.cpp, tutorial-simu-pioneer-continuous-gain-constant.cpp, tutorial-simu-pioneer-pan.cpp, and tutorial-simu-pioneer.cpp.

Definition at line 703 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.

◆ computeControlLaw() [2/3]

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:

\[ {\bf \dot q} = \pm \lambda {{\bf \widehat J}_e}^+ {\bf e} \mp \lambda {{\bf \widehat J}_{e(0)}}^+ {{\bf e}(0)} \exp(-\mu t) \]

where :

  • ${\bf \dot q}$ is the resulting continuous velocity command to apply to the robot.
  • the sign of the control law depends on the eye in hand or eye to hand configuration.
  • $\bf J$ is the Jacobian of the task. It is function of the interaction matrix and of the robot Jacobian.
  • $\bf e = (s-s^*)$ is the error to regulate.
  • $t$ is the time given as parameter of this method.
  • $\mu$ is a gain that is set by default to 4 and that could be modified using setMu().
  • ${\bf \widehat J}_{e(0)}^+ {\bf e}(0)$ is the value of ${\bf \widehat J}_e^+ {\bf e}$ when $t=0$. This value is internally stored either at the first call of this method, or when t parameter is set to 0.
Parameters
t: Time in second. When set to zero, ${{\bf \widehat J}_{e(0)}}^+ {{\bf e}(0)}$ is refreshed internally.

Definition at line 815 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.

◆ computeControlLaw() [3/3]

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:

\[ {\bf \dot q} = \pm \lambda {{\bf \widehat J}_e}^+ {\bf e} + \left({\bf \dot e}(0) \mp \lambda {{\bf \widehat J}_{e(0)}}^+ {{\bf e}(0)}\right) \exp(-\mu t) \]

where :

  • ${\bf \dot q}$ is the resulting continuous velocity command to apply to the robot.
  • the sign of the control law depends on the eye in hand or eye to hand configuration.
  • $\bf J$ is the Jacobian of the task. It is function of the interaction matrix and of the robot Jacobian.
  • $\bf e = (s-s^*)$ is the error to regulate.
  • $t$ is the time given as parameter of this method.
  • $\mu$ is a gain that is set by default to 4 and that could be modified using setMu().
  • ${\bf \widehat J}_{e(0)}^+ {\bf e}(0)$ is the value of ${\bf \widehat J}_e^+ {\bf e}$ when $t=0$. This value is internally stored either at the first call of this method, or when t parameter is set to 0.
Parameters
t: Time in second. When set to zero, ${{\bf \widehat J}_{e(0)}}^+ {{\bf e}(0)}$ is refreshed internally.
e_dot_init: Initial value of ${\bf \dot e}(0)$.

Definition at line 935 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.

◆ computeError()

vpColVector vpServo::computeError ( )

Compute the error $\bf e =(s - s^*)$ between the current set of visual features $\bf s$ and the desired set of visual features $\bf s^*$.

Returns
The error vector $\bf e$.

Definition at line 507 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().

◆ computeInteractionMatrix()

vpMatrix vpServo::computeInteractionMatrix ( )

Compute and return the interaction matrix related to the set of visual features.

Returns
The interaction matrix ${\widehat {\bf L}}_e$ used in the control law specified using setServo().

Definition at line 450 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().

◆ computeProjectionOperators()

void vpServo::computeProjectionOperators ( const vpMatrix J1_,
const vpMatrix I_,
const vpMatrix I_WpW_,
const vpColVector error_,
vpMatrix P_ 
) const
protected

Compute the classic projection operator and the large projection operator.

Definition at line 1055 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().

◆ get_cVe()

vpVelocityTwistMatrix vpServo::get_cVe ( ) const
inline

Return the velocity twist matrix used to transform a velocity skew vector from end-effector frame into the camera frame.

Definition at line 630 of file vpServo.h.

◆ get_cVf()

vpVelocityTwistMatrix vpServo::get_cVf ( ) const
inline

Return the velocity twist matrix used to transform a velocity skew vector from robot fixed frame (also called world or base frame) into the camera frame.

Definition at line 636 of file vpServo.h.

◆ get_eJe()

vpMatrix vpServo::get_eJe ( ) const
inline

Return the robot jacobian expressed in the end-effector frame.

Definition at line 648 of file vpServo.h.

◆ get_fJe()

vpMatrix vpServo::get_fJe ( ) const
inline

Return the robot jacobian expressed in the robot fixed frame (also called world or base frame).

Definition at line 654 of file vpServo.h.

◆ get_fVe()

vpVelocityTwistMatrix vpServo::get_fVe ( ) const
inline

Return the velocity twist matrix used to transform a velocity skew vector from robot end-effector frame into the fixed frame (also called world or base frame).

Definition at line 643 of file vpServo.h.

◆ getDimension()

unsigned int vpServo::getDimension ( ) const

Return the task dimension.

Examples
servoSimuCylinder.cpp, and servoSimuSphere.cpp.

Definition at line 364 of file vpServo.cpp.

References featureList, and featureSelectionList.

◆ getError()

vpColVector vpServo::getError ( ) const
inline

Return the error $\bf e = (s - s^*)$ between the current set of visual features $\bf s$ and the desired set of visual features $\bf s^*$. The error vector is updated after a call of computeError() or computeControlLaw().

vpServo task;
...
vpColVector v = task.computeControlLaw(); // Compute the velocity corresponding to the visual servoing
vpColVector e = task.getError(); // Get the error vector
vpColVector e
Task .
Definition: vpServo.h:1177
Examples
manServoMomentsSimple.cpp, photometricVisualServoing.cpp, servoAfma4Point2DArtVelocity.cpp, servoAfma4Point2DCamVelocity.cpp, servoAfma62DhalfCamVelocity.cpp, servoAfma6AprilTagIBVS.cpp, servoAfma6AprilTagPBVS.cpp, servoAfma6Cylinder2DCamVelocity.cpp, servoAfma6Cylinder2DCamVelocitySecondaryTask.cpp, servoAfma6Ellipse2DCamVelocity.cpp, servoAfma6FourPoints2DArtVelocity.cpp, servoAfma6FourPoints2DCamVelocityLs_cur.cpp, servoAfma6FourPoints2DCamVelocityLs_des.cpp, servoAfma6Line2DCamVelocity.cpp, servoAfma6MegaposePBVS.cpp, servoAfma6Point2DArtVelocity.cpp, servoAfma6Point2DCamVelocity.cpp, servoAfma6Points2DCamVelocityEyeToHand.cpp, servoAfma6Segment2DCamVelocity.cpp, servoAfma6SquareLines2DCamVelocity.cpp, servoAfma6TwoLines2DCamVelocity.cpp, servoBebop2.cpp, servoBiclopsPoint2DArtVelocity.cpp, servoFlirPtuIBVS.cpp, servoFrankaIBVS.cpp, servoFrankaPBVS.cpp, servoPioneerPanSegment3D.cpp, servoPololuPtuPoint2DJointVelocity.cpp, servoPtu46Point2DArtVelocity.cpp, servoSimu3D_cMcd_CamVelocity.cpp, servoSimu3D_cdMc_CamVelocity.cpp, servoSimu4Points.cpp, servoSimuAfma6FourPoints2DCamVelocity.cpp, servoSimuCircle2DCamVelocity.cpp, servoSimuCircle2DCamVelocityDisplay.cpp, servoSimuCylinder.cpp, servoSimuCylinder2DCamVelocityDisplay.cpp, servoSimuCylinder2DCamVelocityDisplaySecondaryTask.cpp, servoSimuFourPoints2DCamVelocity.cpp, servoSimuFourPoints2DCamVelocityDisplay.cpp, servoSimuFourPoints2DPolarCamVelocityDisplay.cpp, servoSimuLine2DCamVelocityDisplay.cpp, servoSimuPoint2DCamVelocity1.cpp, servoSimuPoint2DCamVelocity2.cpp, servoSimuPoint2DCamVelocity3.cpp, servoSimuPoint2DhalfCamVelocity1.cpp, servoSimuPoint2DhalfCamVelocity2.cpp, servoSimuPoint2DhalfCamVelocity3.cpp, servoSimuPoint3DCamVelocity.cpp, servoSimuSphere.cpp, servoSimuSphere2DCamVelocity.cpp, servoSimuSphere2DCamVelocityDisplay.cpp, servoSimuSphere2DCamVelocityDisplaySecondaryTask.cpp, servoSimuSquareLine2DCamVelocityDisplay.cpp, servoSimuThetaUCamVelocity.cpp, servoSimuViper850FourPoints2DCamVelocity.cpp, servoUniversalRobotsIBVS.cpp, servoUniversalRobotsPBVS.cpp, servoViper650FourPoints2DArtVelocityLs_cur.cpp, servoViper650FourPoints2DCamVelocityLs_cur-SR300.cpp, servoViper650FourPoints2DCamVelocityLs_cur.cpp, servoViper650Point2DCamVelocity.cpp, servoViper850FourPoints2DArtVelocityLs_cur.cpp, servoViper850FourPoints2DArtVelocityLs_des.cpp, servoViper850FourPoints2DCamVelocityLs_cur.cpp, servoViper850FourPointsKinect.cpp, servoViper850Point2DArtVelocity.cpp, servoViper850Point2DCamVelocity.cpp, servoViper850Point2DCamVelocityKalman.cpp, testFeatureSegment.cpp, tutorial-ibvs-4pts-json.cpp, tutorial-ibvs-4pts-plotter-continuous-gain-adaptive.cpp, tutorial-ibvs-4pts-plotter-gain-adaptive.cpp, tutorial-ibvs-4pts-plotter.cpp, tutorial-simu-pioneer-continuous-gain-adaptive.cpp, tutorial-simu-pioneer-continuous-gain-constant.cpp, tutorial-simu-pioneer-pan.cpp, and tutorial-simu-pioneer.cpp.

Definition at line 504 of file vpServo.h.

Referenced by vpServoData::save().

◆ getI_WpW()

vpMatrix vpServo::getI_WpW ( ) const
inline

Return the projection operator ${\bf I}-{\bf W}^+{\bf W}$. This operator is updated after a call of computeControlLaw().

vpServo task;
...
vpColVector v = task.computeControlLaw(); // Compute the velocity corresponding to the visual servoing
vpMatrix I_WpW = task.getI_WpW(); // Get the projection operator
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:146
vpMatrix getI_WpW() const
Definition: vpServo.h:533
vpMatrix I_WpW
Projection operators .
Definition: vpServo.h:1287
See also
getWpW()

Definition at line 533 of file vpServo.h.

◆ getInteractionMatrix()

vpMatrix vpServo::getInteractionMatrix ( ) const
inline

Return the interaction matrix $L$ used to compute the task jacobian $J_1$. The interaction matrix is updated after a call to computeInteractionMatrix() or computeControlLaw().

vpServo task;
...
vpColVector v = task.computeControlLaw(); // Compute the velocity corresponding to the visual servoing vpMatrix
L = task.getInteractionMatrix(); // Get the interaction matrix used to compute v
vpMatrix getInteractionMatrix() const
Definition: vpServo.h:519
vpMatrix L
Interaction matrix.
Definition: vpServo.h:1154
See also
getTaskJacobian()
Examples
tutorial-ibvs-4pts-json.cpp.

Definition at line 519 of file vpServo.h.

◆ getLargeP()

vpMatrix vpServo::getLargeP ( ) const
inline

Return the large projection operator. This operator is updated after a call of computeControlLaw().

vpServo task;
...
vpColVector v = task.computeControlLaw(); // Compute the velocity corresponding to the visual servoing
vpMatrix P = task.getP(); // Get the large projection operator
vpMatrix P
Definition: vpServo.h:1304
See also
getP()

Definition at line 552 of file vpServo.h.

◆ getPseudoInverseThreshold()

double vpServo::getPseudoInverseThreshold ( ) const
inline

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.

See also
setPseudoInverseThreshold()

Definition at line 663 of file vpServo.h.

◆ getServoType()

vpServoType vpServo::getServoType ( ) const
inline

Return the visual servo type.

Definition at line 538 of file vpServo.h.

◆ getTaskJacobian()

vpMatrix vpServo::getTaskJacobian ( ) const
inline

Return the task jacobian $J$. The task jacobian is updated after a call of computeControlLaw().

In the general case, the task jacobian is given by ${\bf J} = {\widehat {\bf L}} {^c}{\bf V}_a {^a}{\bf J}_e$.

vpServo task;
...
vpColVector v = task.computeControlLaw(); // Compute the velocity corresponding to the visual servoing vpMatrix
J = task.getTaskJacobian(); // Get the task jacobian used to compute v
vpMatrix getTaskJacobian() const
Definition: vpServo.h:568
See also
getTaskJacobianPseudoInverse(), getInteractionMatrix()
Examples
servoViper850Point2DArtVelocity-jointAvoidance-basic.cpp, and servoViper850Point2DCamVelocityKalman.cpp.

Definition at line 568 of file vpServo.h.

◆ getTaskJacobianPseudoInverse()

vpMatrix vpServo::getTaskJacobianPseudoInverse ( ) const
inline

Return the pseudo inverse of the task jacobian $J$.

In the general case, the task jacobian is given by ${\bf J} = {\widehat {\bf L}} {^c}{\bf V}_a {^a}{\bf J}_e$.

The task jacobian and its pseudo inverse are updated after a call of computeControlLaw().

Returns
Pseudo inverse ${J}^{+}$ of the task jacobian.
vpServo task;
...
vpColVector v = task.computeControlLaw(); // Compute the velocity corresponding to the visual servoing
vpMatrix Jp = task.getTaskJacobianPseudoInverse(); // Get the pseudo inverse of task jacobian used to compute v
vpMatrix getTaskJacobianPseudoInverse() const
Definition: vpServo.h:588
See also
getTaskJacobian()
Examples
servoAfma4Point2DCamVelocityKalman.cpp, and servoViper850Point2DCamVelocityKalman.cpp.

Definition at line 588 of file vpServo.h.

◆ getTaskRank()

unsigned int vpServo::getTaskRank ( ) const
inline

Return the rank of the task jacobian. The rank is updated after a call of computeControlLaw().

vpServo task;
...
vpColVector v = task.computeControlLaw(); // Compute the velocity corresponding to the visual servoing
unsigned int rank = task.getTaskRank(); // Get the rank of the task jacobian
unsigned int getTaskRank() const
Definition: vpServo.h:600
Examples
servoAfma6Ellipse2DCamVelocity.cpp, servoPioneerPanSegment3D.cpp, servoSimuCircle2DCamVelocity.cpp, servoSimuCircle2DCamVelocityDisplay.cpp, servoSimuSphere2DCamVelocity.cpp, servoSimuSphere2DCamVelocityDisplay.cpp, and simulateCircle2DCamVelocity.cpp.

Definition at line 600 of file vpServo.h.

◆ getTaskSingularValues()

vpColVector vpServo::getTaskSingularValues ( ) const
inline

Get task singular values.

Returns
Singular values that relies on the task jacobian pseudo inverse.

Definition at line 607 of file vpServo.h.

◆ getWpW()

vpMatrix vpServo::getWpW ( ) const
inline

Return the projection operator ${\bf W}^+{\bf W}$. 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 ${\bf W^+W = I}$.

vpServo task;
...
vpColVector v = task.computeControlLaw(); // Compute the velocity corresponding to the visual servoing
vpMatrix WpW = task.getWpW(); // Get the projection operator
vpMatrix WpW
Projection operators .
Definition: vpServo.h:1285
vpMatrix getWpW() const
Definition: vpServo.h:624
See also
getI_WpW()

Definition at line 624 of file vpServo.h.

◆ init()

void vpServo::init ( void  )
protected

Initialize the servo with the following settings:

  • No control law is specified. The user has to call setServo() to specify the control law.
  • In the control law, the interaction matrix ${\widehat {\bf L}}_e $ is computed with the desired features ${\bf s}^*$. Using setInteractionMatrixType() you can also compute the interaction matrix with the current visual features, or from the mean $\left({\widehat {\bf L}}_s + {\widehat {\bf L}}_{s^*}\right)/2$.
  • In the control law the pseudo inverse will be used. The method setInteractionMatrixType() allows to use the transpose instead.

Definition at line 70 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.

◆ kill()

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().

vpServo task ;
...
task.addFeature(s); // Add current ThetaU feature
task.kill(); // This call is no more mandatory since achieved in the destructor
void kill()
Definition: vpServo.cpp:106

Definition at line 106 of file vpServo.cpp.

References desiredFeatureList, featureList, taskWasKilled, and vpBasicFeature::vpServo.

Referenced by ~vpServo().

◆ print()

void vpServo::print ( const vpServo::vpServoPrintType  display_level = ALL,
std::ostream &  os = std::cout 
)

Prints on os stream information about the task:

Parameters
display_level: Indicates which are the task information to print. See vpServo::vpServoPrintType for more details.
os: Output stream.
Examples
manServo4PointsDisplay.cpp, manServoMomentsSimple.cpp, manSimu4Dots.cpp, manSimu4Points.cpp, mbot-apriltag-2D-half-vs.cpp, mbot-apriltag-ibvs.cpp, mbot-apriltag-pbvs.cpp, servoAfma4Point2DArtVelocity.cpp, servoAfma4Point2DCamVelocity.cpp, servoAfma4Point2DCamVelocityKalman.cpp, servoAfma62DhalfCamVelocity.cpp, servoAfma6Cylinder2DCamVelocity.cpp, servoAfma6Cylinder2DCamVelocitySecondaryTask.cpp, servoAfma6Ellipse2DCamVelocity.cpp, servoAfma6FourPoints2DArtVelocity.cpp, servoAfma6FourPoints2DCamVelocityLs_cur.cpp, servoAfma6FourPoints2DCamVelocityLs_des.cpp, servoAfma6Line2DCamVelocity.cpp, servoAfma6Point2DArtVelocity.cpp, servoAfma6Point2DCamVelocity.cpp, servoAfma6Points2DCamVelocityEyeToHand.cpp, servoAfma6Segment2DCamVelocity.cpp, servoAfma6SquareLines2DCamVelocity.cpp, servoAfma6TwoLines2DCamVelocity.cpp, servoPioneerPanSegment3D.cpp, servoPioneerPoint2DDepth.cpp, servoPtu46Point2DArtVelocity.cpp, servoSimu3D_cMcd_CamVelocity.cpp, servoSimu3D_cdMc_CamVelocity.cpp, servoSimu4Points.cpp, servoSimuAfma6FourPoints2DCamVelocity.cpp, servoSimuCircle2DCamVelocity.cpp, servoSimuCircle2DCamVelocityDisplay.cpp, servoSimuCylinder.cpp, servoSimuCylinder2DCamVelocityDisplay.cpp, servoSimuCylinder2DCamVelocityDisplaySecondaryTask.cpp, servoSimuFourPoints2DCamVelocity.cpp, servoSimuFourPoints2DCamVelocityDisplay.cpp, servoSimuFourPoints2DPolarCamVelocityDisplay.cpp, servoSimuLine2DCamVelocityDisplay.cpp, servoSimuPoint2DCamVelocity1.cpp, servoSimuPoint2DCamVelocity2.cpp, servoSimuPoint2DCamVelocity3.cpp, servoSimuPoint2DhalfCamVelocity1.cpp, servoSimuPoint2DhalfCamVelocity2.cpp, servoSimuPoint2DhalfCamVelocity3.cpp, servoSimuPoint3DCamVelocity.cpp, servoSimuSphere.cpp, servoSimuSphere2DCamVelocity.cpp, servoSimuSphere2DCamVelocityDisplay.cpp, servoSimuSphere2DCamVelocityDisplaySecondaryTask.cpp, servoSimuSquareLine2DCamVelocityDisplay.cpp, servoSimuThetaUCamVelocity.cpp, servoSimuViper850FourPoints2DCamVelocity.cpp, servoViper650FourPoints2DArtVelocityLs_cur.cpp, servoViper650FourPoints2DCamVelocityLs_cur-SR300.cpp, servoViper650FourPoints2DCamVelocityLs_cur.cpp, servoViper650Point2DCamVelocity.cpp, servoViper850FourPoints2DArtVelocityLs_cur.cpp, servoViper850FourPoints2DArtVelocityLs_des.cpp, servoViper850FourPoints2DCamVelocityLs_cur.cpp, servoViper850FourPointsKinect.cpp, servoViper850Point2DArtVelocity-jointAvoidance-basic.cpp, servoViper850Point2DArtVelocity-jointAvoidance-gpa.cpp, servoViper850Point2DArtVelocity-jointAvoidance-large.cpp, servoViper850Point2DArtVelocity.cpp, servoViper850Point2DCamVelocity.cpp, servoViper850Point2DCamVelocityKalman.cpp, simulateCircle2DCamVelocity.cpp, simulateFourPoints2DCartesianCamVelocity.cpp, simulateFourPoints2DPolarCamVelocity.cpp, tutorial-simu-pioneer-continuous-gain-adaptive.cpp, tutorial-simu-pioneer-continuous-gain-constant.cpp, tutorial-simu-pioneer-pan.cpp, and tutorial-simu-pioneer.cpp.

Definition at line 169 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().

◆ secondaryTask() [1/2]

vpColVector vpServo::secondaryTask ( const vpColVector de2dt,
const bool &  useLargeProjectionOperator = false 
)

Compute and return the secondary task vector according to the classic projection operator ${\bf I-W^+W}$ (see equation(7) in the paper [33]) or the new large projection operator (see equation(24) in the paper [35]).

Parameters
de2dt: Value of $\frac{\partial {\bf e_2}}{\partial t}$ the derivative of the secondary task ${\bf e}_2$.
useLargeProjectionOperator: if true will be use the large projection operator, if false the classic one (default).
Returns
The secondary task vector.

If the classic projection operator is used ( useLargeProjectionOperator = false (default value)) this function return:

\[ ({\bf I-W^+W})\frac{\partial {\bf e_2}}{\partial t} \]

Note that the secondary task vector need than to be added to the primary task which can be in the general case written as:

\[ -\lambda {\bf W^+W {\widehat {\bf J}}_e^+({\bf s-s^*})} \]

Otherwise if the new large projection operator is used ( useLargeProjectionOperator = true ) this function return:

\[ {\bf P}\frac{\partial {\bf e_2}}{\partial t} \]

where

\[ {\bf P} =\bar{\lambda }\left ( \left \| {\bf e} \right \| \right ){\bf P}_{ \left \| {\bf e } \right \| } \left ( 1 - \bar{\lambda }\left ( \left \| {\bf e } \right \| \right ) \right ) \left ( {\bf I-W^+W}\right ) \]

with

\[ {\bf P}_{\left \| {\bf e } \right \| } = I_{n} - \frac{1}{{\bf e }^\top {\bf J_{{\bf e }} } {\bf J_{{\bf e }}^\top }{\bf e }}{\bf J_{{\bf e }}^\top }{\bf e }{\bf e }^\top{\bf J_{{\bf e }} } \]

Warning
computeControlLaw() must be call prior to this function since it updates the projection operators.

The following sample code shows how to use this method to compute a secondary task using the classic projection operator:

// Velocity applied to the robot vpColVector de2dt; vpServo task;
...
v = task.computeControlLaw(); // Compute the primary task
v += task.secondaryTask(de2dt) // Compute and add the 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:

// Velocity applied to the robot vpColVector de2dt; vpServo task;
...
v = task.computeControlLaw(); // Compute the primary task
v += task.secondaryTask(de2dt, true) // Compute and add the secondary task using the large projection operator
See also
computeControlLaw()
Examples
servoAfma6Cylinder2DCamVelocitySecondaryTask.cpp, servoSimuCylinder.cpp, servoSimuCylinder2DCamVelocityDisplaySecondaryTask.cpp, servoSimuSphere2DCamVelocityDisplaySecondaryTask.cpp, and servoViper850Point2DArtVelocity-jointAvoidance-gpa.cpp.

Definition at line 1087 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.

◆ secondaryTask() [2/2]

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 ${\bf I-W^+W}$ (see equation(7) in the paper [33]) or the new large projection operator (see equation(24) in the paper [35]).

Parameters
e2: Value of the secondary task ${\bf e}_2$.
de2dt: Value of $\frac{\partial {\bf e_2}}{\partial t}$ the derivative of the secondary task ${\bf e}_2$.
useLargeProjectionOperatorif true will be use the large projection operator, if false the classic one (default).
Returns
The secondary task vector.

If the classic projection operator is used ( useLargeProjectionOperator = false (default value)) this function return:

\[ -\lambda ({\bf I-W^+W}) {\bf e_2} + ({\bf I-W^+W})\frac{\partial {\bf e_2}}{\partial t} \]

Note that the secondary task vector need than to be added to the primary task which can be in the general case written as:

\[ -\lambda {\bf W^+W {\widehat {\bf J}}_e^+({\bf s-s^*})} \]

Otherwise if the new large projection operator is used ( useLargeProjectionOperator = true ) this function return:

\[ -\lambda {\bf P} {\bf e_2} + {\bf P}\frac{\partial {\bf e_2}}{\partial t} \]

where

\[ {\bf P} =\bar{\lambda }\left ( \left \| {\bf e} \right \| \right ){\bf P}_{ \left \| {\bf e } \right \| } \left ( 1 - \bar{\lambda }\left ( \left \| {\bf e } \right \| \right ) \right ) \left ( {\bf I-W^+W}\right ) \]

with

\[ {\bf P}_{\left \| {\bf e } \right \| } = I_{n} - \frac{1}{{\bf e }^\top {\bf J_{{\bf e }} } {\bf J_{{\bf e }}^\top }{\bf e }}{\bf J_{{\bf e }}^\top }{\bf e }{\bf e }^\top{\bf J_{{\bf e }} } \]

Warning
computeControlLaw() must be call prior to this function since it updates the projection operators.

The following sample code shows how to use this method to compute a secondary task using the classical projection operator:

// Velocity applied to the robot vpColVector e2; vpColVector de2dt; vpServo
task;
...
v = task.computeControlLaw(); // Compute the primary task
v += task.secondaryTask(e2, de2dt) // Compute and add the 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:

// Velocity applied to the robot vpColVector e2; vpColVector de2dt; vpServo
task;
...
v = task.computeControlLaw(); // Compute the primary task
v += task.secondaryTask(e2, de2dt, true) // Compute and add the secondary task using the large projection operator
See also
computeControlLaw()

Definition at line 1119 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.

◆ secondaryTaskJointLimitAvoidance()

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.

Parameters
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 parameter ${\left [ 0,\frac{1}{2} \right]}$ used to define the safe configuration for the joint. When the joint angle value cross the max or min boundaries ( ${ q_{l_{0}}^{max} }$ and ${q_{l_{0}}^{min}}$) the secondary task is activated gradually.
rho1: tuning parameter ${\left ] 0,1 \right ]}$ to compute the external boundaries ( ${q_{l_{1}}^{max}}$ and ${q_{l_{1}}^{min}}$) for the joint limits. Here the secondary task it completely activated with the highest gain.
lambda_tune: value ${\left [ 0,1 \right ]}$ 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] )
vpServo task;
// Fill vector qmin and qmax with min and max limits of the joints (same joint order than vector q).
// Update vector of joint position q and velocities dq;
...
// Compute the velocity corresponding to the visual servoing
// Compute and add the secondary task for the joint limit avoidance
// using the large projection operator
v += task.secondaryTaskJointLimitAvoidance(q, dq, qmin, qmax)
vpColVector 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)
Definition: vpServo.cpp:1155
Examples
servoViper850Point2DArtVelocity-jointAvoidance-large.cpp.

Definition at line 1155 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.

◆ set_cVe() [1/2]

void vpServo::set_cVe ( const vpHomogeneousMatrix cMe)
inline

Set the velocity twist matrix used to transform a velocity skew vector from end-effector frame into the camera frame.

Definition at line 1038 of file vpServo.h.

◆ set_cVe() [2/2]

void vpServo::set_cVe ( const vpVelocityTwistMatrix cVe_)
inline

Set the velocity twist matrix used to transform a velocity skew vector from end-effector frame into the camera frame.

Examples
manServo4PointsDisplay.cpp, manSimu4Dots.cpp, manSimu4Points.cpp, mbot-apriltag-2D-half-vs.cpp, mbot-apriltag-ibvs.cpp, mbot-apriltag-pbvs.cpp, servoAfma4Point2DArtVelocity.cpp, servoAfma6FourPoints2DArtVelocity.cpp, servoAfma6Point2DArtVelocity.cpp, servoAfma6Points2DCamVelocityEyeToHand.cpp, servoBebop2.cpp, servoBiclopsPoint2DArtVelocity.cpp, servoFlirPtuIBVS.cpp, servoPioneerPanSegment3D.cpp, servoPioneerPoint2DDepth.cpp, servoPololuPtuPoint2DJointVelocity.cpp, servoPtu46Point2DArtVelocity.cpp, servoSimu4Points.cpp, servoSimuCylinder.cpp, servoSimuFourPoints2DCamVelocity.cpp, servoSimuFourPoints2DCamVelocityDisplay.cpp, servoSimuFourPoints2DPolarCamVelocityDisplay.cpp, servoSimuPoint2DCamVelocity2.cpp, servoSimuPoint2DCamVelocity3.cpp, servoSimuSphere.cpp, servoViper650FourPoints2DArtVelocityLs_cur.cpp, servoViper850FourPoints2DArtVelocityLs_cur.cpp, servoViper850FourPoints2DArtVelocityLs_des.cpp, servoViper850Point2DArtVelocity-jointAvoidance-basic.cpp, servoViper850Point2DArtVelocity-jointAvoidance-gpa.cpp, servoViper850Point2DArtVelocity-jointAvoidance-large.cpp, servoViper850Point2DArtVelocity.cpp, simulateFourPoints2DCartesianCamVelocity.cpp, simulateFourPoints2DPolarCamVelocity.cpp, tutorial-flir-ptu-ibvs.cpp, tutorial-simu-pioneer-continuous-gain-adaptive.cpp, tutorial-simu-pioneer-continuous-gain-constant.cpp, tutorial-simu-pioneer-pan.cpp, and tutorial-simu-pioneer.cpp.

Definition at line 1028 of file vpServo.h.

Referenced by setServo().

◆ set_cVf() [1/2]

void vpServo::set_cVf ( const vpHomogeneousMatrix cMf)
inline

Set the velocity twist matrix used to transform a velocity skew vector from robot fixed frame (also called world or base frame) into the camera frame.

Definition at line 1060 of file vpServo.h.

◆ set_cVf() [2/2]

void vpServo::set_cVf ( const vpVelocityTwistMatrix cVf_)
inline

Set the velocity twist matrix used to transform a velocity skew vector from robot fixed frame (also called world or base frame) into the camera frame.

Definition at line 1049 of file vpServo.h.

◆ set_eJe()

void vpServo::set_eJe ( const vpMatrix eJe_)
inline

Set the robot jacobian expressed in the end-effector frame.

Examples
manServo4PointsDisplay.cpp, manSimu4Dots.cpp, manSimu4Points.cpp, mbot-apriltag-2D-half-vs.cpp, mbot-apriltag-ibvs.cpp, mbot-apriltag-pbvs.cpp, servoAfma4Point2DArtVelocity.cpp, servoAfma6FourPoints2DArtVelocity.cpp, servoAfma6Point2DArtVelocity.cpp, servoAfma6Points2DCamVelocityEyeToHand.cpp, servoBebop2.cpp, servoBiclopsPoint2DArtVelocity.cpp, servoFlirPtuIBVS.cpp, servoPioneerPanSegment3D.cpp, servoPioneerPoint2DDepth.cpp, servoPololuPtuPoint2DJointVelocity.cpp, servoPtu46Point2DArtVelocity.cpp, servoSimu4Points.cpp, servoSimuCylinder.cpp, servoSimuFourPoints2DCamVelocity.cpp, servoSimuFourPoints2DCamVelocityDisplay.cpp, servoSimuFourPoints2DPolarCamVelocityDisplay.cpp, servoSimuPoint2DCamVelocity2.cpp, servoSimuPoint2DCamVelocity3.cpp, servoSimuSphere.cpp, servoViper650FourPoints2DArtVelocityLs_cur.cpp, servoViper850FourPoints2DArtVelocityLs_cur.cpp, servoViper850FourPoints2DArtVelocityLs_des.cpp, servoViper850Point2DArtVelocity-jointAvoidance-basic.cpp, servoViper850Point2DArtVelocity-jointAvoidance-gpa.cpp, servoViper850Point2DArtVelocity-jointAvoidance-large.cpp, servoViper850Point2DArtVelocity.cpp, simulateFourPoints2DCartesianCamVelocity.cpp, simulateFourPoints2DPolarCamVelocity.cpp, tutorial-flir-ptu-ibvs.cpp, tutorial-simu-pioneer-continuous-gain-adaptive.cpp, tutorial-simu-pioneer-continuous-gain-constant.cpp, tutorial-simu-pioneer-pan.cpp, and tutorial-simu-pioneer.cpp.

Definition at line 1091 of file vpServo.h.

Referenced by setServo().

◆ set_fJe()

void vpServo::set_fJe ( const vpMatrix fJe_)
inline

Set the robot jacobian expressed in the robot fixed frame (also called world or base frame).

Definition at line 1101 of file vpServo.h.

◆ set_fVe() [1/2]

void vpServo::set_fVe ( const vpHomogeneousMatrix fMe)
inline

Set the velocity twist matrix used to transform a velocity skew vector from robot end-effector frame into the fixed frame (also called world or base frame).

Definition at line 1082 of file vpServo.h.

◆ set_fVe() [2/2]

void vpServo::set_fVe ( const vpVelocityTwistMatrix fVe_)
inline

Set the velocity twist matrix used to transform a velocity skew vector from robot end-effector frame into the fixed frame (also called world or base frame).

Definition at line 1071 of file vpServo.h.

◆ setCameraDoF()

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.

Parameters
dof: Degrees of freedom to control in the camera frame. Below we give the correspondence between the index of the vector and the considered dof:
  • dof[0] = 1 if translation along X is controled, 0 otherwise;
  • dof[1] = 1 if translation along Y is controled, 0 otherwise;
  • dof[2] = 1 if translation along Z is controled, 0 otherwise;
  • dof[3] = 1 if rotation along X is controled, 0 otherwise;
  • dof[4] = 1 if rotation along Y is controled, 0 otherwise;
  • dof[5] = 1 if rotation along Z is controled, 0 otherwise;

The following example shows how to use this function to control only wx, wy like a pan/tilt:

#include <visp3/visual_features/vpFeaturePoint.h>
#include <visp3/vs/vpServo.h>
int main()
{
vpServo servo;
servo.addFeature(s, sd);
vpColVector dof(6, 1);
dof[0] = 0; // turn off vx
dof[1] = 0; // turn off vy
dof[2] = 0; // turn off vz
dof[5] = 0; // turn off wz
servo.setCameraDoF(dof);
while(1) {
// vpFeatureBuilder::create(s, ...); // update current feature
vpColVector v = servo.computeControlLaw(); // compute control law
// only v[3] and v[4] corresponding to wx and wy are different from 0
}
}
void setCameraDoF(const vpColVector &dof)
Definition: vpServo.cpp:153

Definition at line 153 of file vpServo.cpp.

References cJc, iscJcIdentity, and vpArray2D< Type >::size().

◆ setForceInteractionMatrixComputation()

void vpServo::setForceInteractionMatrixComputation ( bool  force_computation)
inline

Set a variable which enables to compute the interaction matrix at each iteration.

When the interaction matrix is computed from the desired features ${\bf s}^*$ which are in general constant, the interaction matrix ${\widehat {\bf L}}_{s^*}$ is computed just at the first iteration of the servo loop. Sometimes, when the desired features are time dependent ${{\bf s}(t)}^*$ or varying, the interaction matrix need to be computed at each iteration of the servo loop. This method allows to force the computation of ${\widehat {\bf L}}$ in this particular case.

Parameters
force_computation: If true it forces the interaction matrix computation even if it is already done.

Definition at line 949 of file vpServo.h.

◆ setInteractionMatrixType()

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.

Parameters
interactionMatrixType: The interaction matrix type. See vpServo::vpServoIteractionMatrixType for more details.
interactionMatrixInversion: How is the inverse computed. See vpServo::vpServoInversionType for more details.
Examples
manServo4PointsDisplay.cpp, manServoMomentsSimple.cpp, manSimu4Dots.cpp, manSimu4Points.cpp, mbot-apriltag-2D-half-vs.cpp, mbot-apriltag-ibvs.cpp, mbot-apriltag-pbvs.cpp, photometricVisualServoing.cpp, servoAfma4Point2DArtVelocity.cpp, servoAfma62DhalfCamVelocity.cpp, servoAfma6AprilTagIBVS.cpp, servoAfma6AprilTagPBVS.cpp, servoAfma6Cylinder2DCamVelocity.cpp, servoAfma6Cylinder2DCamVelocitySecondaryTask.cpp, servoAfma6Ellipse2DCamVelocity.cpp, servoAfma6FourPoints2DArtVelocity.cpp, servoAfma6FourPoints2DCamVelocityLs_cur.cpp, servoAfma6FourPoints2DCamVelocityLs_des.cpp, servoAfma6MegaposePBVS.cpp, servoAfma6Point2DArtVelocity.cpp, servoAfma6Points2DCamVelocityEyeToHand.cpp, servoAfma6Segment2DCamVelocity.cpp, servoAfma6SquareLines2DCamVelocity.cpp, servoBebop2.cpp, servoBiclopsPoint2DArtVelocity.cpp, servoFlirPtuIBVS.cpp, servoFrankaIBVS.cpp, servoFrankaPBVS.cpp, servoPioneerPanSegment3D.cpp, servoPioneerPoint2DDepth.cpp, servoPololuPtuPoint2DJointVelocity.cpp, servoPtu46Point2DArtVelocity.cpp, servoSimu3D_cMcd_CamVelocity.cpp, servoSimu3D_cdMc_CamVelocity.cpp, servoSimu4Points.cpp, servoSimuAfma6FourPoints2DCamVelocity.cpp, servoSimuCircle2DCamVelocityDisplay.cpp, servoSimuCylinder.cpp, servoSimuCylinder2DCamVelocityDisplay.cpp, servoSimuCylinder2DCamVelocityDisplaySecondaryTask.cpp, servoSimuFourPoints2DCamVelocity.cpp, servoSimuFourPoints2DCamVelocityDisplay.cpp, servoSimuFourPoints2DPolarCamVelocityDisplay.cpp, servoSimuPoint2DCamVelocity2.cpp, servoSimuPoint2DhalfCamVelocity2.cpp, servoSimuPoint2DhalfCamVelocity3.cpp, servoSimuSphere.cpp, servoSimuSquareLine2DCamVelocityDisplay.cpp, servoSimuThetaUCamVelocity.cpp, servoSimuViper850FourPoints2DCamVelocity.cpp, servoUniversalRobotsIBVS.cpp, servoUniversalRobotsPBVS.cpp, servoViper650FourPoints2DArtVelocityLs_cur.cpp, servoViper650FourPoints2DCamVelocityLs_cur-SR300.cpp, servoViper650FourPoints2DCamVelocityLs_cur.cpp, servoViper850FourPoints2DArtVelocityLs_cur.cpp, servoViper850FourPoints2DArtVelocityLs_des.cpp, servoViper850FourPoints2DCamVelocityLs_cur.cpp, servoViper850FourPointsKinect.cpp, servoViper850Point2DArtVelocity-jointAvoidance-basic.cpp, servoViper850Point2DArtVelocity-jointAvoidance-gpa.cpp, servoViper850Point2DArtVelocity-jointAvoidance-large.cpp, servoViper850Point2DArtVelocity.cpp, servoViper850Point2DCamVelocityKalman.cpp, simulateCircle2DCamVelocity.cpp, simulateFourPoints2DCartesianCamVelocity.cpp, simulateFourPoints2DPolarCamVelocity.cpp, testFeatureSegment.cpp, tutorial-flir-ptu-ibvs.cpp, tutorial-ibvs-4pts-display.cpp, tutorial-ibvs-4pts-image-tracking.cpp, tutorial-ibvs-4pts-json.cpp, tutorial-ibvs-4pts-ogre-tracking.cpp, tutorial-ibvs-4pts-ogre.cpp, tutorial-ibvs-4pts-plotter-continuous-gain-adaptive.cpp, tutorial-ibvs-4pts-plotter-gain-adaptive.cpp, tutorial-ibvs-4pts-plotter.cpp, tutorial-ibvs-4pts-wireframe-camera.cpp, tutorial-ibvs-4pts-wireframe-robot-afma6.cpp, tutorial-ibvs-4pts-wireframe-robot-viper.cpp, tutorial-ibvs-4pts.cpp, tutorial-simu-pioneer-continuous-gain-adaptive.cpp, tutorial-simu-pioneer-continuous-gain-constant.cpp, tutorial-simu-pioneer-pan.cpp, and tutorial-simu-pioneer.cpp.

Definition at line 378 of file vpServo.cpp.

References interactionMatrixType, and inversionType.

◆ setLambda() [1/3]

void vpServo::setLambda ( const vpAdaptiveGain l)
inline

Set the gain $\lambda$ used in the control law (see vpServo::vpServoType) as adaptive. Value of $\lambda$ 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.

See also
vpAdaptiveGain

Definition at line 1007 of file vpServo.h.

◆ setLambda() [2/3]

void vpServo::setLambda ( double  c)
inline

Set the gain $\lambda$ 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&).

Parameters
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.
Examples
manServo4PointsDisplay.cpp, manServoMomentsSimple.cpp, manSimu4Dots.cpp, manSimu4Points.cpp, mbot-apriltag-2D-half-vs.cpp, mbot-apriltag-ibvs.cpp, mbot-apriltag-pbvs.cpp, photometricVisualServoing.cpp, servoAfma4Point2DArtVelocity.cpp, servoAfma4Point2DCamVelocity.cpp, servoAfma4Point2DCamVelocityKalman.cpp, servoAfma62DhalfCamVelocity.cpp, servoAfma6AprilTagIBVS.cpp, servoAfma6AprilTagPBVS.cpp, servoAfma6Cylinder2DCamVelocity.cpp, servoAfma6Cylinder2DCamVelocitySecondaryTask.cpp, servoAfma6Ellipse2DCamVelocity.cpp, servoAfma6FourPoints2DArtVelocity.cpp, servoAfma6FourPoints2DCamVelocityLs_cur.cpp, servoAfma6FourPoints2DCamVelocityLs_des.cpp, servoAfma6Line2DCamVelocity.cpp, servoAfma6MegaposePBVS.cpp, servoAfma6Point2DArtVelocity.cpp, servoAfma6Point2DCamVelocity.cpp, servoAfma6Points2DCamVelocityEyeToHand.cpp, servoAfma6Segment2DCamVelocity.cpp, servoAfma6SquareLines2DCamVelocity.cpp, servoAfma6TwoLines2DCamVelocity.cpp, servoBebop2.cpp, servoBiclopsPoint2DArtVelocity.cpp, servoFlirPtuIBVS.cpp, servoFrankaIBVS.cpp, servoFrankaPBVS.cpp, servoPioneerPanSegment3D.cpp, servoPioneerPoint2DDepth.cpp, servoPololuPtuPoint2DJointVelocity.cpp, servoPtu46Point2DArtVelocity.cpp, servoSimu3D_cMcd_CamVelocity.cpp, servoSimu3D_cdMc_CamVelocity.cpp, servoSimu4Points.cpp, servoSimuAfma6FourPoints2DCamVelocity.cpp, servoSimuCircle2DCamVelocity.cpp, servoSimuCircle2DCamVelocityDisplay.cpp, servoSimuCylinder.cpp, servoSimuCylinder2DCamVelocityDisplay.cpp, servoSimuCylinder2DCamVelocityDisplaySecondaryTask.cpp, servoSimuFourPoints2DCamVelocity.cpp, servoSimuFourPoints2DCamVelocityDisplay.cpp, servoSimuFourPoints2DPolarCamVelocityDisplay.cpp, servoSimuLine2DCamVelocityDisplay.cpp, servoSimuPoint2DCamVelocity1.cpp, servoSimuPoint2DCamVelocity2.cpp, servoSimuPoint2DCamVelocity3.cpp, servoSimuPoint2DhalfCamVelocity1.cpp, servoSimuPoint2DhalfCamVelocity2.cpp, servoSimuPoint2DhalfCamVelocity3.cpp, servoSimuPoint3DCamVelocity.cpp, servoSimuSphere.cpp, servoSimuSphere2DCamVelocity.cpp, servoSimuSphere2DCamVelocityDisplay.cpp, servoSimuSphere2DCamVelocityDisplaySecondaryTask.cpp, servoSimuSquareLine2DCamVelocityDisplay.cpp, servoSimuThetaUCamVelocity.cpp, servoSimuViper850FourPoints2DCamVelocity.cpp, servoUniversalRobotsIBVS.cpp, servoUniversalRobotsPBVS.cpp, servoViper650FourPoints2DArtVelocityLs_cur.cpp, servoViper650FourPoints2DCamVelocityLs_cur-SR300.cpp, servoViper650FourPoints2DCamVelocityLs_cur.cpp, servoViper650Point2DCamVelocity.cpp, servoViper850FourPoints2DArtVelocityLs_cur.cpp, servoViper850FourPoints2DArtVelocityLs_des.cpp, servoViper850FourPoints2DCamVelocityLs_cur.cpp, servoViper850FourPointsKinect.cpp, servoViper850Point2DArtVelocity-jointAvoidance-basic.cpp, servoViper850Point2DArtVelocity-jointAvoidance-gpa.cpp, servoViper850Point2DArtVelocity-jointAvoidance-large.cpp, servoViper850Point2DArtVelocity.cpp, servoViper850Point2DCamVelocity.cpp, servoViper850Point2DCamVelocityKalman.cpp, simulateCircle2DCamVelocity.cpp, simulateFourPoints2DCartesianCamVelocity.cpp, simulateFourPoints2DPolarCamVelocity.cpp, testFeatureSegment.cpp, tutorial-flir-ptu-ibvs.cpp, tutorial-ibvs-4pts-display.cpp, tutorial-ibvs-4pts-image-tracking.cpp, tutorial-ibvs-4pts-json.cpp, tutorial-ibvs-4pts-ogre-tracking.cpp, tutorial-ibvs-4pts-ogre.cpp, tutorial-ibvs-4pts-plotter-continuous-gain-adaptive.cpp, tutorial-ibvs-4pts-plotter-gain-adaptive.cpp, tutorial-ibvs-4pts-plotter.cpp, tutorial-ibvs-4pts-wireframe-camera.cpp, tutorial-ibvs-4pts-wireframe-robot-afma6.cpp, tutorial-ibvs-4pts-wireframe-robot-viper.cpp, tutorial-ibvs-4pts.cpp, tutorial-simu-pioneer-continuous-gain-adaptive.cpp, tutorial-simu-pioneer-continuous-gain-constant.cpp, tutorial-simu-pioneer-pan.cpp, and tutorial-simu-pioneer.cpp.

Definition at line 976 of file vpServo.h.

◆ setLambda() [3/3]

void vpServo::setLambda ( double  gain_at_zero,
double  gain_at_infinity,
double  slope_at_zero 
)
inline

Set the gain $\lambda$ used in the control law (see vpServo::vpServoType) as adaptive. Value of $\lambda$ 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.

Parameters
gain_at_zero: the expected gain when $x=0$: $\lambda(0)$.
gain_at_infinity: the expected gain when $x=\infty$: $\lambda(\infty)$.
slope_at_zero: the expected slope of $\lambda(x)$ when $x=0$: ${\dot \lambda}(0)$.

For more details on these parameters see vpAdaptiveGain class.

Definition at line 992 of file vpServo.h.

◆ setMu()

void vpServo::setMu ( double  mu_)
inline

Set the value of the parameter $\mu$ used to ensure the continuity of the velocities computed using computeControlLaw(double).

A recommended value is 4.

Definition at line 1015 of file vpServo.h.

◆ setPseudoInverseThreshold()

void vpServo::setPseudoInverseThreshold ( double  pseudo_inverse_threshold)
inline

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.

Parameters
pseudo_inverse_threshold: Value to use. Default value is set to 1e-6.
See also
getPseudoInverseThreshold()

Definition at line 1114 of file vpServo.h.

◆ setServo()

void vpServo::setServo ( const vpServoType servo_type)

Set the visual servoing control law.

Parameters
servo_type: Control law that will be considered. See vpServo::vpServoType to see the possible values.
Examples
manServo4PointsDisplay.cpp, manServoMomentsSimple.cpp, manSimu4Dots.cpp, manSimu4Points.cpp, mbot-apriltag-2D-half-vs.cpp, mbot-apriltag-ibvs.cpp, mbot-apriltag-pbvs.cpp, photometricVisualServoing.cpp, servoAfma4Point2DArtVelocity.cpp, servoAfma4Point2DCamVelocity.cpp, servoAfma4Point2DCamVelocityKalman.cpp, servoAfma62DhalfCamVelocity.cpp, servoAfma6AprilTagIBVS.cpp, servoAfma6AprilTagPBVS.cpp, servoAfma6Cylinder2DCamVelocity.cpp, servoAfma6Cylinder2DCamVelocitySecondaryTask.cpp, servoAfma6Ellipse2DCamVelocity.cpp, servoAfma6FourPoints2DArtVelocity.cpp, servoAfma6FourPoints2DCamVelocityLs_cur.cpp, servoAfma6FourPoints2DCamVelocityLs_des.cpp, servoAfma6Line2DCamVelocity.cpp, servoAfma6MegaposePBVS.cpp, servoAfma6Point2DArtVelocity.cpp, servoAfma6Point2DCamVelocity.cpp, servoAfma6Points2DCamVelocityEyeToHand.cpp, servoAfma6Segment2DCamVelocity.cpp, servoAfma6SquareLines2DCamVelocity.cpp, servoAfma6TwoLines2DCamVelocity.cpp, servoBebop2.cpp, servoBiclopsPoint2DArtVelocity.cpp, servoFlirPtuIBVS.cpp, servoFrankaIBVS.cpp, servoFrankaPBVS.cpp, servoPioneerPanSegment3D.cpp, servoPioneerPoint2DDepth.cpp, servoPololuPtuPoint2DJointVelocity.cpp, servoPtu46Point2DArtVelocity.cpp, servoSimu3D_cMcd_CamVelocity.cpp, servoSimu3D_cdMc_CamVelocity.cpp, servoSimu4Points.cpp, servoSimuAfma6FourPoints2DCamVelocity.cpp, servoSimuCircle2DCamVelocity.cpp, servoSimuCircle2DCamVelocityDisplay.cpp, servoSimuCylinder.cpp, servoSimuCylinder2DCamVelocityDisplay.cpp, servoSimuCylinder2DCamVelocityDisplaySecondaryTask.cpp, servoSimuFourPoints2DCamVelocity.cpp, servoSimuFourPoints2DCamVelocityDisplay.cpp, servoSimuFourPoints2DPolarCamVelocityDisplay.cpp, servoSimuLine2DCamVelocityDisplay.cpp, servoSimuPoint2DCamVelocity1.cpp, servoSimuPoint2DCamVelocity2.cpp, servoSimuPoint2DCamVelocity3.cpp, servoSimuPoint2DhalfCamVelocity1.cpp, servoSimuPoint2DhalfCamVelocity2.cpp, servoSimuPoint2DhalfCamVelocity3.cpp, servoSimuPoint3DCamVelocity.cpp, servoSimuSphere.cpp, servoSimuSphere2DCamVelocity.cpp, servoSimuSphere2DCamVelocityDisplay.cpp, servoSimuSphere2DCamVelocityDisplaySecondaryTask.cpp, servoSimuSquareLine2DCamVelocityDisplay.cpp, servoSimuThetaUCamVelocity.cpp, servoSimuViper850FourPoints2DCamVelocity.cpp, servoUniversalRobotsIBVS.cpp, servoUniversalRobotsPBVS.cpp, servoViper650FourPoints2DArtVelocityLs_cur.cpp, servoViper650FourPoints2DCamVelocityLs_cur-SR300.cpp, servoViper650FourPoints2DCamVelocityLs_cur.cpp, servoViper650Point2DCamVelocity.cpp, servoViper850FourPoints2DArtVelocityLs_cur.cpp, servoViper850FourPoints2DArtVelocityLs_des.cpp, servoViper850FourPoints2DCamVelocityLs_cur.cpp, servoViper850FourPointsKinect.cpp, servoViper850Point2DArtVelocity-jointAvoidance-basic.cpp, servoViper850Point2DArtVelocity-jointAvoidance-gpa.cpp, servoViper850Point2DArtVelocity-jointAvoidance-large.cpp, servoViper850Point2DArtVelocity.cpp, servoViper850Point2DCamVelocity.cpp, servoViper850Point2DCamVelocityKalman.cpp, simulateCircle2DCamVelocity.cpp, simulateFourPoints2DCartesianCamVelocity.cpp, simulateFourPoints2DPolarCamVelocity.cpp, testFeatureSegment.cpp, tutorial-flir-ptu-ibvs.cpp, tutorial-ibvs-4pts-display.cpp, tutorial-ibvs-4pts-image-tracking.cpp, tutorial-ibvs-4pts-json.cpp, tutorial-ibvs-4pts-ogre-tracking.cpp, tutorial-ibvs-4pts-ogre.cpp, tutorial-ibvs-4pts-plotter-continuous-gain-adaptive.cpp, tutorial-ibvs-4pts-plotter-gain-adaptive.cpp, tutorial-ibvs-4pts-plotter.cpp, tutorial-ibvs-4pts-wireframe-camera.cpp, tutorial-ibvs-4pts-wireframe-robot-afma6.cpp, tutorial-ibvs-4pts-wireframe-robot-viper.cpp, tutorial-ibvs-4pts.cpp, tutorial-simu-pioneer-continuous-gain-adaptive.cpp, tutorial-simu-pioneer-continuous-gain-constant.cpp, tutorial-simu-pioneer-pan.cpp, and tutorial-simu-pioneer.cpp.

Definition at line 132 of file vpServo.cpp.

References vpMatrix::eye(), EYEINHAND_CAMERA, EYEINHAND_L_cVe_eJe, servoType, set_cVe(), set_eJe(), and signInteractionMatrix.

◆ testInitialization()

bool vpServo::testInitialization ( )

Test if all the initialization are correct. If true, the control law can be computed.

Definition at line 624 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().

◆ testUpdated()

bool vpServo::testUpdated ( )

Test if all the update are correct. If true control law can be computed.

Definition at line 664 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().

Member Data Documentation

◆ cJc

vpMatrix vpServo::cJc
protected

A diag matrix used to determine which are the degrees of freedom that are controlled in the camera frame (c).

Definition at line 1330 of file vpServo.h.

Referenced by computeControlLaw(), setCameraDoF(), and vpServo().

◆ cVe

vpVelocityTwistMatrix vpServo::cVe
protected

Twist transformation matrix between camera frame (c) and robot end-effector frame (e).

Definition at line 1219 of file vpServo.h.

Referenced by computeControlLaw().

◆ cVf

vpVelocityTwistMatrix vpServo::cVf
protected

Twist transformation matrix between camera frame (c) and robot base frame (f).

Definition at line 1228 of file vpServo.h.

Referenced by computeControlLaw().

◆ desiredFeatureList

std::list<vpBasicFeature *> vpServo::desiredFeatureList

List of desired visual features $\bf s^*$.

Definition at line 1193 of file vpServo.h.

Referenced by addFeature(), computeError(), computeInteractionMatrix(), vpServoDisplay::display(), init(), kill(), and print().

◆ dim_task

unsigned int vpServo::dim_task
protected

Dimension of the task updated during computeControlLaw().

Definition at line 1276 of file vpServo.h.

Referenced by computeError(), computeInteractionMatrix(), and init().

◆ e

vpColVector vpServo::e

Task $e = e_1 + (I-{J_1}^{+} J_1) e_2$.

Definition at line 1177 of file vpServo.h.

Referenced by computeControlLaw().

◆ e1

vpColVector vpServo::e1

Primary task $e_1 = {J_1}^{+}(s-s*)$.

Definition at line 1175 of file vpServo.h.

Referenced by computeControlLaw(), and secondaryTask().

◆ e1_initial

vpColVector vpServo::e1_initial
protected

First primary task value ${\bf \widehat J}_e^+ {\bf e}$ used in the control law with the task sequencing approach when time is initial $t=0$.

See also
computeControlLaw(double) and computeControlLaw(double, const vpColVector &)

Definition at line 1321 of file vpServo.h.

Referenced by computeControlLaw().

◆ eJe

vpMatrix vpServo::eJe
protected

Jacobian expressed in the end-effector frame (e).

Definition at line 1252 of file vpServo.h.

Referenced by computeControlLaw().

◆ error

vpColVector vpServo::error

Error $(s - s^*)$ between the current set of visual features $s$ and the desired set of visual features $s^*$. This vector is updated after a call of computeError() or computeControlLaw().

Examples
servoAfma4Point2DCamVelocityKalman.cpp.

Definition at line 1159 of file vpServo.h.

Referenced by computeControlLaw(), computeError(), print(), secondaryTask(), and secondaryTaskJointLimitAvoidance().

◆ errorComputed

bool vpServo::errorComputed
protected

true if the error has been computed.

Definition at line 1272 of file vpServo.h.

Referenced by computeError(), init(), and print().

◆ featureList

std::list<vpBasicFeature *> vpServo::featureList

List of current visual features $\bf s$.

Definition at line 1191 of file vpServo.h.

Referenced by addFeature(), computeError(), vpServoDisplay::display(), getDimension(), init(), kill(), and print().

◆ featureSelectionList

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 1196 of file vpServo.h.

Referenced by addFeature(), computeError(), getDimension(), init(), and print().

◆ fJe

vpMatrix vpServo::fJe
protected

Jacobian expressed in the robot base frame (f).

Definition at line 1260 of file vpServo.h.

Referenced by computeControlLaw().

◆ forceInteractionMatrixComputation

bool vpServo::forceInteractionMatrixComputation
protected

Force the interaction matrix computation even if it is already done.

Definition at line 1280 of file vpServo.h.

Referenced by computeInteractionMatrix(), and init().

◆ fVe

vpVelocityTwistMatrix vpServo::fVe
protected

Twist transformation matrix between robot base frame (f) and robot end-effector frame (e).

Definition at line 1239 of file vpServo.h.

Referenced by computeControlLaw().

◆ I

vpMatrix vpServo::I
protected

Identity matrix.

Definition at line 1283 of file vpServo.h.

Referenced by computeControlLaw(), secondaryTask(), and secondaryTaskJointLimitAvoidance().

◆ I_WpW

vpMatrix vpServo::I_WpW
protected

Projection operators $\bf I-WpW$.

Definition at line 1287 of file vpServo.h.

Referenced by computeControlLaw(), secondaryTask(), and secondaryTaskJointLimitAvoidance().

◆ init_cVe

bool vpServo::init_cVe
protected

Boolean indicating if twist transformation matrix between camera frame (c) and robot end-effector frame (e) is set by the user and thus differs from eye matrix.

Definition at line 1226 of file vpServo.h.

Referenced by computeControlLaw(), init(), testInitialization(), and testUpdated().

◆ init_cVf

bool vpServo::init_cVf
protected

Boolean indicating if twist transformation matrix between camera frame (c) and robot base frame (f) is set by the user and thus differs from eye matrix.

Definition at line 1234 of file vpServo.h.

Referenced by init(), and testInitialization().

◆ init_eJe

bool vpServo::init_eJe
protected

Boolean indicating if Jacobian expressed in the end-effector frame (e) is set by the user and thus differs from eye matrix.

Definition at line 1257 of file vpServo.h.

Referenced by computeControlLaw(), init(), testInitialization(), and testUpdated().

◆ init_fJe

bool vpServo::init_fJe
protected

Boolean indicating if Jacobian expressed in the robot base frame (f) is set by the user and thus differs from eye matrix.

Definition at line 1265 of file vpServo.h.

Referenced by computeControlLaw(), init(), testInitialization(), and testUpdated().

◆ init_fVe

bool vpServo::init_fVe
protected

Boolean indicating if twist transformation matrix between robot base frame (f) and robot end-effector frame(e) is set by the user and thus differs from eye matrix.

Definition at line 1245 of file vpServo.h.

Referenced by computeControlLaw(), init(), testInitialization(), and testUpdated().

◆ interactionMatrixComputed

bool vpServo::interactionMatrixComputed
protected

true if the interaction matrix has been computed.

Definition at line 1274 of file vpServo.h.

Referenced by computeInteractionMatrix(), init(), and print().

◆ interactionMatrixType

vpServoIteractionMatrixType vpServo::interactionMatrixType

Type of the interaction matrix (current, mean, desired, user)

Definition at line 1205 of file vpServo.h.

Referenced by computeInteractionMatrix(), init(), and setInteractionMatrixType().

◆ inversionType

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 1208 of file vpServo.h.

Referenced by computeControlLaw(), init(), and setInteractionMatrixType().

◆ iscJcIdentity

bool vpServo::iscJcIdentity
protected

Boolean to know if cJc is identity (for fast computation)

Definition at line 1324 of file vpServo.h.

Referenced by computeControlLaw(), and setCameraDoF().

◆ J1

vpMatrix vpServo::J1

Task Jacobian $J_1 = L {^c}V_a {^a}J_e$.

Examples
servoAfma4Point2DCamVelocityKalman.cpp.

Definition at line 1161 of file vpServo.h.

Referenced by computeControlLaw(), secondaryTask(), and secondaryTaskJointLimitAvoidance().

◆ J1p

vpMatrix vpServo::J1p

Pseudo inverse ${J_1}^{+}$ of the task Jacobian.

Definition at line 1163 of file vpServo.h.

Referenced by computeControlLaw().

◆ L

vpMatrix vpServo::L

Interaction matrix.

Definition at line 1154 of file vpServo.h.

Referenced by computeControlLaw(), computeInteractionMatrix(), and print().

◆ lambda

vpAdaptiveGain vpServo::lambda

Gain used in the control law.

Definition at line 1199 of file vpServo.h.

Referenced by computeControlLaw(), print(), and secondaryTask().

◆ m_first_iteration

bool vpServo::m_first_iteration
protected

True until first call of computeControlLaw() is achieved.

Definition at line 1332 of file vpServo.h.

Referenced by computeControlLaw(), and init().

◆ m_pseudo_inverse_threshold

double vpServo::m_pseudo_inverse_threshold
protected

Threshold used in the pseudo inverse.

Definition at line 1334 of file vpServo.h.

Referenced by computeControlLaw().

◆ mu

double vpServo::mu
protected

Gain $ mu $ used to compute the control law with the task sequencing approach.

See also
computeControlLaw(double) and computeControlLaw(double, const vpColVector &)

Definition at line 1314 of file vpServo.h.

Referenced by computeControlLaw().

◆ P

vpMatrix vpServo::P
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.

\[ {\bf P} =\bar{\lambda }\left ( \left \| {\bf e} \right \| \right ){\bf P}_{ \left \| {\bf e } \right \| } \left ( 1 - \bar{\lambda }\left ( \left \| {\bf e } \right \| \right ) \right ) \left ( {\bf I-W^+W}\right ) \]

with

\[ {\bf P}_{\left \| {\bf e } \right \| } = I_{n} - \frac{1}{{\bf e }^\top {\bf J_{{\bf e }} } {\bf J_{{\bf e }}^\top } {\bf e }}{\bf J_{{\bf e }}^\top }{\bf e }{\bf e }^\top{\bf J_{{\bf e }} } \]

Definition at line 1304 of file vpServo.h.

Referenced by secondaryTask(), and secondaryTaskJointLimitAvoidance().

◆ q_dot

vpColVector vpServo::q_dot

Articular velocity.

Definition at line 1180 of file vpServo.h.

Referenced by vpServoData::save().

◆ rankJ1

unsigned int vpServo::rankJ1

Rank of the task Jacobian.

Definition at line 1188 of file vpServo.h.

Referenced by computeControlLaw(), init(), and secondaryTask().

◆ s

vpColVector vpServo::s

Current state of visual features $s$. This vector is updated after a call of computeError() or computeControlLaw().

Definition at line 1168 of file vpServo.h.

Referenced by computeError(), and vpServoData::save().

◆ servoType

vpServoType vpServo::servoType

Chosen visual servoing control law.

Definition at line 1185 of file vpServo.h.

Referenced by computeControlLaw(), init(), print(), setServo(), testInitialization(), and testUpdated().

◆ signInteractionMatrix

int vpServo::signInteractionMatrix

Sign of the interaction +/- 1 (1 for eye-in-hand, -1 for eye-to-hand configuration)

Definition at line 1203 of file vpServo.h.

Referenced by computeControlLaw(), init(), and setServo().

◆ sStar

vpColVector vpServo::sStar

Desired state of visual features $s^*$. This vector is updated after a call of computeError() or computeControlLaw().

Definition at line 1172 of file vpServo.h.

Referenced by computeError(), and vpServoData::save().

◆ sv

vpColVector vpServo::sv
protected

Singular values from the pseudo inverse.

Definition at line 1307 of file vpServo.h.

Referenced by computeControlLaw().

◆ taskWasKilled

bool vpServo::taskWasKilled
protected

Flag to indicate if the task was killed.

Definition at line 1278 of file vpServo.h.

Referenced by init(), and kill().

◆ v

vpColVector vpServo::v

Camera velocity.

Definition at line 1182 of file vpServo.h.

◆ WpW

vpMatrix vpServo::WpW
protected

Projection operators $\bf WpW$.

Definition at line 1285 of file vpServo.h.

Referenced by computeControlLaw(), and secondaryTask().