Visual Servoing Platform  version 3.4.0

#include <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
 
virtual void getPosition (const vpRobot::vpControlFrameType frame, vpColVector &q)=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_template

Definition at line 58 of file vpRobot.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.

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::vpRobot ( void  )

Definition at line 53 of file vpRobot.cpp.

vpRobot::vpRobot ( const vpRobot robot)

Definition at line 61 of file vpRobot.cpp.

vpRobot::~vpRobot ( )
virtual

Destructor that free allocated memory.

Definition at line 73 of file vpRobot.cpp.

References qmax, and qmin.

Member Function Documentation

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

Return the current robot position in the specified frame.

Definition at line 216 of file vpRobot.cpp.

References getPosition().

vpControlFrameType vpRobot::getRobotFrame ( void  ) const
inlineprotected
virtual vpRobotStateType vpRobot::getRobotState ( void  ) const
inlinevirtual
vpRobot & vpRobot::operator= ( const vpRobot robot)
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>
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 vpRobotTemplate::setVelocity(), vpSimulatorCamera::setVelocity(), vpRobotCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpRobotPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotKinova::setVelocity(), vpRobotFlirPtu::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotFranka::setVelocity(), vpRobotViper650::setVelocity(), and vpRobotViper850::setVelocity().

void vpRobot::setMaxRotationVelocity ( double  w_max)
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 239 of file vpRobot.cpp.

References maxTranslationVelocity.

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

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

Member Data Documentation

vpMatrix vpRobot::eJe
protected
int vpRobot::eJeAvailable
protected

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

Definition at line 106 of file vpRobot.h.

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

vpMatrix vpRobot::fJe
protected

robot Jacobian expressed in the robot reference frame available

Definition at line 108 of file vpRobot.h.

Referenced by vpRobotFlirPtu::get_fJe(), and operator=().

int vpRobot::fJeAvailable
protected

is the robot Jacobian expressed in the robot reference frame available

Definition at line 110 of file vpRobot.h.

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

const double vpRobot::maxRotationVelocityDefault = 0.7
staticprotected

Definition at line 99 of file vpRobot.h.

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

double vpRobot::maxTranslationVelocity
protected
const double vpRobot::maxTranslationVelocityDefault = 0.2
staticprotected

Definition at line 97 of file vpRobot.h.

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