Visual Servoing Platform
version 3.6.1 under development (2024-10-13)
|
#include <visp3/robot/vpRobotPioneer.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 | |
vpRobotPioneer () | |
virtual | ~vpRobotPioneer () VP_OVERRIDE |
void | get_eJe (vpMatrix &eJe) VP_OVERRIDE |
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) VP_OVERRIDE |
void | useSonar (bool usage) |
Inherited functionalities from vpRobot | |
double | getMaxTranslationVelocity (void) const |
double | getMaxRotationVelocity (void) const |
int | getNDof () 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 | |
bool | isInitialized |
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 |
Inherited functionalities from vpUnicycle | |
vpHomogeneousMatrix | cMe_ |
vpMatrix | eJe_ |
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 |
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.
Definition at line 63 of file vpRobotPioneer.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.
BEGIN_VISP_NAMESPACE vpRobotPioneer::vpRobotPioneer | ( | ) |
Default constructor that initializes Aria.
Definition at line 53 of file vpRobotPioneer.cpp.
References isInitialized.
|
virtual |
Destructor.
Definition at line 63 of file vpRobotPioneer.cpp.
|
inlineinherited |
Return the transformation between the camera frame and the mobile robot end effector frame.
Definition at line 65 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 72 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 86 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 96 of file vpUnicycle.h.
Referenced by get_eJe(), vpSimulatorPioneer::get_eJe(), and vpSimulatorPioneerPan::get_eJe().
|
inlinevirtual |
Get the robot Jacobian expressed at point E, the point located at the middle between the two wheels.
eJe | : Robot jacobian such as with respectively the translational and rotational control velocities of the mobile robot, the six dimension velocity skew, and where |
Implements vpRobot.
Definition at line 86 of file vpRobotPioneer.h.
References vpUnicycle::get_eJe().
|
inherited |
Get the maximal rotation velocity that can be sent to the robot during a velocity control.
Definition at line 274 of file vpRobot.cpp.
References vpRobot::maxRotationVelocity.
Referenced by vpRobotPololuPtu::setPosition(), vpRobotPololuPtu::setVelocity(), vpRobotFlirPtu::setVelocity(), vpRobotFranka::setVelocity(), vpRobotKinova::setVelocity(), setVelocity(), vpRobotTemplate::setVelocity(), vpRobotUniversalRobots::setVelocity(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::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 252 of file vpRobot.cpp.
References vpRobot::maxTranslationVelocity.
Referenced by vpRobotFlirPtu::setVelocity(), vpRobotFranka::setVelocity(), vpRobotKinova::setVelocity(), setVelocity(), vpRobotTemplate::setVelocity(), vpRobotUniversalRobots::setVelocity(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotViper650::setVelocity(), and vpRobotViper850::setVelocity().
|
inlineinherited |
Return robot degrees of freedom number.
|
inherited |
Return the current robot position in the specified frame.
Definition at line 217 of file vpRobot.cpp.
References vpRobot::getPosition().
|
inlineprotectedinherited |
|
inlinevirtualinherited |
Definition at line 155 of file vpRobot.h.
Referenced by vpRobotBiclops::getPosition(), vpRobotBiclops::getVelocity(), vpSimulatorCamera::setPosition(), vpRobotAfma4::setPosition(), vpRobotAfma6::setPosition(), vpRobotFranka::setPosition(), vpRobotUniversalRobots::setPosition(), vpRobotViper650::setPosition(), vpRobotViper850::setPosition(), vpRobotBiclops::setPosition(), vpRobotPololuPtu::setPosition(), vpRobotPtu46::setPosition(), vpRobotBiclops::setRobotState(), vpRobotPololuPtu::setRobotState(), vpRobotAfma4::setRobotState(), vpRobotAfma6::setRobotState(), vpRobotFlirPtu::setRobotState(), vpRobotFranka::setRobotState(), vpRobotPtu46::setRobotState(), vpRobotUniversalRobots::setRobotState(), vpRobotViper650::setRobotState(), vpRobotViper850::setRobotState(), vpRobotBiclops::setVelocity(), vpRobotPololuPtu::setVelocity(), vpRobotPtu46::setVelocity(), vpRobotFlirPtu::setVelocity(), vpRobotFranka::setVelocity(), vpRobotKinova::setVelocity(), vpRobotTemplate::setVelocity(), vpRobotUniversalRobots::setVelocity(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotViper650::setVelocity(), vpRobotViper850::setVelocity(), vpRobotFlirPtu::stopMotion(), vpRobotFranka::stopMotion(), vpRobotViper650::stopMotion(), and vpRobotViper850::stopMotion().
vpColVector vpRobotPioneer::getVelocity | ( | const vpRobot::vpControlFrameType | frame | ) |
Gets the current translational velocity of the robot.
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. |
vpRobotException::dimensionError | : Velocity vector is not a 2 dimension vector. |
vpRobotException::wrongStateError | : If the specified control frame is not supported. |
Definition at line 233 of file vpRobotPioneer.cpp.
References getVelocity().
void vpRobotPioneer::getVelocity | ( | const vpRobot::vpControlFrameType | frame, |
vpColVector & | velocity | ||
) |
Gets the current translational velocity of the robot.
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.
|
vpRobotException::dimensionError | : Velocity vector is not a 2 dimension vector. |
vpRobotException::wrongStateError | : If the specified control frame is not supported. |
Definition at line 190 of file vpRobotPioneer.cpp.
References vpRobot::ARTICULAR_FRAME, init(), vpMath::rad(), vpRobot::REFERENCE_FRAME, vpColVector::resize(), and vpRobotException::wrongStateError.
Referenced by getVelocity().
|
virtual |
Initialize the robot.
Implements vpRobot.
Definition at line 155 of file vpRobotPioneer.cpp.
References isInitialized.
Referenced by getVelocity(), and setVelocity().
|
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 164 of file vpRobot.cpp.
References vpException::dimensionError, and vpArray2D< Type >::size().
Referenced by vpRobotFlirPtu::setVelocity(), vpRobotFranka::setVelocity(), vpRobotKinova::setVelocity(), setVelocity(), vpRobotTemplate::setVelocity(), vpRobotUniversalRobots::setVelocity(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::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 102 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 dimension velocity skew. |
Definition at line 112 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 rotational velocity expressed in rad/s. |
Definition at line 261 of file vpRobot.cpp.
References vpRobot::maxRotationVelocity.
Referenced by vpRobotViper650::setMaxRotationVelocity(), and vpRobotViper850::setMaxRotationVelocity().
|
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 240 of file vpRobot.cpp.
References vpRobot::maxTranslationVelocity.
|
protectedinherited |
Definition at line 208 of file vpRobot.cpp.
Referenced by vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), and vpSimulatorPioneerPan::setVelocity().
|
virtualinherited |
Reimplemented in vpRobotViper850, vpRobotViper650, vpRobotUniversalRobots, vpRobotPtu46, vpRobotFranka, vpRobotFlirPtu, vpRobotAfma6, vpRobotAfma4, vpRobotPololuPtu, and vpRobotBiclops.
Definition at line 202 of file vpRobot.cpp.
Referenced by vpSimulatorCamera::setPosition(), vpRobotBiclops::setRobotState(), vpRobotPololuPtu::setRobotState(), vpRobotAfma4::setRobotState(), vpRobotAfma6::setRobotState(), vpRobotFlirPtu::setRobotState(), vpRobotFranka::setRobotState(), vpRobotPtu46::setRobotState(), vpRobotUniversalRobots::setRobotState(), vpRobotViper650::setRobotState(), vpRobotViper850::setRobotState(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), and vpSimulatorPioneerPan::setVelocity().
|
virtual |
Set the velocity (frame has to be specified) that will be applied to the robot.
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.
|
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().
vpRobotException::dimensionError | : Velocity vector is not a 2 dimension vector. |
vpRobotException::wrongStateError | : If the specified control frame is not supported. |
Implements vpRobot.
Definition at line 100 of file vpRobotPioneer.cpp.
References vpRobot::ARTICULAR_FRAME, vpMath::deg(), vpException::dimensionError, vpRobot::getMaxRotationVelocity(), vpRobot::getMaxTranslationVelocity(), init(), vpRobot::REFERENCE_FRAME, vpRobot::saturateVelocities(), vpArray2D< Type >::size(), and vpRobotException::wrongStateError.
|
inlineinherited |
Definition at line 170 of file vpRobot.h.
Referenced by vpRobotAfma4::vpRobotAfma4(), vpRobotAfma6::vpRobotAfma6(), vpRobotViper650::vpRobotViper650(), and vpRobotViper850::vpRobotViper850().
|
inline |
Enable or disable sonar device usage.
Definition at line 129 of file vpRobotPioneer.h.
|
protectedinherited |
Definition at line 114 of file vpRobot.h.
Referenced by vpRobot::operator=().
|
protectedinherited |
Definition at line 116 of file vpUnicycle.h.
Referenced by vpSimulatorPioneer::setVelocity(), and vpSimulatorPioneerPan::setVelocity().
|
protectedinherited |
robot Jacobian expressed in the end-effector frame
Definition at line 106 of file vpRobot.h.
Referenced by vpRobotFlirPtu::get_eJe(), vpRobotAfma6::get_eJe(), vpRobotPtu46::get_eJe(), vpRobotAfma4::get_eJe(), vpRobotBiclops::get_eJe(), vpRobotKinova::get_eJe(), vpRobotPololuPtu::get_eJe(), vpRobotViper650::get_eJe(), vpRobotViper850::get_eJe(), vpSimulatorCamera::get_eJe(), vpRobot::operator=(), and vpRobotAfma4::setVelocity().
|
protectedinherited |
Definition at line 117 of file vpUnicycle.h.
|
protectedinherited |
is the robot Jacobian expressed in the end-effector frame available
Definition at line 108 of file vpRobot.h.
Referenced by vpRobot::operator=().
|
protectedinherited |
robot Jacobian expressed in the robot reference frame available
Definition at line 110 of file vpRobot.h.
Referenced by vpRobotFlirPtu::get_fJe(), vpRobotAfma6::get_fJe(), vpRobotPtu46::get_fJe(), vpRobotAfma4::get_fJe(), vpRobotBiclops::get_fJe(), vpRobotKinova::get_fJe(), vpRobotPololuPtu::get_fJe(), vpRobotViper650::get_fJe(), vpRobotViper850::get_fJe(), and vpRobot::operator=().
|
protectedinherited |
is the robot Jacobian expressed in the robot reference frame available
Definition at line 112 of file vpRobot.h.
Referenced by vpRobot::operator=().
|
protected |
Definition at line 132 of file vpRobotPioneer.h.
Referenced by init(), and vpRobotPioneer().
|
protectedinherited |
Definition at line 100 of file vpRobot.h.
Referenced by vpRobot::getMaxRotationVelocity(), vpRobotFlirPtu::init(), vpRobotKinova::init(), vpRobotTemplate::init(), vpRobot::operator=(), vpRobot::setMaxRotationVelocity(), vpRobotPtu46::setVelocity(), vpRobotViper650::vpRobotViper650(), and vpRobotViper850::vpRobotViper850().
|
staticprotectedinherited |
Definition at line 101 of file vpRobot.h.
Referenced by vpRobotFlirPtu::init(), vpRobotKinova::init(), and vpRobotTemplate::init().
|
protectedinherited |
Definition at line 98 of file vpRobot.h.
Referenced by vpRobot::getMaxTranslationVelocity(), vpRobotFlirPtu::init(), vpRobotKinova::init(), vpRobotTemplate::init(), vpRobot::operator=(), and vpRobot::setMaxTranslationVelocity().
|
staticprotectedinherited |
Definition at line 99 of file vpRobot.h.
Referenced by vpRobotFlirPtu::init(), vpRobotKinova::init(), and vpRobotTemplate::init().
|
protectedinherited |
number of degrees of freedom
Definition at line 104 of file vpRobot.h.
Referenced by vpRobotPololuPtu::get_eJe(), vpRobotPololuPtu::get_fJe(), vpRobotKinova::getJointPosition(), vpRobotPololuPtu::getPosition(), vpRobotFlirPtu::init(), vpRobotKinova::init(), vpRobotUniversalRobots::init(), vpRobotTemplate::init(), vpRobot::operator=(), vpRobotUniversalRobots::readPosFile(), vpRobotKinova::setDoF(), vpRobotKinova::setJointVelocity(), vpRobotKinova::setPosition(), vpRobotPololuPtu::setPosition(), vpRobotPololuPtu::setVelocity(), vpRobotFlirPtu::setVelocity(), vpRobotKinova::setVelocity(), vpRobotTemplate::setVelocity(), and vpRobotPololuPtu::vpRobotPololuPtu().
|
protectedinherited |
Definition at line 116 of file vpRobot.h.
Referenced by vpRobot::operator=(), and vpRobot::~vpRobot().
|
protectedinherited |
Definition at line 115 of file vpRobot.h.
Referenced by vpRobot::operator=(), and vpRobot::~vpRobot().
|
protectedinherited |
Definition at line 118 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().