ViSP  2.8.0

#include <vpSimulatorPioneer.h>

+ Inheritance diagram for vpSimulatorPioneer:

Public Types

enum  vpRobotStateType { STATE_STOP, STATE_VELOCITY_CONTROL, STATE_POSITION_CONTROL, STATE_ACCELERATION_CONTROL }
 
enum  vpControlFrameType { REFERENCE_FRAME, ARTICULAR_FRAME, CAMERA_FRAME, MIXT_FRAME }
 

Public Member Functions

 vpSimulatorPioneer ()
 
virtual ~vpSimulatorPioneer ()
 
void get_eJe (vpMatrix &eJe)
 
void getPosition (vpHomogeneousMatrix &wMc) const
 
void getPosition (const vpRobot::vpControlFrameType frame, vpColVector &q)
 
void setVelocity (const vpRobot::vpControlFrameType frame, const vpColVector &vel)
 
void set_cMe (const vpHomogeneousMatrix &cMe)
 
void set_eJe (const vpMatrix &eJe)
 
vpHomogeneousMatrix get_cMe () const
 
vpVelocityTwistMatrix get_cVe () const
 
void get_cVe (vpVelocityTwistMatrix &cVe) const
 
vpMatrix get_eJe () const
 
double getSamplingTime () const
 
virtual void setSamplingTime (const double &delta_t)
 
double getMaxTranslationVelocity (void) const
 
double getMaxRotationVelocity (void) const
 
vpColVector getPosition (const vpRobot::vpControlFrameType frame)
 
virtual vpRobotStateType getRobotState (void)
 
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 vpColVector saturateVelocities (const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
 

Protected Member Functions

vpControlFrameType setRobotFrame (vpRobot::vpControlFrameType newFrame)
 
vpControlFrameType getRobotFrame (void)
 

Protected Attributes

vpHomogeneousMatrix wMc_
 
vpHomogeneousMatrix wMe_
 
double xm_
 
double ym_
 
double theta_
 
vpHomogeneousMatrix cMe_
 
vpMatrix eJe_
 
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 Pioneer mobile robot simulator equipped with a static camera.

It intends to simulate the mobile robot described in vpPioneer class. This robot has 2 dof: $(v_x, w_z)$, the translational and rotational velocities that are applied at point E.

The robot position evolves with respect to a world frame; wMc. When a new joint velocity is applied to the robot using setVelocity(), the position of the camera wrt the world frame is updated.

pioneer.png

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

#include <visp/vpSimulatorPioneer.h>
int main()
{
robot.getPosition(wMc); // Position of the camera in the world frame
std::cout << "Default position of the camera in the world frame wMc:\n" << wMc << std::endl;
robot.setSamplingTime(0.100); // Modify the default sampling time to 0.1 second
robot.setMaxTranslationVelocity(1.); // vx max set to 1 m/s
robot.setMaxRotationVelocity(vpMath::rad(90)); // wz max set to 90 deg/s
vpColVector v(2); // we control vx and wz dof
v = 0;
v[0] = 1.; // set vx to 1 m/s
// The robot has moved from 0.1 meters along the z axis
robot.getPosition(wMc); // Position of the camera in the world frame
std::cout << "New position of the camera wMc:\n" << wMc << std::endl;
}

The usage of this class is also highlighted in Tutorial: Visual servo simulation on a pioneer-like unicycle robot.

Examples:
tutorial-simu-pioneer.cpp.

Definition at line 104 of file vpSimulatorPioneer.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 space.

CAMERA_FRAME 

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

MIXT_FRAME 

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

Definition at line 78 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 66 of file vpRobot.h.

Constructor & Destructor Documentation

vpSimulatorPioneer::vpSimulatorPioneer ( )

Constructor.

Definition at line 60 of file vpSimulatorPioneer.cpp.

vpSimulatorPioneer::~vpSimulatorPioneer ( )
virtual

Destructor.

Definition at line 93 of file vpSimulatorPioneer.cpp.

Member Function Documentation

vpHomogeneousMatrix vpUnicycle::get_cMe ( ) const
inlineinherited

Return the tranformation ${^c}{\bf M}_e$ between the camera frame and the mobile robot end effector frame.

Definition at line 78 of file vpUnicycle.h.

vpVelocityTwistMatrix vpUnicycle::get_cVe ( ) const
inlineinherited

Return the twist transformation from camera frame to the mobile robot end effector frame. This transformation allows to compute a velocity expressed in the end effector frame into the camera frame.

Examples:
servoPioneerPanSegment3D.cpp, servoPioneerPoint2DDepth.cpp, servoPioneerPoint2DDepthWithoutVpServo.cpp, tutorial-simu-pioneer-pan.cpp, and tutorial-simu-pioneer.cpp.

Definition at line 89 of file vpUnicycle.h.

References vpVelocityTwistMatrix::buildFrom().

Referenced by vpUnicycle::get_cVe().

void vpUnicycle::get_cVe ( vpVelocityTwistMatrix cVe) const
inlineinherited

Return the twist transformation from camera frame to the mobile robot end effector frame. This transformation allows to compute a velocity expressed in the end effector frame into the camera frame.

See also
get_cVe()

Definition at line 104 of file vpUnicycle.h.

References vpUnicycle::get_cVe().

vpMatrix vpUnicycle::get_eJe ( ) const
inlineinherited

Return the robot jacobian ${^e}{\bf J}_e$ expressed in the end effector frame.

Returns
The robot jacobian such as ${\bf v} = {^e}{\bf J}_e \; \dot{\bf q}$ with $\dot{\bf q} = (v_x, w_z)$ the robot control velocities and $\bf v$ the six dimention velocity skew.
Examples:
servoPioneerPanSegment3D.cpp.

Definition at line 115 of file vpUnicycle.h.

Referenced by vpRobotPioneer::get_eJe(), get_eJe(), and vpSimulatorPioneerPan::get_eJe().

void vpSimulatorPioneer::get_eJe ( vpMatrix eJe)
virtual

Get the robot jacobian expressed in the end-effector frame. The jacobian expression is given in vpPioneer class.

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

Implements vpRobot.

Examples:
tutorial-simu-pioneer.cpp.

Definition at line 105 of file vpSimulatorPioneer.cpp.

References vpUnicycle::get_eJe().

double vpRobot::getMaxTranslationVelocity ( void  ) const
inherited
void vpSimulatorPioneer::getPosition ( vpHomogeneousMatrix wMc) const

Get the robot position in the world frame.

Examples:
tutorial-simu-pioneer.cpp.

Definition at line 191 of file vpSimulatorPioneer.cpp.

References wMc_.

void vpSimulatorPioneer::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 171 of file vpRobot.cpp.

vpControlFrameType vpRobot::getRobotFrame ( void  )
inlineprotectedinherited
double vpRobotSimulator::getSamplingTime ( ) const
inlineinherited
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 <visp/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 116 of file vpRobot.cpp.

References vpException::dimensionError, and vpColVector::size().

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

void vpUnicycle::set_cMe ( const vpHomogeneousMatrix cMe)
inlineinherited

Set the transformation between the camera frame and the end effector frame.

Definition at line 123 of file vpUnicycle.h.

Referenced by vpPioneer::vpPioneer(), and vpPioneerPan::vpPioneerPan().

void vpUnicycle::set_eJe ( const vpMatrix eJe)
inlineinherited

Set the robot jacobian ${^e}{\bf J}_e$ expressed in the end effector frame.

Parameters
eJe: The robot jacobian to set such as ${\bf v} = {^e}{\bf J}_e \; \dot{\bf q}$ with $\dot{\bf q} = (v_x, w_z)$ the robot control velocities and $\bf v$ the six dimention velocity skew.

Definition at line 134 of file vpUnicycle.h.

Referenced by vpPioneer::vpPioneer(), and vpPioneerPan::vpPioneerPan().

void vpRobot::setMaxRotationVelocity ( const double  w_max)
inherited

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

Parameters
w_max: Maximum rotation velocity expressed in rad/s.
Examples:
servoMomentPoints.cpp, servoSimu4Points.cpp, and servoSimuSphere.cpp.

Definition at line 215 of file vpRobot.cpp.

Referenced by vpSimulatorAfma6::setPosition().

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, and servoSimuSphere.cpp.

Definition at line 191 of file vpRobot.cpp.

Referenced by vpSimulatorAfma6::setPosition().

void vpSimulatorPioneer::setVelocity ( const vpRobot::vpControlFrameType  frame,
const vpColVector v 
)
virtual

Member Data Documentation

int vpRobot::areJointLimitsAvailable
protectedinherited

Definition at line 111 of file vpRobot.h.

vpHomogeneousMatrix vpUnicycle::cMe_
protectedinherited

Definition at line 140 of file vpUnicycle.h.

Referenced by setVelocity(), and vpSimulatorPioneerPan::setVelocity().

double vpRobotSimulator::delta_t_
protectedinherited
vpMatrix vpUnicycle::eJe_
protectedinherited

Definition at line 141 of file vpUnicycle.h.

int vpRobot::eJeAvailable
protectedinherited

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

Definition at line 105 of file vpRobot.h.

vpMatrix vpRobot::fJe
protectedinherited

robot Jacobian expressed in the robot reference frame available

Definition at line 107 of file vpRobot.h.

Referenced by vpSimulatorAfma6::computeArticularVelocity(), vpSimulatorViper850::computeArticularVelocity(), vpSimulatorAfma6::getVelocity(), and vpSimulatorViper850::getVelocity().

int vpRobot::fJeAvailable
protectedinherited

is the robot Jacobian expressed in the robot reference frame available

Definition at line 109 of file vpRobot.h.

double vpRobot::maxRotationVelocity
protectedinherited

Definition at line 97 of file vpRobot.h.

const double vpRobot::maxRotationVelocityDefault = 0.7
staticprotectedinherited

Definition at line 98 of file vpRobot.h.

double vpRobot::maxTranslationVelocity
protectedinherited

Definition at line 95 of file vpRobot.h.

const double vpRobot::maxTranslationVelocityDefault = 0.2
staticprotectedinherited

Definition at line 96 of file vpRobot.h.

int vpRobot::nDof
protectedinherited

number of degrees of freedom

Definition at line 101 of file vpRobot.h.

double* vpRobot::qmax
protectedinherited

Definition at line 113 of file vpRobot.h.

double* vpRobot::qmin
protectedinherited

Definition at line 112 of file vpRobot.h.

double vpSimulatorPioneer::theta_
protected

Definition at line 117 of file vpSimulatorPioneer.h.

Referenced by setVelocity().

vpHomogeneousMatrix vpSimulatorPioneer::wMc_
protected

Definition at line 109 of file vpSimulatorPioneer.h.

Referenced by getPosition(), and setVelocity().

vpHomogeneousMatrix vpSimulatorPioneer::wMe_
protected

Definition at line 112 of file vpSimulatorPioneer.h.

Referenced by setVelocity().

double vpSimulatorPioneer::xm_
protected

Definition at line 115 of file vpSimulatorPioneer.h.

Referenced by setVelocity().

double vpSimulatorPioneer::ym_
protected

Definition at line 116 of file vpSimulatorPioneer.h.

Referenced by setVelocity().