Visual Servoing Platform
version 3.3.0 under development (2020-02-17)
|
#include <visp3/robot/vpSimulatorPioneer.h>
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 | |
vpSimulatorPioneer () | |
virtual | ~vpSimulatorPioneer () |
Inherited functionalities from 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) |
Inherited functionalities from vpUnicycle | |
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 |
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 | 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 103 of file vpSimulatorPioneer.h.
|
inherited |
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. |
|
inherited |
Robot control states.
vpSimulatorPioneer::vpSimulatorPioneer | ( | ) |
Constructor.
Definition at line 56 of file vpSimulatorPioneer.cpp.
References vpRobot::areJointLimitsAvailable, vpUnicycle::cMe_, vpRobot::eJeAvailable, vpRobot::fJeAvailable, vpHomogeneousMatrix::inverse(), vpRobot::nDof, vpRobot::qmax, vpRobot::qmin, theta_, wMc_, wMe_, xm_, and ym_.
|
virtual |
Destructor.
Definition at line 85 of file vpSimulatorPioneer.cpp.
|
inlineinherited |
Return the tranformation between the camera frame and the mobile robot end effector frame.
Definition at line 74 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 82 of file vpUnicycle.h.
References vpVelocityTwistMatrix::buildFrom().
|
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 97 of file vpUnicycle.h.
References vpUnicycle::get_cVe().
Referenced by vpUnicycle::get_cVe().
|
inlineinherited |
Return the robot jacobian expressed in the end effector frame.
Definition at line 107 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 94 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 273 of file vpRobot.cpp.
References vpRobot::maxRotationVelocity.
Referenced by vpSimulatorAfma6::computeArticularVelocity(), vpSimulatorViper850::computeArticularVelocity(), vpSimulatorAfma6::findHighestPositioningSpeed(), vpSimulatorViper850::findHighestPositioningSpeed(), vpSimulatorAfma6::setPosition(), vpRobotTemplate::setVelocity(), vpSimulatorCamera::setVelocity(), vpRobotCamera::setVelocity(), setVelocity(), vpRobotPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotFlirPtu::setVelocity(), vpSimulatorAfma6::setVelocity(), vpSimulatorViper850::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotFranka::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 251 of file vpRobot.cpp.
References vpRobot::maxTranslationVelocity.
Referenced by vpSimulatorAfma6::setPosition(), vpRobotTemplate::setVelocity(), vpSimulatorCamera::setVelocity(), vpRobotCamera::setVelocity(), setVelocity(), vpRobotPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotFlirPtu::setVelocity(), vpSimulatorAfma6::setVelocity(), vpSimulatorViper850::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotFranka::setVelocity(), vpRobotViper650::setVelocity(), and vpRobotViper850::setVelocity().
void vpSimulatorPioneer::getPosition | ( | vpHomogeneousMatrix & | wMc | ) | const |
Get the robot position in the world frame.
Definition at line 170 of file vpSimulatorPioneer.cpp.
References wMc_.
|
virtual |
Get the robot position (frame has to be specified).
Implements vpRobot.
Definition at line 191 of file vpSimulatorPioneer.cpp.
References vpRobot::ARTICULAR_FRAME, vpRxyzVector::buildFrom(), vpRobot::CAMERA_FRAME, vpRobot::END_EFFECTOR_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 216 of file vpRobot.cpp.
References vpRobot::getPosition().
|
inlineprotectedinherited |
Definition at line 172 of file vpRobot.h.
Referenced by vpSimulatorAfma6::computeArticularVelocity(), and vpSimulatorViper850::computeArticularVelocity().
|
inlinevirtualinherited |
Definition at line 144 of file vpRobot.h.
Referenced by vpRobotBiclops::getPosition(), vpRobotBiclops::getVelocity(), vpRobotPtu46::setPosition(), vpRobotBiclops::setPosition(), vpSimulatorCamera::setPosition(), vpRobotCamera::setPosition(), vpSimulatorAfma6::setPosition(), vpRobotAfma4::setPosition(), vpSimulatorViper850::setPosition(), vpRobotAfma6::setPosition(), vpRobotFranka::setPosition(), vpRobotViper650::setPosition(), vpRobotViper850::setPosition(), vpRobotPtu46::setRobotState(), vpRobotBiclops::setRobotState(), vpRobotFlirPtu::setRobotState(), vpSimulatorAfma6::setRobotState(), vpSimulatorViper850::setRobotState(), vpRobotAfma4::setRobotState(), vpRobotAfma6::setRobotState(), vpRobotFranka::setRobotState(), vpRobotViper650::setRobotState(), vpRobotViper850::setRobotState(), vpRobotTemplate::setVelocity(), vpRobotPtu46::setVelocity(), vpRobotBiclops::setVelocity(), vpSimulatorCamera::setVelocity(), vpRobotCamera::setVelocity(), setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotFlirPtu::setVelocity(), vpSimulatorAfma6::setVelocity(), vpSimulatorViper850::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotFranka::setVelocity(), vpRobotViper650::setVelocity(), vpRobotViper850::setVelocity(), vpRobotFlirPtu::stopMotion(), vpSimulatorAfma6::stopMotion(), vpSimulatorViper850::stopMotion(), vpRobotFranka::stopMotion(), vpRobotViper650::stopMotion(), and vpRobotViper850::stopMotion().
|
inlineinherited |
Return the sampling time.
Definition at line 82 of file vpRobotSimulator.h.
Referenced by vpVirtualGrabber::acquire(), 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 163 of file vpRobot.cpp.
References vpException::dimensionError, and vpArray2D< Type >::size().
Referenced by vpRobotTemplate::setVelocity(), vpSimulatorCamera::setVelocity(), vpRobotCamera::setVelocity(), setVelocity(), vpRobotPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotFlirPtu::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotFranka::setVelocity(), vpRobotViper650::setVelocity(), and vpRobotViper850::setVelocity().
|
inlineinherited |
Set the transformation between the camera frame and the end effector frame.
Definition at line 113 of file vpUnicycle.h.
Referenced by vpPioneer::vpPioneer(), vpPioneerPan::vpPioneerPan(), and vpPioneer::~vpPioneer().
|
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 123 of file vpUnicycle.h.
Referenced by vpPioneer::vpPioneer(), vpPioneerPan::vpPioneerPan(), and vpPioneer::~vpPioneer().
|
inherited |
Set the maximal rotation velocity that can be sent to the robot during a velocity control.
w_max | : Maximum rotational velocity expressed in rad/s. |
Definition at line 260 of file vpRobot.cpp.
References vpRobot::maxRotationVelocity.
Referenced by vpRobotViper650::getControlMode(), vpRobotViper850::getControlMode(), vpRobotViper650::setMaxRotationVelocity(), vpRobotViper850::setMaxRotationVelocity(), vpSimulatorAfma6::setPosition(), vpRobotCamera::vpRobotCamera(), and vpSimulatorCamera::vpSimulatorCamera().
|
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 239 of file vpRobot.cpp.
References vpRobot::maxTranslationVelocity.
Referenced by vpSimulatorAfma6::setPosition(), vpRobotCamera::vpRobotCamera(), and vpSimulatorCamera::vpSimulatorCamera().
|
protectedinherited |
Definition at line 207 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, vpRobotFranka, vpRobotAfma6, vpRobotAfma4, vpSimulatorViper850, vpSimulatorAfma6, vpRobotFlirPtu, vpRobotBiclops, and vpRobotPtu46.
Definition at line 201 of file vpRobot.cpp.
Referenced by vpRobotViper650::getControlMode(), vpRobotViper850::getControlMode(), vpRobotFranka::getHandler(), vpRobotFlirPtu::set_eMc(), vpSimulatorCamera::setPosition(), vpRobotCamera::setPosition(), vpSimulatorAfma6::setPositioningVelocity(), vpSimulatorViper850::setPositioningVelocity(), vpRobotPtu46::setRobotState(), vpRobotBiclops::setRobotState(), vpRobotFlirPtu::setRobotState(), vpSimulatorAfma6::setRobotState(), vpSimulatorViper850::setRobotState(), vpRobotAfma4::setRobotState(), vpRobotAfma6::setRobotState(), vpRobotFranka::setRobotState(), vpRobotViper650::setRobotState(), vpRobotViper850::setRobotState(), vpSimulatorCamera::setVelocity(), vpRobotCamera::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 91 of file vpRobotSimulator.h.
Referenced by vpVirtualGrabber::acquire().
|
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, where is the linear translational velocity in m/s and is the rotational velocity in rad/s arround the vertical axis. |
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 113 of file vpSimulatorPioneer.cpp.
References vpRobot::ARTICULAR_FRAME, vpHomogeneousMatrix::buildFrom(), vpRobot::CAMERA_FRAME, vpUnicycle::cMe_, vpRobotSimulator::delta_t_, vpException::dimensionError, vpRobot::END_EFFECTOR_FRAME, vpRobot::getMaxRotationVelocity(), vpRobot::getMaxTranslationVelocity(), vpRobot::getRobotState(), vpHomogeneousMatrix::inverse(), vpRobot::MIXT_FRAME, vpRobot::REFERENCE_FRAME, vpRobot::saturateVelocities(), vpRobot::setRobotFrame(), vpRobot::setRobotState(), vpArray2D< Type >::size(), vpRobot::STATE_VELOCITY_CONTROL, theta_, vpERROR_TRACE, wMc_, wMe_, vpRobotException::wrongStateError, xm_, and ym_.
|
inlineinherited |
Definition at line 159 of file vpRobot.h.
Referenced by vpRobotAfma4::vpRobotAfma4(), vpRobotAfma6::vpRobotAfma6(), vpRobotViper650::vpRobotViper650(), and vpRobotViper850::vpRobotViper850().
|
protectedinherited |
Definition at line 112 of file vpRobot.h.
Referenced by vpRobot::operator=(), vpRobotCamera::vpRobotCamera(), vpSimulatorCamera::vpSimulatorCamera(), vpSimulatorPioneer(), and vpSimulatorPioneerPan::vpSimulatorPioneerPan().
|
protectedinherited |
Definition at line 127 of file vpUnicycle.h.
Referenced by setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpSimulatorPioneer(), and vpSimulatorPioneerPan::vpSimulatorPioneerPan().
|
protectedinherited |
Definition at line 65 of file vpRobotSimulator.h.
Referenced by vpSimulatorCamera::setVelocity(), vpRobotCamera::setVelocity(), setVelocity(), and vpSimulatorPioneerPan::setVelocity().
|
protectedinherited |
robot Jacobian expressed in the end-effector frame
Definition at line 104 of file vpRobot.h.
Referenced by vpRobotFlirPtu::get_eJe(), vpSimulatorCamera::get_eJe(), vpRobotCamera::get_eJe(), vpRobot::operator=(), vpRobotAfma4::setVelocity(), vpRobotCamera::vpRobotCamera(), and vpSimulatorCamera::vpSimulatorCamera().
|
protectedinherited |
Definition at line 128 of file vpUnicycle.h.
|
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::vpRobotCamera(), vpSimulatorCamera::vpSimulatorCamera(), vpSimulatorPioneer(), and vpSimulatorPioneerPan::vpSimulatorPioneerPan().
|
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=().
|
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::vpRobotCamera(), vpSimulatorCamera::vpSimulatorCamera(), vpSimulatorPioneer(), and vpSimulatorPioneerPan::vpSimulatorPioneerPan().
|
protectedinherited |
Definition at line 98 of file vpRobot.h.
Referenced by vpRobot::getMaxRotationVelocity(), vpRobotTemplate::init(), vpRobotFlirPtu::init(), vpRobot::operator=(), vpRobot::setMaxRotationVelocity(), vpRobotPtu46::setVelocity(), vpRobotViper650::vpRobotViper650(), and vpRobotViper850::vpRobotViper850().
|
staticprotectedinherited |
Definition at line 99 of file vpRobot.h.
Referenced by vpRobotTemplate::init(), and vpRobotFlirPtu::init().
|
protectedinherited |
Definition at line 96 of file vpRobot.h.
Referenced by vpRobot::getMaxTranslationVelocity(), vpRobotTemplate::init(), vpRobotFlirPtu::init(), vpRobot::operator=(), and vpRobot::setMaxTranslationVelocity().
|
staticprotectedinherited |
Definition at line 97 of file vpRobot.h.
Referenced by vpRobotTemplate::init(), and vpRobotFlirPtu::init().
|
protectedinherited |
number of degrees of freedom
Definition at line 102 of file vpRobot.h.
Referenced by vpRobotTemplate::init(), vpRobotFlirPtu::init(), vpRobot::operator=(), vpRobotTemplate::setVelocity(), vpRobotFlirPtu::setVelocity(), vpRobotCamera::vpRobotCamera(), vpRobotFranka::vpRobotFranka(), vpSimulatorCamera::vpSimulatorCamera(), vpSimulatorPioneer(), and vpSimulatorPioneerPan::vpSimulatorPioneerPan().
|
protectedinherited |
Definition at line 114 of file vpRobot.h.
Referenced by vpRobot::operator=(), vpRobotCamera::vpRobotCamera(), vpSimulatorCamera::vpSimulatorCamera(), vpSimulatorPioneer(), vpSimulatorPioneerPan::vpSimulatorPioneerPan(), and vpRobot::~vpRobot().
|
protectedinherited |
Definition at line 113 of file vpRobot.h.
Referenced by vpRobot::operator=(), vpRobotCamera::vpRobotCamera(), vpSimulatorCamera::vpSimulatorCamera(), vpSimulatorPioneer(), vpSimulatorPioneerPan::vpSimulatorPioneerPan(), and vpRobot::~vpRobot().
|
protected |
Definition at line 116 of file vpSimulatorPioneer.h.
Referenced by setVelocity(), and vpSimulatorPioneer().
|
protectedinherited |
Definition at line 116 of file vpRobot.h.
Referenced by vpRobotAfma4::init(), vpRobotAfma6::init(), vpRobotViper650::init(), vpRobotViper850::init(), vpRobot::operator=(), vpRobotAfma4::vpRobotAfma4(), vpRobotAfma6::vpRobotAfma6(), vpRobotViper650::vpRobotViper650(), and vpRobotViper850::vpRobotViper850().
|
protected |
Definition at line 108 of file vpSimulatorPioneer.h.
Referenced by getPosition(), setVelocity(), and vpSimulatorPioneer().
|
protected |
Definition at line 111 of file vpSimulatorPioneer.h.
Referenced by setVelocity(), and vpSimulatorPioneer().
|
protected |
Definition at line 114 of file vpSimulatorPioneer.h.
Referenced by setVelocity(), and vpSimulatorPioneer().
|
protected |
Definition at line 115 of file vpSimulatorPioneer.h.
Referenced by setVelocity(), and vpSimulatorPioneer().