![]() |
ViSP
2.6.2
|
#include <vpRobotPtu46.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) |
Static Public Attributes | |
static const double | defaultPositioningVelocity = 10.0 |
static const unsigned int | ndof = 2 |
static const float | L = 0.0765f |
static const float | h = 0.068f |
static const vpRobot::vpRobotStateType | defaultEtatRobot = vpRobot::STATE_STOP |
static const vpRobot::vpControlFrameType | defaultFrameRobot = vpRobot::CAMERA_FRAME |
Protected Attributes | |
double | maxTranslationVelocity |
double | maxRotationVelocity |
int | nDof |
vpMatrix | eJe |
int | eJeAvailable |
vpMatrix | fJe |
int | fJeAvailable |
Static Protected Attributes | |
static const double | maxTranslationVelocityDefault = 0.2 |
static const double | maxRotationVelocityDefault = 0.7 |
Interface for the Directed Perception ptu-46 pan, tilt head .
See http://www.DPerception.com for more details.
This class provide a position and a speed control interface for the ptu-46 head.
Definition at line 88 of file vpRobotPtu46.h.
|
inherited |
Robot control frames.
|
inherited |
vpRobotPtu46::vpRobotPtu46 | ( | const char * | device = "/dev/ttyS0" | ) |
Default constructor.
Initialize the ptu-46 pan, tilt head by opening the serial port.
Definition at line 75 of file vpRobotPtu46.cpp.
References defaultPositioningVelocity, init(), setRobotState(), vpRobot::STATE_STOP, vpDEBUG_TRACE, and vpERROR_TRACE.
vpRobotPtu46::vpRobotPtu46 | ( | vpRobotPtu46 * | pub | ) |
|
virtual |
Destructor. Close the serial connection with the head.
Definition at line 119 of file vpRobotPtu46.cpp.
References setRobotState(), vpRobot::STATE_STOP, and vpERROR_TRACE.
|
inherited |
Compute the direct geometric model of the camera: fMc
q | : Articular position for pan and tilt axis. |
fMc | : Homogeneous matrix corresponding to the direct geometric model of the camera. Describes the transformation between the robot reference frame (called fixed) and the camera frame. |
Definition at line 83 of file vpPtu46.cpp.
References vpException::dimensionError, vpMatrix::getRows(), vpPtu46::h, vpPtu46::L, vpCDEBUG, and vpERROR_TRACE.
Referenced by vpPtu46::computeMGD().
|
inherited |
Return the direct geometric model of the camera: fMc
q | : Articular position for pan and tilt axis. |
Definition at line 134 of file vpPtu46.cpp.
References vpPtu46::computeMGD().
|
inherited |
Compute the direct geometric model of the camera in terms of pose vector.
q | : Articular position for pan and tilt axis. |
r | : Pose vector corresponding to the transformation between the robot reference frame (called fixed) and the camera frame. |
Definition at line 153 of file vpPtu46.cpp.
References vpPoseVector::buildFrom(), vpPtu46::computeMGD(), and vpHomogeneousMatrix::inverse().
void vpRobotPtu46::get_cMe | ( | vpHomogeneousMatrix & | cMe | ) |
Get the homogeneous matrix corresponding to the transformation between the camera frame and the end effector frame. The end effector frame is located on the tilt axis.
cMe | : Homogeneous matrix between camera and end effector frame. |
Definition at line 256 of file vpRobotPtu46.cpp.
References vpPtu46::get_cMe().
void vpRobotPtu46::get_cVe | ( | vpVelocityTwistMatrix & | cVe | ) |
Get the twist matrix corresponding to the transformation between the camera frame and the end effector frame. The end effector frame is located on the tilt axis.
cVe | : Twist transformation between camera and end effector frame to expess a velocity skew from end effector frame in camera frame. |
Definition at line 238 of file vpRobotPtu46.cpp.
References vpVelocityTwistMatrix::buildFrom(), and vpPtu46::get_cMe().
|
inherited |
Get the robot jacobian expressed in the end-effector frame.
q | : Articular position for pan and tilt axis. |
eJe | : Jacobian between end effector frame and end effector frame (on tilt axis). |
Definition at line 282 of file vpPtu46.cpp.
References vpException::dimensionError, vpMatrix::getRows(), vpMatrix::resize(), and vpERROR_TRACE.
Referenced by get_eJe().
|
virtual |
Get the robot jacobian expressed in the end-effector frame.
eJe | : Jacobian between end effector frame and end effector frame (on tilt axis). |
Implements vpRobot.
Definition at line 272 of file vpRobotPtu46.cpp.
References vpRobot::ARTICULAR_FRAME, vpPtu46::get_eJe(), getPosition(), and vpERROR_TRACE.
|
inherited |
Get the robot jacobian expressed in the robot reference frame
q | : Articular position for pan and tilt axis. |
fJe | : Jacobian between reference frame (or fix frame) and end effector frame (on tilt axis). |
Definition at line 314 of file vpPtu46.cpp.
References vpException::dimensionError, vpMatrix::getRows(), vpMatrix::resize(), and vpERROR_TRACE.
Referenced by get_fJe().
|
virtual |
Get the robot jacobian expressed in the robot reference frame
fJe | : Jacobian between reference frame (or fix frame) and end effector frame (on tilt axis). |
Implements vpRobot.
Definition at line 296 of file vpRobotPtu46.cpp.
References vpRobot::ARTICULAR_FRAME, vpPtu46::get_fJe(), getPosition(), and vpERROR_TRACE.
|
virtual |
Get the robot articular displacement since the last call of this method.
d | The measured articular displacement. The dimension of d is 2 (the number of axis of the robot) with respectively d[0] (pan displacement), d[1] (tilt displacement) |
Implements vpRobot.
Definition at line 854 of file vpRobotPtu46.cpp.
References vpRobot::ARTICULAR_FRAME, and getDisplacement().
|
virtual |
Get the robot displacement expressed in the camera frame since the last call of this method.
v | The measured displacement in camera frame. The dimension of v is 6 (tx, ty, ty, rx, ry, rz). Translations are expressed in meters, rotations in radians. |
Implements vpRobot.
Definition at line 838 of file vpRobotPtu46.cpp.
References vpRobot::CAMERA_FRAME, and getDisplacement().
|
virtual |
Get the robot displacement since the last call of this method.
frame | The frame in which the measured displacement is expressed. |
d | The displacement:
|
vpRobotException::wrongStateError | If a not supported frame type is given. |
Implements vpRobot.
Definition at line 881 of file vpRobotPtu46.cpp.
References vpRobot::ARTICULAR_FRAME, vpRobot::CAMERA_FRAME, vpRobot::MIXT_FRAME, vpPtu46::ndof, vpRobot::REFERENCE_FRAME, vpColVector::resize(), vpERROR_TRACE, and vpRobotException::wrongStateError.
Referenced by getArticularDisplacement(), and getCameraDisplacement().
|
inherited |
Get the maximal rotation velocity that can be sent to the robot during a velocity control.
Definition at line 233 of file vpRobot.cpp.
Referenced by vpSimulatorAfma6::computeArticularVelocity(), vpSimulatorViper850::computeArticularVelocity(), vpSimulatorAfma6::findHighestPositioningSpeed(), vpSimulatorViper850::findHighestPositioningSpeed(), vpSimulatorAfma6::setPosition(), vpRobotPioneer::setVelocity(), vpSimulatorAfma6::setVelocity(), vpSimulatorViper850::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), and vpRobotViper850::setVelocity().
|
inherited |
Get the maximal translation velocity that can be sent to the robot during a velocity control.
Definition at line 208 of file vpRobot.cpp.
Referenced by vpSimulatorAfma6::setPosition(), vpRobotPioneer::setVelocity(), vpSimulatorAfma6::setVelocity(), vpSimulatorViper850::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), and vpRobotViper850::setVelocity().
|
virtual |
Return the position of each axis.
frame | : Control frame. This head can only be controlled in articular. |
q | : The position of the axis. |
vpRobotException::wrongStateError | : If a not supported frame type is given. |
Implements vpRobot.
Definition at line 483 of file vpRobotPtu46.cpp.
References vpRobot::ARTICULAR_FRAME, vpRobot::CAMERA_FRAME, vpRobotException::lowLevelError, vpRobot::MIXT_FRAME, vpPtu46::ndof, vpRobot::REFERENCE_FRAME, vpColVector::resize(), vpDEBUG_TRACE, and vpERROR_TRACE.
|
inherited |
Return the robot position (frame has to be specified).
Recupere la position actuelle du robot. Recupere la position actuelle du robot et renvoie le resultat Le repere de travail dans lequel est exprime le resultat est celui donne par la variable repere. INPUT:
Definition at line 176 of file vpRobot.cpp.
double vpRobotPtu46::getPositioningVelocity | ( | void | ) |
Get the velocity in % used for a position control.
Definition at line 332 of file vpRobotPtu46.cpp.
|
inlineinherited |
Definition at line 147 of file vpRobot.h.
Referenced by vpSimulatorAfma6::computeArticularVelocity(), and vpSimulatorViper850::computeArticularVelocity().
|
inlinevirtualinherited |
Definition at line 148 of file vpRobot.h.
Referenced by vpRobotBiclops::getPosition(), vpRobotBiclops::getVelocity(), setPosition(), vpRobotBiclops::setPosition(), vpSimulatorAfma6::setPosition(), vpRobotAfma4::setPosition(), vpSimulatorViper850::setPosition(), vpRobotAfma6::setPosition(), vpRobotViper850::setPosition(), setRobotState(), vpRobotBiclops::setRobotState(), vpSimulatorAfma6::setRobotState(), vpSimulatorViper850::setRobotState(), vpRobotAfma4::setRobotState(), vpRobotAfma6::setRobotState(), vpRobotViper850::setRobotState(), setVelocity(), vpRobotBiclops::setVelocity(), vpSimulatorAfma6::setVelocity(), vpSimulatorViper850::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotViper850::setVelocity(), vpSimulatorAfma6::stopMotion(), vpSimulatorViper850::stopMotion(), and vpRobotViper850::stopMotion().
void vpRobotPtu46::getVelocity | ( | const vpRobot::vpControlFrameType | frame, |
vpColVector & | q_dot | ||
) |
Get the articular velocity.
frame | : Control frame. This head can only be controlled in articular. |
q_dot | : The measured articular velocity in rad/s. |
vpRobotException::wrongStateError | : If a not supported frame type is given. |
Definition at line 685 of file vpRobotPtu46.cpp.
References vpRobot::ARTICULAR_FRAME, vpRobot::CAMERA_FRAME, vpRobot::MIXT_FRAME, vpPtu46::ndof, vpRobot::REFERENCE_FRAME, vpColVector::resize(), vpERROR_TRACE, and vpRobotException::wrongStateError.
Referenced by getVelocity().
vpColVector vpRobotPtu46::getVelocity | ( | const vpRobot::vpControlFrameType | frame | ) |
Return the articular velocity.
frame | : Control frame. This head can only be controlled in articular. |
vpRobotException::wrongStateError | : If a not supported frame type is given. |
Definition at line 751 of file vpRobotPtu46.cpp.
References getVelocity().
|
virtual |
Open the serial port.
vpRobotException::constructionError | : If the device cannot be oppened. |
Implements vpRobot.
Definition at line 151 of file vpRobotPtu46.cpp.
References vpRobotException::constructionError, vpDEBUG_TRACE, and vpERROR_TRACE.
Referenced by vpRobotPtu46().
bool vpRobotPtu46::readPositionFile | ( | const char * | filename, |
vpColVector & | q | ||
) |
Get an articular position from the position file.
filename | : Position file. |
q | : The articular position read in the file. |
Definition at line 779 of file vpRobotPtu46.cpp.
References vpPtu46::ndof, vpMath::rad(), vpColVector::resize(), and vpERROR_TRACE.
Referenced by setPosition().
|
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 114 of file vpRobot.cpp.
References vpException::dimensionError, and vpColVector::size().
Referenced by vpRobotPioneer::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), and vpRobotViper850::setVelocity().
|
inherited |
Set the maximal rotation velocity that can be sent to the robot during a velocity control.
maxVr | : Maximum rotation velocity expressed in rad/s. |
Definition at line 220 of file vpRobot.cpp.
Referenced by vpSimulatorAfma6::setPosition().
|
inherited |
Set the maximal translation velocity that can be sent to the robot during a velocity control.
maxVt | : Maximum translation velocity expressed in m/s. |
Definition at line 196 of file vpRobot.cpp.
Referenced by vpSimulatorAfma6::setPosition().
|
virtual |
Move the robot in position control.
frame | : Control frame. This head can only be controlled in articular. |
q | : The position to set for each axis. |
vpRobotException::wrongStateError | : If a not supported frame type is given. |
Implements vpRobot.
Definition at line 355 of file vpRobotPtu46.cpp.
References vpRobot::ARTICULAR_FRAME, vpRobot::CAMERA_FRAME, vpRobot::getRobotState(), vpRobotException::lowLevelError, vpRobot::MIXT_FRAME, vpRobot::REFERENCE_FRAME, setRobotState(), vpRobot::STATE_POSITION_CONTROL, vpERROR_TRACE, and vpRobotException::wrongStateError.
Referenced by setPosition().
void vpRobotPtu46::setPosition | ( | const vpRobot::vpControlFrameType | frame, |
const double & | q1, | ||
const double & | q2 | ||
) |
Move the robot in position control.
frame | : Control frame. This head can only be controlled in articular. |
q1 | : The pan position to set. |
q2 | : The tilt position to set. |
vpRobotException::wrongStateError | : If a not supported frame type is given. |
Definition at line 427 of file vpRobotPtu46.cpp.
References setPosition(), and vpERROR_TRACE.
void vpRobotPtu46::setPosition | ( | const char * | filename | ) |
Read the content of the position file and moves to head to articular position.
filename | : Position filename |
vpRobotException::readingParametersError | : If the articular position cannot be read from file. |
Definition at line 458 of file vpRobotPtu46.cpp.
References vpRobot::ARTICULAR_FRAME, vpRobotException::readingParametersError, readPositionFile(), setPosition(), and vpERROR_TRACE.
void vpRobotPtu46::setPositioningVelocity | ( | const double | velocity | ) |
Set the velocity used for a position control.
velocity | : Velocity in % of the maximum velocity between [0,100]. |
Definition at line 321 of file vpRobotPtu46.cpp.
|
inherited |
Definition at line 159 of file vpRobot.cpp.
Referenced by vpSimulatorAfma6::init(), vpSimulatorViper850::init(), vpSimulatorAfma6::setVelocity(), and vpSimulatorViper850::setVelocity().
|
virtual |
Change the state of the robot either to stop them, or to set position or speed control.
Reimplemented from vpRobot.
Definition at line 173 of file vpRobotPtu46.cpp.
References vpRobot::getRobotState(), vpRobot::setRobotState(), vpRobot::STATE_POSITION_CONTROL, vpRobot::STATE_STOP, vpRobot::STATE_VELOCITY_CONTROL, and vpDEBUG_TRACE.
Referenced by setPosition(), stopMotion(), vpRobotPtu46(), and ~vpRobotPtu46().
|
virtual |
Send a velocity on each axis.
frame | : Control frame. This head can only be controlled in articular and camera frame. Be aware, the reference frame (vpRobot::REFERENCE_FRAME) and the mixt frame (vpRobot::MIXT_FRAME) are not implemented. |
v | : The desired velocity of the axis. The size of this vector is always 2. Velocitoes are expressed in rad/s. |
vpRobotException::wrongStateError | : If a the robot is not configured to handle a velocity. The robot can handle a velocity only if the velocity control mode is set. For that, call setRobotState( vpRobot::STATE_VELOCITY_CONTROL) before setVelocity(). |
vpRobotException::wrongStateError | : If a not supported frame type (vpRobot::REFERENCE_FRAME, vpRobot::MIXT_FRAME) is given. |
Implements vpRobot.
Definition at line 560 of file vpRobotPtu46.cpp.
References vpRobot::ARTICULAR_FRAME, vpRobot::CAMERA_FRAME, vpRobot::getRobotState(), vpMatrix::getRows(), vpRobot::MIXT_FRAME, vpRobot::REFERENCE_FRAME, vpRobot::STATE_VELOCITY_CONTROL, vpCDEBUG, vpDEBUG_TRACE, vpERROR_TRACE, and vpRobotException::wrongStateError.
void vpRobotPtu46::stopMotion | ( | void | ) |
Halt all the axis.
Definition at line 220 of file vpRobotPtu46.cpp.
References setRobotState(), and vpRobot::STATE_STOP.
|
staticinherited |
|
staticinherited |
|
static |
Definition at line 110 of file vpRobotPtu46.h.
Referenced by vpRobotPtu46().
|
protectedinherited |
robot Jacobian expressed in the end-effector frame
Definition at line 113 of file vpRobot.h.
Referenced by vpSimulatorAfma6::computeArticularVelocity(), vpSimulatorViper850::computeArticularVelocity(), vpRobotCamera::get_eJe(), vpSimulatorAfma6::getVelocity(), vpSimulatorViper850::getVelocity(), vpRobotCamera::init(), vpSimulatorAfma6::setPosition(), and vpRobotAfma4::setVelocity().
|
protectedinherited |
|
protectedinherited |
robot Jacobian expressed in the robot reference frame available
Definition at line 117 of file vpRobot.h.
Referenced by vpSimulatorAfma6::computeArticularVelocity(), vpSimulatorViper850::computeArticularVelocity(), vpSimulatorAfma6::getVelocity(), and vpSimulatorViper850::getVelocity().
|
protectedinherited |
|
staticinherited |
Horizontal offset along the last joint, from last joint to camera frame.
Definition at line 90 of file vpPtu46.h.
Referenced by vpPtu46::computeMGD(), and vpPtu46::get_cMe().
|
staticinherited |
Geometric model
Definition at line 89 of file vpPtu46.h.
Referenced by vpPtu46::computeMGD(), and vpPtu46::get_cMe().
|
staticprotectedinherited |
|
staticprotectedinherited |
|
staticinherited |
Nombre d'articulations du robot. Number of dof
Definition at line 86 of file vpPtu46.h.
Referenced by getDisplacement(), getPosition(), getVelocity(), and readPositionFile().