Visual Servoing Platform  version 3.6.1 under development (2024-12-17)

#include <visp3/robot/vpRobot.h>

+ Inheritance diagram for vpRobot:

Public Types

enum  vpRobotStateType {
  STATE_STOP , STATE_VELOCITY_CONTROL , STATE_POSITION_CONTROL , STATE_ACCELERATION_CONTROL ,
  STATE_FORCE_TORQUE_CONTROL
}
 
enum  vpControlFrameType {
  REFERENCE_FRAME , ARTICULAR_FRAME , JOINT_STATE = ARTICULAR_FRAME , END_EFFECTOR_FRAME ,
  CAMERA_FRAME , TOOL_FRAME = CAMERA_FRAME , MIXT_FRAME
}
 

Public Member Functions

 vpRobot (void)
 
 vpRobot (const vpRobot &robot)
 
virtual ~vpRobot ()
 
Inherited functionalities from vpRobot
virtual void get_eJe (vpMatrix &_eJe)=0
 
virtual void get_fJe (vpMatrix &_fJe)=0
 
virtual void getDisplacement (const vpRobot::vpControlFrameType frame, vpColVector &q)=0
 
double getMaxTranslationVelocity (void) const
 
double getMaxRotationVelocity (void) const
 
int getNDof () const
 
virtual void getPosition (const vpRobot::vpControlFrameType frame, vpColVector &position)=0
 
vpColVector getPosition (const vpRobot::vpControlFrameType frame)
 
virtual vpRobotStateType getRobotState (void) const
 
virtual void init ()=0
 
vpRobotoperator= (const vpRobot &robot)
 
void setMaxRotationVelocity (double maxVr)
 
void setMaxTranslationVelocity (double maxVt)
 
virtual void setPosition (const vpRobot::vpControlFrameType frame, const vpColVector &q)=0
 
virtual vpRobotStateType setRobotState (const vpRobot::vpRobotStateType newState)
 
virtual void setVelocity (const vpRobot::vpControlFrameType frame, const vpColVector &vel)=0
 
void setVerbose (bool verbose)
 

Static Public Member Functions

Static Public Member Functions inherited from vpRobot
static vpColVector saturateVelocities (const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
 

Protected Member Functions

Protected Member Functions Inherited from vpRobot
vpControlFrameType setRobotFrame (vpRobot::vpControlFrameType newFrame)
 
vpControlFrameType getRobotFrame (void) const
 

Protected Attributes

double maxTranslationVelocity
 
double maxRotationVelocity
 
int nDof
 
vpMatrix eJe
 
int eJeAvailable
 
vpMatrix fJe
 
int fJeAvailable
 
int areJointLimitsAvailable
 
double * qmin
 
double * qmax
 
bool verbose_
 

Static Protected Attributes

static const double maxTranslationVelocityDefault = 0.2
 
static const double maxRotationVelocityDefault = 0.7
 

Detailed Description

Class that defines a generic virtual robot.

group_robot_real_arm group_robot_real_ptu group_robot_real_unicycle group_robot_real_template

Definition at line 58 of file vpRobot.h.

Member Enumeration Documentation

◆ vpControlFrameType

Robot control frames.

Enumerator
REFERENCE_FRAME 

Corresponds to a fixed reference frame attached to the robot structure.

ARTICULAR_FRAME 

Corresponds to the joint state. This value is deprecated. You should rather use vpRobot::JOINT_STATE.

JOINT_STATE 

Corresponds to the joint state.

END_EFFECTOR_FRAME 

Corresponds to robot end-effector frame.

CAMERA_FRAME 

Corresponds to a frame attached to the camera mounted on the robot end-effector.

TOOL_FRAME 

Corresponds to a frame attached to the tool (camera, gripper...) mounted on the robot end-effector. This value is equal to vpRobot::CAMERA_FRAME.

MIXT_FRAME 

Corresponds to a "virtual" frame where translations are expressed in the reference frame, and rotations in the camera frame.

Definition at line 76 of file vpRobot.h.

◆ vpRobotStateType

Robot control states.

Enumerator
STATE_STOP 

Stops robot motion especially in velocity and acceleration control.

STATE_VELOCITY_CONTROL 

Initialize the velocity controller.

STATE_POSITION_CONTROL 

Initialize the position controller.

STATE_ACCELERATION_CONTROL 

Initialize the acceleration controller.

STATE_FORCE_TORQUE_CONTROL 

Initialize the force/torque controller.

Definition at line 64 of file vpRobot.h.

Constructor & Destructor Documentation

◆ vpRobot() [1/2]

vpRobot::vpRobot ( void  )

Definition at line 51 of file vpRobot.cpp.

◆ vpRobot() [2/2]

vpRobot::vpRobot ( const vpRobot robot)

Definition at line 58 of file vpRobot.cpp.

◆ ~vpRobot()

vpRobot::~vpRobot ( )
virtual

Destructor that free allocated memory.

Definition at line 70 of file vpRobot.cpp.

References qmax, and qmin.

Member Function Documentation

◆ get_eJe()

virtual void vpRobot::get_eJe ( vpMatrix _eJe)
pure virtual

◆ get_fJe()

virtual void vpRobot::get_fJe ( vpMatrix _fJe)
pure virtual

Get the robot Jacobian expressed in the robot reference (or world) frame.

Implemented in vpRobotTemplate, vpRobotViper850, vpRobotViper650, vpRobotPololuPtu, vpRobotKinova, vpRobotFranka, vpRobotFlirPtu, vpRobotBiclops, vpRobotAfma4, vpRobotPtu46, and vpRobotAfma6.

◆ getDisplacement()

virtual void vpRobot::getDisplacement ( const vpRobot::vpControlFrameType  frame,
vpColVector q 
)
pure virtual

Get a displacement (frame as to ve specified) between two successive position control.

Implemented in vpRobotPtu46, vpRobotViper850, vpRobotViper650, vpRobotAfma6, vpRobotAfma4, vpRobotTemplate, vpRobotKinova, vpRobotFlirPtu, and vpRobotBiclops.

◆ getMaxRotationVelocity()

◆ getMaxTranslationVelocity()

double vpRobot::getMaxTranslationVelocity ( void  ) const

◆ getNDof()

int vpRobot::getNDof ( ) const
inline

Return robot degrees of freedom number.

Examples
servoPololuPtuPoint2DJointVelocity.cpp.

Definition at line 145 of file vpRobot.h.

◆ getPosition() [1/2]

vpColVector vpRobot::getPosition ( const vpRobot::vpControlFrameType  frame)

Return the current robot position in the specified frame.

Definition at line 217 of file vpRobot.cpp.

References getPosition().

◆ getPosition() [2/2]

virtual void vpRobot::getPosition ( const vpRobot::vpControlFrameType  frame,
vpColVector position 
)
pure virtual

◆ getRobotFrame()

vpControlFrameType vpRobot::getRobotFrame ( void  ) const
inlineprotected

Definition at line 183 of file vpRobot.h.

◆ getRobotState()

◆ init()

◆ operator=()

vpRobot & vpRobot::operator= ( const vpRobot robot)

◆ saturateVelocities()

vpColVector vpRobot::saturateVelocities ( const vpColVector v_in,
const vpColVector v_max,
bool  verbose = false 
)
static

Saturate velocities.

Parameters
v_in: Vector of input velocities to saturate. Translation velocities should be expressed in m/s while rotation velocities in rad/s.
v_max: Vector of maximal allowed velocities. Maximal translation velocities should be expressed in m/s while maximal rotation velocities in rad/s.
verbose: Print a message indicating which axis causes the saturation.
Returns
Saturated velocities.
Exceptions
vpRobotException::dimensionError: If the input vectors have different dimensions.

The code below shows how to use this static method in order to saturate a velocity skew vector.

#include <iostream>
#include <visp3/robot/vpRobot.h>
#ifdef ENABLE_VISP_NAMESPACE
using namespace VISP_NAMESPACE_NAME;
#endif
int main()
{
// Set a velocity skew vector
v[0] = 0.1; // vx in m/s
v[1] = 0.2; // vy
v[2] = 0.3; // vz
v[3] = vpMath::rad(10); // wx in rad/s
v[4] = vpMath::rad(-10); // wy
v[5] = vpMath::rad(20); // wz
// Set the maximal allowed velocities
vpColVector v_max(6);
for (int i=0; i<3; i++)
v_max[i] = 0.3; // in translation (m/s)
for (int i=3; i<6; i++)
v_max[i] = vpMath::rad(10); // in rotation (rad/s)
// Compute the saturated velocity skew vector
vpColVector v_sat = vpRobot::saturateVelocities(v, v_max, true);
std::cout << "v : " << v.t() << std::endl;
std::cout << "v max: " << v_max.t() << std::endl;
std::cout << "v sat: " << v_sat.t() << std::endl;
return 0;
}
Implementation of column vector and the associated operations.
Definition: vpColVector.h:191
vpRowVector t() const
static double rad(double deg)
Definition: vpMath.h:129
static vpColVector saturateVelocities(const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
Definition: vpRobot.cpp:164

Definition at line 164 of file vpRobot.cpp.

References vpException::dimensionError, and vpArray2D< Type >::size().

Referenced by vpRobotFlirPtu::setVelocity(), vpRobotFranka::setVelocity(), vpRobotKinova::setVelocity(), vpRobotPioneer::setVelocity(), vpRobotTemplate::setVelocity(), vpRobotUniversalRobots::setVelocity(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotViper650::setVelocity(), and vpRobotViper850::setVelocity().

◆ setMaxRotationVelocity()

void vpRobot::setMaxRotationVelocity ( double  w_max)

Set the maximal rotation velocity that can be sent to the robot during a velocity control.

Parameters
w_max: Maximum rotational velocity expressed in rad/s.
Examples
servoMomentPoints.cpp, servoSimu4Points.cpp, servoSimuSphere.cpp, testFeatureSegment.cpp, testFrankaJointVelocityLimits.cpp, and testRobotFlirPtu.cpp.

Definition at line 261 of file vpRobot.cpp.

References maxRotationVelocity.

Referenced by vpRobotViper650::setMaxRotationVelocity(), and vpRobotViper850::setMaxRotationVelocity().

◆ setMaxTranslationVelocity()

void vpRobot::setMaxTranslationVelocity ( double  v_max)

Set the maximal translation velocity that can be sent to the robot during a velocity control.

Parameters
v_max: Maximum translation velocity expressed in m/s.
Examples
servoMomentPoints.cpp, servoSimu4Points.cpp, servoSimuSphere.cpp, simulateCircle2DCamVelocity.cpp, simulateFourPoints2DCartesianCamVelocity.cpp, simulateFourPoints2DPolarCamVelocity.cpp, and testFeatureSegment.cpp.

Definition at line 240 of file vpRobot.cpp.

References maxTranslationVelocity.

◆ setPosition()

virtual void vpRobot::setPosition ( const vpRobot::vpControlFrameType  frame,
const vpColVector q 
)
pure virtual

◆ setRobotFrame()

◆ setRobotState()

vpRobot::vpRobotStateType vpRobot::setRobotState ( const vpRobot::vpRobotStateType  newState)
virtual

Reimplemented in vpRobotViper850, vpRobotViper650, vpRobotUniversalRobots, vpRobotPtu46, vpRobotFranka, vpRobotFlirPtu, vpRobotAfma6, vpRobotAfma4, vpRobotPololuPtu, and vpRobotBiclops.

Examples
UniversalRobotsMoveToPosition.cpp, UniversalRobotsSavePosition.cpp, frankaMoveToPosition.cpp, frankaSavePosition.cpp, moveAfma4.cpp, moveBiclops.cpp, movePtu46.cpp, photometricMappingVisualServoing.cpp, photometricVisualServoing.cpp, photometricVisualServoingWithoutVpServo.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_cur_integrator.cpp, servoAfma6FourPoints2DCamVelocityLs_des.cpp, servoAfma6Line2DCamVelocity.cpp, servoAfma6MegaposePBVS.cpp, servoAfma6Point2DArtVelocity.cpp, servoAfma6Point2DCamVelocity.cpp, servoAfma6Points2DCamVelocityEyeToHand.cpp, servoAfma6Segment2DCamVelocity.cpp, servoAfma6SquareLines2DCamVelocity.cpp, servoAfma6TwoLines2DCamVelocity.cpp, servoBiclopsPoint2DArtVelocity.cpp, servoFlirPtuIBVS.cpp, servoFrankaIBVS.cpp, servoFrankaPBVS.cpp, servoKinovaJacoCart.cpp, servoKinovaJacoJoint.cpp, servoPololuPtuPoint2DJointVelocity.cpp, servoPtu46Point2DArtVelocity.cpp, servoSimuAfma6FourPoints2DCamVelocity.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, testFrankaCartForceTorque-2.cpp, testFrankaCartForceTorque.cpp, testFrankaCartVelocity-2.cpp, testFrankaCartVelocity-3.cpp, testFrankaCartVelocity.cpp, testFrankaJointPosition.cpp, testFrankaJointTorque.cpp, testFrankaJointVelocity-2.cpp, testFrankaJointVelocity-3.cpp, testFrankaJointVelocity.cpp, testFrankaJointVelocityLimits.cpp, testRobotFlirPtu.cpp, testRobotViper650-frames.cpp, testRobotViper850-frames.cpp, testUniversalRobotsCartPosition.cpp, testUniversalRobotsCartVelocity.cpp, testUniversalRobotsJointPosition.cpp, testUniversalRobotsJointVelocity.cpp, testVirtuoseAfma6.cpp, tutorial-flir-ptu-ibvs.cpp, tutorial-ibvs-4pts-wireframe-robot-afma6.cpp, and tutorial-ibvs-4pts-wireframe-robot-viper.cpp.

Definition at line 202 of file vpRobot.cpp.

Referenced by vpSimulatorCamera::setPosition(), vpRobotBiclops::setRobotState(), vpRobotPololuPtu::setRobotState(), vpRobotAfma4::setRobotState(), vpRobotAfma6::setRobotState(), vpRobotFlirPtu::setRobotState(), vpRobotFranka::setRobotState(), vpRobotPtu46::setRobotState(), vpRobotUniversalRobots::setRobotState(), vpRobotViper650::setRobotState(), vpRobotViper850::setRobotState(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), and vpSimulatorPioneerPan::setVelocity().

◆ setVelocity()

virtual void vpRobot::setVelocity ( const vpRobot::vpControlFrameType  frame,
const vpColVector vel 
)
pure virtual

◆ setVerbose()

Member Data Documentation

◆ areJointLimitsAvailable

int vpRobot::areJointLimitsAvailable
protected

Definition at line 114 of file vpRobot.h.

Referenced by operator=().

◆ eJe

◆ eJeAvailable

int vpRobot::eJeAvailable
protected

is the robot Jacobian expressed in the end-effector frame available

Definition at line 108 of file vpRobot.h.

Referenced by operator=().

◆ fJe

◆ fJeAvailable

int vpRobot::fJeAvailable
protected

is the robot Jacobian expressed in the robot reference frame available

Definition at line 112 of file vpRobot.h.

Referenced by operator=().

◆ maxRotationVelocity

◆ maxRotationVelocityDefault

const double vpRobot::maxRotationVelocityDefault = 0.7
staticprotected

Definition at line 101 of file vpRobot.h.

Referenced by vpRobotFlirPtu::init(), vpRobotKinova::init(), and vpRobotTemplate::init().

◆ maxTranslationVelocity

double vpRobot::maxTranslationVelocity
protected

◆ maxTranslationVelocityDefault

BEGIN_VISP_NAMESPACE const double vpRobot::maxTranslationVelocityDefault = 0.2
staticprotected

Definition at line 99 of file vpRobot.h.

Referenced by vpRobotFlirPtu::init(), vpRobotKinova::init(), and vpRobotTemplate::init().

◆ nDof

◆ qmax

double* vpRobot::qmax
protected

Definition at line 116 of file vpRobot.h.

Referenced by operator=(), and ~vpRobot().

◆ qmin

double* vpRobot::qmin
protected

Definition at line 115 of file vpRobot.h.

Referenced by operator=(), and ~vpRobot().

◆ verbose_