ViSP
2.10.0
|
#include <vpRobotPioneer.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 | |
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 |
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 65 of file vpRobotPioneer.h.
|
inherited |
Robot control frames.
|
inherited |
vpRobotPioneer::vpRobotPioneer | ( | ) |
Default constructor that initializes Aria.
Definition at line 52 of file vpRobotPioneer.cpp.
References isInitialized.
|
virtual |
Destructor.
Definition at line 62 of file vpRobotPioneer.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().
|
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 dimention velocity skew, and where |
Implements vpRobot.
Definition at line 89 of file vpRobotPioneer.h.
References vpUnicycle::get_eJe().
|
inlineinherited |
Return the robot jacobian expressed in the end effector frame.
Definition at line 115 of file vpUnicycle.h.
Referenced by get_eJe(), vpSimulatorPioneer::get_eJe(), and vpSimulatorPioneerPan::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(), vpSimulatorPioneer::setVelocity(), 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(), vpSimulatorPioneer::setVelocity(), setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpSimulatorAfma6::setVelocity(), vpSimulatorViper850::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotViper650::setVelocity(), and vpRobotViper850::setVelocity().
|
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(), vpSimulatorCamera::setPosition(), vpRobotCamera::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(), vpSimulatorPioneer::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().
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 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.
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 228 of file vpRobotPioneer.cpp.
References getVelocity().
|
virtual |
Initialize the robot.
Implements vpRobot.
Definition at line 151 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 167 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().
|
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(), vpSimulatorPioneer::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(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpSimulatorAfma6::stopMotion(), and vpSimulatorViper850::stopMotion().
|
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 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.
|
inlineinherited |
Definition at line 158 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 134 of file vpRobotPioneer.h.
|
protectedinherited |
Definition at line 111 of file vpRobot.h.
Referenced by vpRobot::operator=().
|
protectedinherited |
Definition at line 140 of file vpUnicycle.h.
Referenced by vpSimulatorPioneer::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=().
|
protected |
Definition at line 140 of file vpRobotPioneer.h.
Referenced by init(), and vpRobotPioneer().
|
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().
|
protectedinherited |
Definition at line 115 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().