ViSP  2.9.0

#include <vpRobotPioneer.h>

+ Inheritance diagram for vpRobotPioneer:

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

 vpRobotPioneer ()
 
virtual ~vpRobotPioneer ()
 
void get_eJe (vpMatrix &eJe)
 
void getVelocity (const vpRobot::vpControlFrameType frame, vpColVector &velocity)
 
vpColVector getVelocity (const vpRobot::vpControlFrameType frame)
 
void init ()
 
void setVelocity (const vpRobot::vpControlFrameType frame, const vpColVector &vel)
 
void useSonar (bool usage)
 
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)
 
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
 

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) const
 

Protected Attributes

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

Static Protected Attributes

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

Detailed Description

Interface for Pioneer mobile robots based on Aria 3rd party library.

This class provides a position and speed control interface for Pioneer mobile robots. It inherits from the Aria ArRobot class. For more information about the model of the robot, see vpPioneer documentation.

Examples:
movePioneer.cpp, servoPioneerPanSegment3D.cpp, servoPioneerPoint2DDepth.cpp, servoPioneerPoint2DDepthWithoutVpServo.cpp, sonarPioneerReader.cpp, and tutorial-pioneer-robot.cpp.

Definition at line 65 of file vpRobotPioneer.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

vpRobotPioneer::vpRobotPioneer ( )

Default constructor that initializes Aria.

Definition at line 52 of file vpRobotPioneer.cpp.

References isInitialized.

vpRobotPioneer::~vpRobotPioneer ( )
virtual

Destructor.

Definition at line 62 of file vpRobotPioneer.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-continuous-gain-adaptive.cpp, tutorial-simu-pioneer-continuous-gain-constant.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().

void vpRobotPioneer::get_eJe ( vpMatrix eJe)
inlinevirtual

Get the robot Jacobian expressed at point E, the point located at the middle between the two wheels.

Parameters
eJe: Robot jacobian such as $(v_x, w_z) = {^e}{\bf J}e \; {\bf v}$ with $(v_x, w_z)$ respectively the translational and rotational control velocities of the mobile robot, $\bf v$ the six dimention velocity skew, and where
See also
get_eJe()

Implements vpRobot.

Examples:
servoPioneerPoint2DDepth.cpp, and servoPioneerPoint2DDepthWithoutVpServo.cpp.

Definition at line 89 of file vpRobotPioneer.h.

References vpUnicycle::get_eJe().

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 get_eJe(), vpSimulatorPioneer::get_eJe(), and vpSimulatorPioneerPan::get_eJe().

double vpRobot::getMaxTranslationVelocity ( void  ) const
inherited
vpColVector vpRobot::getPosition ( const vpRobot::vpControlFrameType  frame)
inherited

Return the current robot position in the specified frame.

Definition at line 207 of file vpRobot.cpp.

vpControlFrameType vpRobot::getRobotFrame ( void  ) const
inlineprotectedinherited
void vpRobotPioneer::getVelocity ( const vpRobot::vpControlFrameType  frame,
vpColVector velocity 
)

Gets the current translational velocity of the robot.

Parameters
frame: Control frame. For the moment, only vpRobot::ARTICULAR_FRAME to get left and right wheel velocities and vpRobot::REFERENCE_FRAME to get translational and rotational velocities are implemented.
velocity: A two dimension vector that corresponds to the current velocities applied to the robot.
  • If the frame is vpRobot::ARTICULAR_FRAME, first value is the velocity of the left wheel and second value is the velocity of the right wheel in m/s.
  • If the frame is vpRobot::REFERENCE_FRAME, first value is the translation velocity in m/s. Second value is the rotational velocity in rad/s.
Exceptions
vpRobotException::dimensionError: Velocity vector is not a 2 dimension vector.
vpRobotException::wrongStateError: If the specified control frame is not supported.
See also
getVelocity(const vpRobot::vpControlFrameType)
Examples:
movePioneer.cpp, sonarPioneerReader.cpp, and tutorial-pioneer-robot.cpp.

Definition at line 185 of file vpRobotPioneer.cpp.

References vpRobot::ARTICULAR_FRAME, init(), vpMath::rad(), vpRobot::REFERENCE_FRAME, vpColVector::resize(), and vpRobotException::wrongStateError.

Referenced by getVelocity().

vpColVector vpRobotPioneer::getVelocity ( const vpRobot::vpControlFrameType  frame)

Gets the current translational velocity of the robot.

Parameters
frame: Control frame. For the moment, only vpRobot::ARTICULAR_FRAME to get left and right wheel velocities and vpRobot::REFERENCE_FRAME to get translational and rotational velocities are implemented.
Returns
A two dimension vector that corresponds to the current velocities applied to the robot.
  • If the frame is vpRobot::ARTICULAR_FRAME, first value is the velocity of the left wheel and second value is the velocity of the right wheel in m/s.
  • If the frame is vpRobot::REFERENCE_FRAME, first value is the translation velocity in m/s. Second value is the rotational velocity in rad/s.
Exceptions
vpRobotException::dimensionError: Velocity vector is not a 2 dimension vector.
vpRobotException::wrongStateError: If the specified control frame is not supported.
See also
getVelocity(const vpRobot::vpControlFrameType, vpColVector &)

Definition at line 228 of file vpRobotPioneer.cpp.

References getVelocity().

void vpRobotPioneer::init ( void  )
virtual

Initialize the robot.

  • Sets the robot in asynchronous mode by starting a low level thread. The robot will be stopped if there is no connection to the robot at any given point.
  • Enables the motors on the robot, if it is connected.

Implements vpRobot.

Definition at line 151 of file vpRobotPioneer.cpp.

References isInitialized.

Referenced by getVelocity(), and setVelocity().

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

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

Referenced by vpRobotCamera::setVelocity(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), 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 251 of file vpRobot.cpp.

Referenced by vpRobotViper850::setMaxRotationVelocity(), and 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 227 of file vpRobot.cpp.

Referenced by vpSimulatorAfma6::setPosition().

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

Set the velocity (frame has to be specified) that will be applied to the robot.

Parameters
frame: Control frame. For the moment, only vpRobot::ARTICULAR_FRAME to control left and right wheel velocities and vpRobot::REFERENCE_FRAME to control translational and rotational velocities are implemented.
vel: A two dimension vector that corresponds to the velocities to apply to the robot.
  • If the frame is vpRobot::ARTICULAR_FRAME, first value is the velocity of the left wheel and second value is the velocity of the right wheel in m/s. In that case sets the velocity of the wheels independently.
  • If the frame is vpRobot::REFERENCE_FRAME, first value is the translation velocity in m/s. Second value is the rotational velocity in rad/s.

Note that to secure the usage of the robot, velocities are saturated to the maximum allowed which can be obtained by getMaxTranslationVelocity() and getMaxRotationVelocity(). To change the default values, use setMaxTranslationVelocity() and setMaxRotationVelocity().

Exceptions
vpRobotException::dimensionError: Velocity vector is not a 2 dimension vector.
vpRobotException::wrongStateError: If the specified control frame is not supported.

Implements vpRobot.

Examples:
movePioneer.cpp, servoPioneerPanSegment3D.cpp, servoPioneerPoint2DDepth.cpp, servoPioneerPoint2DDepthWithoutVpServo.cpp, and tutorial-pioneer-robot.cpp.

Definition at line 94 of file vpRobotPioneer.cpp.

References vpRobot::ARTICULAR_FRAME, vpMath::deg(), vpException::dimensionError, vpRobot::getMaxRotationVelocity(), vpRobot::getMaxTranslationVelocity(), init(), vpRobot::REFERENCE_FRAME, vpRobot::saturateVelocities(), vpColVector::size(), and vpRobotException::wrongStateError.

void vpRobotPioneer::useSonar ( bool  usage)
inline

Enable or disable sonar device usage.

Examples:
movePioneer.cpp, servoPioneerPanSegment3D.cpp, sonarPioneerReader.cpp, and tutorial-pioneer-robot.cpp.

Definition at line 134 of file vpRobotPioneer.h.

Member Data Documentation

int vpRobot::areJointLimitsAvailable
protectedinherited

Definition at line 111 of file vpRobot.h.

Referenced by vpRobot::operator=().

vpHomogeneousMatrix vpUnicycle::cMe_
protectedinherited
vpMatrix vpRobot::eJe
protectedinherited

robot Jacobian expressed in the end-effector frame

Definition at line 103 of file vpRobot.h.

Referenced by vpRobotCamera::get_eJe(), vpSimulatorCamera::get_eJe(), vpRobot::operator=(), and vpRobotAfma4::setVelocity().

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.

Referenced by vpRobot::operator=().

vpMatrix vpRobot::fJe
protectedinherited

robot Jacobian expressed in the robot reference frame available

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

Referenced by vpRobot::operator=().

bool vpRobotPioneer::isInitialized
protected

Definition at line 140 of file vpRobotPioneer.h.

Referenced by init(), and vpRobotPioneer().

double vpRobot::maxRotationVelocity
protectedinherited

Definition at line 97 of file vpRobot.h.

Referenced by vpRobot::operator=(), and vpRobotViper850::vpRobotViper850().

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.

Referenced by vpRobot::operator=().

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.

Referenced by vpRobot::operator=().

double* vpRobot::qmax
protectedinherited

Definition at line 113 of file vpRobot.h.

Referenced by vpRobot::operator=().

double* vpRobot::qmin
protectedinherited

Definition at line 112 of file vpRobot.h.

Referenced by vpRobot::operator=().