Visual Servoing Platform  version 3.2.0 under development (2019-01-22)

#include <visp3/robot/vpRobotTemplate.h>

+ Inheritance diagram for vpRobotTemplate:

Public Types

enum  vpRobotStateType { STATE_STOP, STATE_VELOCITY_CONTROL, STATE_POSITION_CONTROL, STATE_ACCELERATION_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

void init ()
 
 vpRobotTemplate ()
 
virtual ~vpRobotTemplate ()
 
void get_eJe (vpMatrix &_eJe)
 
void get_fJe (vpMatrix &_fJe)
 
void sendCameraVelocity (const vpColVector &v)
 
void sendArticularVelocity (const vpColVector &qdot)
 
void setVelocity (const vpRobot::vpControlFrameType frame, const vpColVector &vel)
 
void getPosition (vpPoseVector &q)
 
void getArticularPosition (vpColVector &q)
 
void getPosition (const vpRobot::vpControlFrameType frame, vpColVector &q)
 
void setPosition (const vpRobot::vpControlFrameType frame, const vpColVector &q)
 
void getDisplacement (const vpRobot::vpControlFrameType frame, vpColVector &q)
 
Inherited functionalities from vpRobot
double getMaxTranslationVelocity (void) const
 
double getMaxRotationVelocity (void) const
 
vpColVector getPosition (const vpRobot::vpControlFrameType frame)
 
virtual vpRobotStateType getRobotState (void) const
 
void setMaxRotationVelocity (const double maxVr)
 
void setMaxTranslationVelocity (const double maxVt)
 
virtual vpRobotStateType setRobotState (const vpRobot::vpRobotStateType newState)
 
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 robot just to show which function you must implement

Definition at line 57 of file vpRobotTemplate.h.

Member Enumeration Documentation

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 75 of file vpRobot.h.

enum vpRobot::vpRobotStateType
inherited

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.

Definition at line 64 of file vpRobot.h.

Constructor & Destructor Documentation

vpRobotTemplate::vpRobotTemplate ( )

constructor

Definition at line 57 of file vpRobotTemplate.cpp.

References init().

vpRobotTemplate::~vpRobotTemplate ( )
virtual

destructor

constructor

Definition at line 60 of file vpRobotTemplate.cpp.

Member Function Documentation

void vpRobotTemplate::get_eJe ( vpMatrix _eJe)
virtual

get the robot Jacobian expressed in the end-effector frame

Implements vpRobot.

Definition at line 72 of file vpRobotTemplate.cpp.

void vpRobotTemplate::get_fJe ( vpMatrix _fJe)
virtual

get the robot Jacobian expressed in the robot reference frame

Implements vpRobot.

Definition at line 75 of file vpRobotTemplate.cpp.

void vpRobotTemplate::getArticularPosition ( vpColVector q)

get a position expressed in the articular frame

Definition at line 117 of file vpRobotTemplate.cpp.

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

get a displacement (frame as to be specified)

get a displacement (frame as to ve specified)

Implements vpRobot.

Definition at line 129 of file vpRobotTemplate.cpp.

double vpRobot::getMaxTranslationVelocity ( void  ) const
inherited
void vpRobotTemplate::getPosition ( vpPoseVector q)

get a position expressed in the robot reference frame

Definition at line 115 of file vpRobotTemplate.cpp.

void vpRobotTemplate::getPosition ( const vpRobot::vpControlFrameType  frame,
vpColVector q 
)
virtual

get a displacement (frame as to be specified)

get a displacement (frame as to ve specified)

Implements vpRobot.

Definition at line 119 of file vpRobotTemplate.cpp.

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

Return the current robot position in the specified frame.

Definition at line 216 of file vpRobot.cpp.

References vpRobot::getPosition().

vpControlFrameType vpRobot::getRobotFrame ( void  ) const
inlineprotectedinherited
void vpRobotTemplate::init ( void  )
virtual

basic initialization

Implements vpRobot.

Definition at line 50 of file vpRobotTemplate.cpp.

References vpTRACE.

Referenced by vpRobotTemplate().

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

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>
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;
}

Definition at line 163 of file vpRobot.cpp.

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

Referenced by vpSimulatorCamera::setVelocity(), vpRobotCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpRobotPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotFranka::setVelocity(), vpRobotViper650::setVelocity(), and vpRobotViper850::setVelocity().

void vpRobotTemplate::sendArticularVelocity ( const vpColVector qdot)

send to the controller a velocity expressed in the articular frame

Definition at line 98 of file vpRobotTemplate.cpp.

void vpRobotTemplate::sendCameraVelocity ( const vpColVector v)

send to the controller a velocity expressed in the camera frame

Definition at line 87 of file vpRobotTemplate.cpp.

void vpRobot::setMaxRotationVelocity ( const double  w_max)
inherited
void vpRobot::setMaxTranslationVelocity ( const double  v_max)
inherited

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 239 of file vpRobot.cpp.

References vpRobot::maxTranslationVelocity.

Referenced by vpSimulatorAfma6::setPosition(), vpRobotCamera::vpRobotCamera(), and vpSimulatorCamera::vpSimulatorCamera().

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

set a displacement (frame as to be specified)

set a displacement (frame as to ve specified)

Implements vpRobot.

Definition at line 124 of file vpRobotTemplate.cpp.

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

send to the controller a velocity (frame as to be specified)

send to the controller a velocity (frame as to ve specified)

Implements vpRobot.

Definition at line 103 of file vpRobotTemplate.cpp.

Member Data Documentation

vpMatrix vpRobot::eJe
protectedinherited
int vpRobot::eJeAvailable
protectedinherited

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

Definition at line 106 of file vpRobot.h.

Referenced by vpRobot::operator=(), vpRobotCamera::vpRobotCamera(), vpSimulatorCamera::vpSimulatorCamera(), vpSimulatorPioneer::vpSimulatorPioneer(), and vpSimulatorPioneerPan::vpSimulatorPioneerPan().

vpMatrix vpRobot::fJe
protectedinherited

robot Jacobian expressed in the robot reference frame available

Definition at line 108 of file vpRobot.h.

Referenced by vpRobot::operator=().

int vpRobot::fJeAvailable
protectedinherited

is the robot Jacobian expressed in the robot reference frame available

Definition at line 110 of file vpRobot.h.

Referenced by vpRobot::operator=(), vpRobotCamera::vpRobotCamera(), vpSimulatorCamera::vpSimulatorCamera(), vpSimulatorPioneer::vpSimulatorPioneer(), and vpSimulatorPioneerPan::vpSimulatorPioneerPan().

const double vpRobot::maxRotationVelocityDefault = 0.7
staticprotectedinherited

Definition at line 99 of file vpRobot.h.

double vpRobot::maxTranslationVelocity
protectedinherited
const double vpRobot::maxTranslationVelocityDefault = 0.2
staticprotectedinherited

Definition at line 97 of file vpRobot.h.