ViSP
2.10.0
|
#include <vpSimulatorPioneer.h>
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 } |
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 | |
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 |
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: , 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.
The following code shows how to control this robot in position and velocity.
The usage of this class is also highlighted in Tutorial: Visual servo simulation on a pioneer-like unicycle robot.
Definition at line 104 of file vpSimulatorPioneer.h.
|
inherited |
Robot control frames.
|
inherited |
vpSimulatorPioneer::vpSimulatorPioneer | ( | ) |
Constructor.
Definition at line 60 of file vpSimulatorPioneer.cpp.
|
virtual |
Destructor.
Definition at line 94 of file vpSimulatorPioneer.cpp.
|
inlineinherited |
Return the tranformation between the camera frame and the mobile robot end effector frame.
Definition at line 78 of file vpUnicycle.h.
|
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.
Definition at line 89 of file vpUnicycle.h.
References vpVelocityTwistMatrix::buildFrom().
Referenced by vpUnicycle::get_cVe().
|
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.
Definition at line 104 of file vpUnicycle.h.
References vpUnicycle::get_cVe().
|
inlineinherited |
Return the robot jacobian expressed in the end effector frame.
Definition at line 115 of file vpUnicycle.h.
Referenced by vpRobotPioneer::get_eJe(), get_eJe(), and vpSimulatorPioneerPan::get_eJe().
|
virtual |
Get the robot jacobian expressed in the end-effector frame. The jacobian expression is given in vpPioneer class.
_eJe | : A 6 by 2 matrix representing the robot jacobian expressed in the end-effector frame. |
Implements vpRobot.
Definition at line 106 of file vpSimulatorPioneer.cpp.
References vpUnicycle::get_eJe().
|
inherited |
Get the maximal rotation velocity that can be sent to the robot during a velocity control.
Definition at line 279 of file vpRobot.cpp.
Referenced by vpSimulatorAfma6::computeArticularVelocity(), vpSimulatorViper850::computeArticularVelocity(), vpSimulatorAfma6::findHighestPositioningSpeed(), vpSimulatorViper850::findHighestPositioningSpeed(), vpSimulatorAfma6::setPosition(), vpRobotCamera::setVelocity(), vpSimulatorCamera::setVelocity(), setVelocity(), vpRobotPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpSimulatorAfma6::setVelocity(), vpSimulatorViper850::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotViper650::setVelocity(), and vpRobotViper850::setVelocity().
|
inherited |
Get the maximal translation velocity that can be sent to the robot during a velocity control.
Definition at line 254 of file vpRobot.cpp.
Referenced by vpSimulatorAfma6::setPosition(), vpRobotCamera::setVelocity(), vpSimulatorCamera::setVelocity(), setVelocity(), vpRobotPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpSimulatorAfma6::setVelocity(), vpSimulatorViper850::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotViper650::setVelocity(), and vpRobotViper850::setVelocity().
void vpSimulatorPioneer::getPosition | ( | vpHomogeneousMatrix & | wMc | ) | const |
Get the robot position in the world frame.
Definition at line 192 of file vpSimulatorPioneer.cpp.
References wMc_.
|
virtual |
Get the robot position (frame has to be specified).
Implements vpRobot.
Definition at line 215 of file vpSimulatorPioneer.cpp.
References vpRobot::ARTICULAR_FRAME, vpRxyzVector::buildFrom(), vpRobot::CAMERA_FRAME, vpHomogeneousMatrix::extract(), vpRobot::MIXT_FRAME, vpRobot::REFERENCE_FRAME, vpColVector::resize(), and wMc_.
|
inherited |
Return the current robot position in the specified frame.
Definition at line 222 of file vpRobot.cpp.
|
inlineprotectedinherited |
Definition at line 162 of file vpRobot.h.
Referenced by vpSimulatorAfma6::computeArticularVelocity(), and vpSimulatorViper850::computeArticularVelocity().
|
inlinevirtualinherited |
Definition at line 140 of file vpRobot.h.
Referenced by vpRobotBiclops::getPosition(), vpRobotBiclops::getVelocity(), vpRobotCamera::setPosition(), vpSimulatorCamera::setPosition(), vpRobotPtu46::setPosition(), vpRobotBiclops::setPosition(), vpSimulatorAfma6::setPosition(), vpSimulatorViper850::setPosition(), vpRobotAfma4::setPosition(), vpRobotAfma6::setPosition(), vpRobotViper650::setPosition(), vpRobotViper850::setPosition(), vpRobotPtu46::setRobotState(), vpRobotBiclops::setRobotState(), vpSimulatorAfma6::setRobotState(), vpSimulatorViper850::setRobotState(), vpRobotAfma4::setRobotState(), vpRobotAfma6::setRobotState(), vpRobotViper650::setRobotState(), vpRobotViper850::setRobotState(), vpRobotCamera::setVelocity(), vpSimulatorCamera::setVelocity(), setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotPtu46::setVelocity(), vpRobotBiclops::setVelocity(), vpSimulatorAfma6::setVelocity(), vpSimulatorViper850::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotViper650::setVelocity(), vpRobotViper850::setVelocity(), vpSimulatorAfma6::stopMotion(), vpSimulatorViper850::stopMotion(), vpRobotViper650::stopMotion(), and vpRobotViper850::stopMotion().
|
inlineinherited |
Return the sampling time.
Definition at line 83 of file vpRobotSimulator.h.
Referenced by vpSimulatorAfma6::updateArticularPosition(), and vpSimulatorViper850::updateArticularPosition().
|
staticinherited |
Saturate velocities.
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. |
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.
Definition at line 167 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().
|
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().
|
inlineinherited |
Set the robot jacobian expressed in the end effector frame.
eJe | : The robot jacobian to set such as with the robot control velocities and the six dimention velocity skew. |
Definition at line 134 of file vpUnicycle.h.
Referenced by vpPioneer::vpPioneer(), and vpPioneerPan::vpPioneerPan().
|
inherited |
Set the maximal rotation velocity that can be sent to the robot during a velocity control.
w_max | : Maximum rotation velocity expressed in rad/s. |
Definition at line 266 of file vpRobot.cpp.
Referenced by vpRobotViper650::setMaxRotationVelocity(), vpRobotViper850::setMaxRotationVelocity(), and vpSimulatorAfma6::setPosition().
|
inherited |
Set the maximal translation velocity that can be sent to the robot during a velocity control.
v_max | : Maximum translation velocity expressed in m/s. |
Definition at line 242 of file vpRobot.cpp.
Referenced by vpSimulatorAfma6::setPosition().
|
protectedinherited |
Definition at line 212 of file vpRobot.cpp.
Referenced by vpSimulatorAfma6::init(), vpSimulatorViper850::init(), vpSimulatorCamera::setVelocity(), setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpSimulatorAfma6::setVelocity(), and vpSimulatorViper850::setVelocity().
|
virtualinherited |
Reimplemented in vpRobotViper850, vpRobotViper650, vpRobotAfma6, vpRobotAfma4, vpSimulatorViper850, vpSimulatorAfma6, vpRobotBiclops, and vpRobotPtu46.
Definition at line 205 of file vpRobot.cpp.
Referenced by vpRobotCamera::setPosition(), vpSimulatorCamera::setPosition(), vpRobotPtu46::setRobotState(), vpRobotBiclops::setRobotState(), vpSimulatorAfma6::setRobotState(), vpSimulatorViper850::setRobotState(), vpRobotAfma4::setRobotState(), vpRobotAfma6::setRobotState(), vpRobotViper650::setRobotState(), vpRobotViper850::setRobotState(), vpRobotCamera::setVelocity(), vpSimulatorCamera::setVelocity(), setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpSimulatorAfma6::stopMotion(), and vpSimulatorViper850::stopMotion().
|
inlinevirtualinherited |
Set the sampling time.
delta_t | : Sampling time in second used to compute the robot displacement from the velocity applied to the robot during this time. |
Reimplemented in vpRobotWireFrameSimulator.
Definition at line 95 of file vpRobotSimulator.h.
|
virtual |
Send to the controller a velocity.
frame | : Control frame type. Only vpRobot::ARTICULAR_FRAME is implemented. |
v | : Velocity vector to apply to the robot. |
Depending on the velocity specified as input, the robot position is updated using the sampling time that can be modified using setSamplingTime().
Implements vpRobot.
Definition at line 126 of file vpSimulatorPioneer.cpp.
References vpRobot::ARTICULAR_FRAME, vpHomogeneousMatrix::buildFrom(), vpRobot::CAMERA_FRAME, vpUnicycle::cMe_, vpRobotSimulator::delta_t_, vpException::dimensionError, vpRobot::getMaxRotationVelocity(), vpRobot::getMaxTranslationVelocity(), vpRobot::getRobotState(), vpHomogeneousMatrix::inverse(), vpRobot::MIXT_FRAME, vpRobot::REFERENCE_FRAME, vpRobot::saturateVelocities(), vpRobot::setRobotFrame(), vpRobot::setRobotState(), vpColVector::size(), vpRobot::STATE_VELOCITY_CONTROL, theta_, vpERROR_TRACE, wMc_, wMe_, vpRobotException::wrongStateError, xm_, and ym_.
|
inlineinherited |
Definition at line 158 of file vpRobot.h.
Referenced by vpRobotAfma4::vpRobotAfma4(), vpRobotAfma6::vpRobotAfma6(), vpRobotViper650::vpRobotViper650(), and vpRobotViper850::vpRobotViper850().
|
protectedinherited |
Definition at line 111 of file vpRobot.h.
Referenced by vpRobot::operator=().
|
protectedinherited |
Definition at line 140 of file vpUnicycle.h.
Referenced by setVelocity(), and vpSimulatorPioneerPan::setVelocity().
|
protectedinherited |
Definition at line 68 of file vpRobotSimulator.h.
Referenced by vpRobotCamera::setVelocity(), vpSimulatorCamera::setVelocity(), setVelocity(), and vpSimulatorPioneerPan::setVelocity().
|
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().
|
protectedinherited |
Definition at line 141 of file vpUnicycle.h.
|
protectedinherited |
is the robot Jacobian expressed in the end-effector frame available
Definition at line 105 of file vpRobot.h.
Referenced by vpRobot::operator=().
|
protectedinherited |
robot Jacobian expressed in the robot reference frame available
Definition at line 107 of file vpRobot.h.
Referenced by vpRobot::operator=().
|
protectedinherited |
is the robot Jacobian expressed in the robot reference frame available
Definition at line 109 of file vpRobot.h.
Referenced by vpRobot::operator=().
|
protectedinherited |
Definition at line 97 of file vpRobot.h.
Referenced by vpRobot::operator=(), vpRobotViper650::vpRobotViper650(), and vpRobotViper850::vpRobotViper850().
|
staticprotectedinherited |
|
protectedinherited |
Definition at line 95 of file vpRobot.h.
Referenced by vpRobot::operator=().
|
staticprotectedinherited |
|
protectedinherited |
number of degrees of freedom
Definition at line 101 of file vpRobot.h.
Referenced by vpRobot::operator=().
|
protectedinherited |
Definition at line 113 of file vpRobot.h.
Referenced by vpRobot::operator=(), and vpRobot::~vpRobot().
|
protectedinherited |
Definition at line 112 of file vpRobot.h.
Referenced by vpRobot::operator=(), and vpRobot::~vpRobot().
|
protected |
Definition at line 117 of file vpSimulatorPioneer.h.
Referenced by setVelocity().
|
protectedinherited |
Definition at line 115 of file vpRobot.h.
Referenced by vpRobotAfma4::init(), vpRobotAfma6::init(), vpRobotViper850::init(), vpRobotViper650::init(), vpRobot::operator=(), vpRobotAfma4::vpRobotAfma4(), vpRobotAfma6::vpRobotAfma6(), vpRobotViper650::vpRobotViper650(), and vpRobotViper850::vpRobotViper850().
|
protected |
Definition at line 109 of file vpSimulatorPioneer.h.
Referenced by getPosition(), and setVelocity().
|
protected |
Definition at line 112 of file vpSimulatorPioneer.h.
Referenced by setVelocity().
|
protected |
Definition at line 115 of file vpSimulatorPioneer.h.
Referenced by setVelocity().
|
protected |
Definition at line 116 of file vpSimulatorPioneer.h.
Referenced by setVelocity().