Visual Servoing Platform  version 3.4.0

#include <vpRobotCamera.h>

+ Inheritance diagram for vpRobotCamera:

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

 vpRobotCamera ()
 
virtual ~vpRobotCamera ()
 
Inherited functionalities from vpRobotCamera
void get_cVe (vpVelocityTwistMatrix &cVe) const
 
void get_eJe (vpMatrix &eJe)
 
void getPosition (vpHomogeneousMatrix &cMw) const
 
void getPosition (const vpRobot::vpControlFrameType frame, vpColVector &q)
 
void setPosition (const vpHomogeneousMatrix &cMw)
 
void setVelocity (const vpRobot::vpControlFrameType frame, const vpColVector &v)
 
Inherited functionalities from vpRobotSimulator
double getSamplingTime () const
 
virtual void setSamplingTime (const double &delta_t)
 
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 (double maxVr)
 
void setMaxTranslationVelocity (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

vpHomogeneousMatrix cMw_
 
double delta_t_
 
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 the simplest robot: a free flying camera. We recommend to use vpSimulatorCamera instead.

Deprecated:
This class is deprecated since ViSP 3.0.0.

This free flying camera has 6 dof; 3 in translation and 3 in rotation. It evolves as a gantry robot with respect to a world frame. This class is similar to vpSimulatorCamera class except that here the position of the robot is provided as the transformation from camera frame to world frame; cMw. Since the position of the camera frame evolves, this representation is less intuitive than the one implemented in vpSimulatorCamera where the transformation from world to camera frame is considered; wMc.

For this particular simulated robot, the end-effector and camera frame are confused. That means that the cMe transformation is equal to identity.

The robot jacobian expressed in the end-effector frame $ {^e}{\bf J}_e $ is also set to identity (see get_eJe()).

The following code shows how to control this robot in position and velocity.

#include <visp3/robot/vpRobotCamera.h>
int main()
{
robot.getPosition(cMw); // Position of the world frame in the camera frame
std::cout << "Default position of the world frame in the camera frame cMw:\n" << cMw << std::endl;
cMw[2][3] = 1.; // World frame is 1 meter along z axis in front of the camera frame
robot.setPosition(cMw); // Set the new position of the world frame in the camera frame
std::cout << "New position of the world frame in the camera frame cMw:\n" << cMw << std::endl;
robot.setSamplingTime(0.100); // Modify the default sampling time to 0.1 second
robot.setMaxTranslationVelocity(1.); // vx, vy and vz max set to 1 m/s
robot.setMaxRotationVelocity(vpMath::rad(90)); // wx, wy and wz max set to 90 deg/s
v = 0;
v[2] = 1.; // set v_z to 1 m/s
// The robot has moved from 0.1 meters along the z axis
robot.getPosition(cMw); // Position of the world frame in the camera frame
std::cout << "New position of the camera cMw:\n" << cMw << std::endl;
}

Definition at line 110 of file vpRobotCamera.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.

STATE_FORCE_TORQUE_CONTROL 

Initialize the force/torque controller.

Definition at line 64 of file vpRobot.h.

Constructor & Destructor Documentation

vpRobotCamera::vpRobotCamera ( )

Constructor.

Initialise the robot by a call to init().

Sampling time is set to 40 ms. To change it you should call setSamplingTime().

Robot jacobian expressed in the end-effector frame $ {^e}{\bf J}_e $ is set to identity (see get_eJe()).

robot.setSamplingTime(0.020); // Set the sampling time to 20 ms.

Definition at line 72 of file vpRobotCamera.cpp.

References vpRobot::areJointLimitsAvailable, vpRobot::eJe, vpRobot::eJeAvailable, vpMatrix::eye(), vpRobot::fJeAvailable, vpRobot::nDof, vpRobot::qmax, vpRobot::qmin, vpMath::rad(), vpRobot::setMaxRotationVelocity(), and vpRobot::setMaxTranslationVelocity().

vpRobotCamera::~vpRobotCamera ( )
virtual

Destructor.

Definition at line 99 of file vpRobotCamera.cpp.

Member Function Documentation

void vpRobotCamera::get_cVe ( vpVelocityTwistMatrix cVe) const

Get the twist transformation from camera frame to end-effector frame. This transformation allows to compute a velocity expressed in the end-effector frame into the camera frame.

Parameters
cVe: Twist transformation. Here this transformation is equal to identity since camera frame and end-effector frame are at the same location.

Definition at line 111 of file vpRobotCamera.cpp.

void vpRobotCamera::get_eJe ( vpMatrix eJe_)
virtual

Get the robot jacobian expressed in the end-effector frame. For that simple robot the Jacobian is the identity.

Parameters
eJe_: A 6 by 6 matrix representing the robot jacobian $ {^e}{\bf J}_e$ expressed in the end-effector frame.

Implements vpRobot.

Definition at line 124 of file vpRobotCamera.cpp.

References vpRobot::eJe.

void vpRobotCamera::getPosition ( vpHomogeneousMatrix cMw) const

Get the robot position as the transformation from camera frame to world frame.

Definition at line 189 of file vpRobotCamera.cpp.

References cMw_.

void vpRobotCamera::getPosition ( const vpRobot::vpControlFrameType  frame,
vpColVector q 
)
virtual
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
virtual vpRobotStateType vpRobot::getRobotState ( void  ) const
inlinevirtualinherited
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 vpRobotTemplate::setVelocity(), vpSimulatorCamera::setVelocity(), 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)
inherited
void vpRobot::setMaxTranslationVelocity ( 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(), and vpSimulatorCamera::vpSimulatorCamera().

void vpRobotCamera::setPosition ( const vpHomogeneousMatrix cMw)

Set the robot position as the transformation from camera frame to world frame.

Definition at line 250 of file vpRobotCamera.cpp.

References cMw_, vpRobot::getRobotState(), vpRobot::setRobotState(), and vpRobot::STATE_POSITION_CONTROL.

vpRobot::vpRobotStateType vpRobot::setRobotState ( const vpRobot::vpRobotStateType  newState)
virtualinherited
void vpRobotCamera::setVelocity ( const vpRobot::vpControlFrameType  frame,
const vpColVector v 
)
virtual

Send to the controller a velocity.

Parameters
frame: Control frame type. Only articular (vpRobot::ARTICULAR_FRAME) and camera frame (vpRobot::CAMERA_FRAME) are implemented.
v: Velocity twist to apply to the robot.
  • In the camera frame, this velocity is represented by a twist vector of dimension 6 $ {\bf v} = [v_x v_y v_z w_x w_y w_z]^t $ where $ v_x, v_y, v_z $ are the translation velocities in m/s and $ w_x, w_y, w_z $ the rotation velocities in rad/s applied in the camera frame.
  • In articular, the behavior is the same as in camera frame.

Internally, the exponential map (vpExponentialMap) is used to update the camera position from its velocity after applying the velocity during a sampling time. This sampling time can be set using setSamplingTime().

See also
setSamplingTime()

Implements vpRobot.

Definition at line 148 of file vpRobotCamera.cpp.

References vpRobot::ARTICULAR_FRAME, vpRobot::CAMERA_FRAME, cMw_, vpRobotSimulator::delta_t_, vpExponentialMap::direct(), vpRobot::END_EFFECTOR_FRAME, vpRobot::getMaxRotationVelocity(), vpRobot::getMaxTranslationVelocity(), vpRobot::getRobotState(), vpHomogeneousMatrix::inverse(), vpRobot::MIXT_FRAME, vpRobot::REFERENCE_FRAME, vpRobot::saturateVelocities(), vpRobot::setRobotState(), vpRobot::STATE_VELOCITY_CONTROL, and vpRobotException::wrongStateError.

Member Data Documentation

int vpRobot::areJointLimitsAvailable
protectedinherited
vpHomogeneousMatrix vpRobotCamera::cMw_
protected

Definition at line 113 of file vpRobotCamera.h.

Referenced by getPosition(), setPosition(), and setVelocity().

double vpRobotSimulator::delta_t_
protectedinherited
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(), 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 vpRobotFlirPtu::get_fJe(), and 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(), vpSimulatorCamera::vpSimulatorCamera(), vpSimulatorPioneer::vpSimulatorPioneer(), and vpSimulatorPioneerPan::vpSimulatorPioneerPan().

const double vpRobot::maxRotationVelocityDefault = 0.7
staticprotectedinherited

Definition at line 99 of file vpRobot.h.

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

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

Definition at line 97 of file vpRobot.h.

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