Visual Servoing Platform
version 3.5.0 under development (2022-02-15)
|
#include <visp3/robot/vpRobotAfma4.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 } |
Static Public Member Functions | |
static bool | readPosFile (const std::string &filename, vpColVector &q) |
static bool | savePosFile (const std::string &filename, const vpColVector &q) |
Static Public Member Functions inherited from vpRobot | |
static vpColVector | saturateVelocities (const vpColVector &v_in, const vpColVector &v_max, bool verbose=false) |
Static Public Attributes | |
static const double | defaultPositioningVelocity = 15.0 |
static const unsigned int | njoint = 4 |
Protected Member Functions | |
Protected Member Functions Inherited from vpRobot | |
vpControlFrameType | setRobotFrame (vpRobot::vpControlFrameType newFrame) |
vpControlFrameType | getRobotFrame (void) const |
Protected Attributes | |
double | _a1 |
double | _d3 |
double | _d4 |
double | _joint_max [4] |
double | _joint_min [4] |
vpTranslationVector | _etc |
vpRxyzVector | _erc |
vpHomogeneousMatrix | _eMc |
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 |
Control of Irisa's cylindrical robot named Afma4.
Implementation of the vpRobot class in order to control Irisa's Afma4 robot. This robot is a cylindrical robot with five degrees of freedom but only four are actuated (see vpAfma4 documentation). It was manufactured in 1995 by the french Afma-Robots company. In 2008, the low level controller change for a more recent Adept technology based on the MotionBlox controller. A firewire camera is mounted on the end-effector to allow eye-in-hand visual servoing. The control of this camera is achieved by the vp1394TwoGrabber class. A Servolens lens is attached to the camera. It allows to control the focal lens, the iris and the focus throw a serial link. The control of the lens is possible using the vpServolens class.
This class allows to control the Afma4 cylindrical robot in position and velocity:
Mixed frame (vpRobot::MIXT_FRAME) where translations are expressed in the reference frame and rotations in the camera frame is not implemented. End-effector frame (vpRobot::END_EFFECTOR_FRAME) is also not implemented.
All the translations are expressed in meters for positions and m/s for the velocities. Rotations are expressed in radians for the positions, and rad/s for the rotation velocities.
The Denavit-Hartenberg representation as well as the direct and inverse kinematics models are given and implemented in the vpAfma4 class.
To communicate with the robot, you may first create an instance of this class by calling the default constructor:
This initialize the robot kinematics with the eMc extrinsic camera parameters.
To control the robot in position, you may set the controller to position control and than send the position to reach in a specific frame like here in the joint space:
The robot moves to the specified position with the default positioning velocity vpRobotAfma4::defaultPositioningVelocity. The setPositioningVelocity() method allows to change the maximal velocity used to reach the desired position.
To control the robot in velocity, you may set the controller to velocity control and than send the velocities. To end the velocity control and stop the robot you have to set the controller to the stop state. Here is an example of a velocity control in the joint space:
There is also possible to measure the robot current position with getPosition() method and the robot current velocities with the getVelocity() method.
For convenience, there is also the ability to read/write joint positions from a position file with readPosFile() and writePosFile() methods.
Definition at line 178 of file vpRobotAfma4.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.
|
explicit |
The only available constructor.
This contructor calls init() to initialise the connection with the MotionBox or low level controller, power on the robot and wait 1 sec before returning to be sure the initialisation is done.
It also set the robot state to vpRobot::STATE_STOP.
Definition at line 133 of file vpRobotAfma4.cpp.
References defaultPositioningVelocity, init(), setRobotState(), vpRobot::setVerbose(), vpRobot::STATE_STOP, and vpRobot::verbose_.
|
virtual |
Destructor.
Free allocated resources.
Definition at line 291 of file vpRobotAfma4.cpp.
References setRobotState(), and vpRobot::STATE_STOP.
void vpRobotAfma4::get_cMe | ( | vpHomogeneousMatrix & | cMe | ) | const |
Get the geometric transformation between the camera frame and the end-effector frame. This transformation is constant and correspond to the extrinsic camera parameters estimated by calibration.
cMe | : Transformation between the camera frame and the end-effector frame. |
Definition at line 574 of file vpRobotAfma4.cpp.
References vpAfma4::get_cMe().
void vpRobotAfma4::get_cVe | ( | vpVelocityTwistMatrix & | cVe | ) | const |
Get the twist transformation from camera frame to end-effector frame. This transformation allows to compute a velocity expressed in the end-effector frame into the camera frame.
cVe | : Twist transformation. |
Definition at line 526 of file vpRobotAfma4.cpp.
References vpVelocityTwistMatrix::buildFrom(), and vpAfma4::get_cMe().
|
inherited |
Get the twist transformation from camera frame to the reference frame. This transformation allows to compute a velocity expressed in the reference frame into the camera frame.
q | : Articular position of the four joints: q[0] corresponds to the first rotation (joint 1 with value ) of the turret around the vertical axis, while q[1] corresponds to the vertical translation (joint 2 with value ), while q[2] and q[3] correspond to the pan and tilt of the camera (respectively joint 4 and 5 with values and ). Rotations q[0], q[2] and q[3] are expressed in radians. The translation q[1] is expressed in meters. |
cVf | : Twist transformation. |
Definition at line 348 of file vpAfma4.cpp.
References vpVelocityTwistMatrix::buildFrom(), vpAfma4::get_fMc(), and vpHomogeneousMatrix::inverse().
Referenced by get_cVf().
void vpRobotAfma4::get_cVf | ( | vpVelocityTwistMatrix & | cVf | ) | const |
Get the twist transformation from camera frame to the reference frame. This transformation allows to compute a velocity expressed in the reference frame into the camera frame.
cVf | : Twist transformation. |
Definition at line 543 of file vpRobotAfma4.cpp.
References vpAfma4::get_cVf(), vpAfma4::njoint, and vpERROR_TRACE.
|
inherited |
Get the robot jacobian expressed in the end-effector frame:
q | : Articular position of the four joints: q[0] corresponds to the first rotation (joint 1 with value ) of the turret around the vertical axis, while q[1] corresponds to the vertical translation (joint 2 with value ), while q[2] and q[3] correspond to the pan and tilt of the camera (respectively joint 4 and 5 with values and ). Rotations q[0], q[2] and q[3] are expressed in radians. The translation q[1] is expressed in meters. |
eJe | : Robot jacobian expressed in the end-effector frame, with:
|
Definition at line 395 of file vpAfma4.cpp.
References vpAfma4::_a1, vpAfma4::_d3, and vpArray2D< Type >::resize().
Referenced by get_eJe().
|
virtual |
Get the robot jacobian expressed in the end-effector frame. To have acces to the analytic form of this jacobian see vpAfma4::get_eJe().
To compute eJe, we communicate with the low level controller to get the articular joint position of the robot.
eJe | : Robot jacobian expressed in the end-effector frame. |
Implements vpRobot.
Definition at line 588 of file vpRobotAfma4.cpp.
References vpAfma4::get_eJe(), vpAfma4::njoint, and vpERROR_TRACE.
|
inherited |
Get the robot jacobian expressed in the robot reference frame also called fix frame:
q | : Articular position of the four joints: q[0] corresponds to the first rotation (joint 1 with value ) of the turret around the vertical axis, while q[1] corresponds to the vertical translation (joint 2 with value ), while q[2] and q[3] correspond to the pan and tilt of the camera (respectively joint 4 and 5 with values and ). Rotations q[0], q[2] and q[3] are expressed in radians. The translation q[1] is expressed in meters. |
fJe | : Robot jacobian expressed in the robot reference frame. |
Definition at line 450 of file vpAfma4.cpp.
References vpAfma4::_a1, vpAfma4::_d3, and vpArray2D< Type >::resize().
Referenced by get_fJe().
|
virtual |
Get the robot jacobian expressed in the robot reference frame also called fix frame. To have acces to the analytic form of this jacobian see vpAfma4::get_fJe().
To compute fJe, we communicate with the low level controller to get the articular joint position of the robot.
fJe | : Robot jacobian expressed in the reference frame. |
Implements vpRobot.
Definition at line 624 of file vpRobotAfma4.cpp.
References vpAfma4::get_fJe(), vpAfma4::njoint, and vpERROR_TRACE.
|
inherited |
Get the inverse jacobian.
q | : Articular position of the four joints: q[0] corresponds to the first rotation (joint 1 with value ) of the turret around the vertical axis, while q[1] corresponds to the vertical translation (joint 2 with value ), while q[2] and q[3] correspond to the pan and tilt of the camera (respectively joint 4 and 5 with values and ). Rotations q[0], q[2] and q[3] are expressed in radians. The translation q[1] is expressed in meters. |
fJe_inverse | : Inverse robot jacobian expressed in the robot reference frame. |
Definition at line 506 of file vpAfma4.cpp.
References vpAfma4::_a1, vpAfma4::_d3, and vpArray2D< Type >::resize().
Referenced by setVelocity().
|
inherited |
Compute the forward kinematics (direct geometric model) as an homogeneous matrix.
By forward kinematics we mean here the position and the orientation of the camera relative to the base frame given the articular positions of all the four joints.
This method is the same than getForwardKinematics(const vpColVector & q).
q | : Articular position of the four joints: q[0] corresponds to the first rotation (joint 1 with value ) of the turret around the vertical axis, while q[1] corresponds to the vertical translation (joint 2 with value ), while q[2] and q[3] correspond to the pan and tilt of the camera (respectively joint 4 and 5 with values and ). Rotations q[0], q[2] and q[3] are expressed in radians. The translation q[1] is expressed in meters. |
Definition at line 176 of file vpAfma4.cpp.
Referenced by vpAfma4::get_cVf(), vpAfma4::getForwardKinematics(), getPosition(), and getVelocity().
|
inherited |
Compute the forward kinematics (direct geometric model) as an homogeneous matrix.
By forward kinematics we mean here the position and the orientation of the camera relative to the base frame given the articular positions of all the four joints.
q | : Articular position of the four joints: q[0] corresponds to the first rotation (joint 1 with value ) of the turret around the vertical axis, while q[1] corresponds to the vertical translation (joint 2 with value ), while q[2] and q[3] correspond to the pan and tilt of the camera (respectively joint 4 and 5 with values and ). Rotations q[0], q[2] and q[3] are expressed in radians. The translation q[1] is expressed in meters. |
fMc | : The homogeneous matrix corresponding to the direct geometric model which expresses the transformation between the fix frame and the camera frame ( ) with:
|
Definition at line 210 of file vpAfma4.cpp.
References vpAfma4::_eMc, and vpAfma4::get_fMe().
|
inherited |
Compute the forward kinematics (direct geometric model) as an homogeneous matrix.
By forward kinematics we mean here the position and the orientation of the end effector with respect to the base frame given the articular positions of all the four variable joints.
q | : Articular position of the four joints: q[0] corresponds to the first rotation (joint 1 with value ) of the turret around the vertical axis, while q[1] corresponds to the vertical translation (joint 2 with value ), while q[2] and q[3] correspond to the pan and tilt of the camera (respectively joint 4 and 5 with values and ). Rotations q[0], q[2] and q[3] are expressed in radians. The translation q[1] is expressed in meters. |
fMe | The homogeneous matrix corresponding to the direct geometric model which expresses the transformation between the fix frame and the end effector frame ( ) with |
Definition at line 259 of file vpAfma4.cpp.
References vpAfma4::_a1, vpAfma4::_d3, and vpAfma4::_d4.
Referenced by vpAfma4::get_fMc(), and setVelocity().
|
virtual |
Get the robot displacement since the last call of this method.
frame | : The frame in which the measured displacement is expressed. |
displacement | : The measured displacement since the last call of this method. The dimension of displacement is always 4, the number of joints. Translations are expressed in meters, rotations in radians. |
In camera or reference frame, rotations are expressed with the Euler Rxyz representation.
Implements vpRobot.
Definition at line 1689 of file vpRobotAfma4.cpp.
References vpRobot::ARTICULAR_FRAME, vpRobot::CAMERA_FRAME, vpRobot::END_EFFECTOR_FRAME, vpRobotException::lowLevelError, vpRobot::MIXT_FRAME, vpAfma4::njoint, vpRobot::REFERENCE_FRAME, vpColVector::resize(), and vpERROR_TRACE.
|
inherited |
Compute the forward kinematics (direct geometric model) as an homogeneous matrix.
By forward kinematics we mean here the position and the orientation of the camera relative to the base frame given the articular positions of all the four joints.
This method is the same than get_fMc(const vpColVector & q).
q | : Articular position of the four joints: q[0] corresponds to the first rotation (joint 1 with value ) of the turret around the vertical axis, while q[1] corresponds to the vertical translation (joint 2 with value ), while q[2] and q[3] correspond to the pan and tilt of the camera (respectively joint 4 and 5 with values and ). Rotations q[0], q[2] and q[3] are expressed in radians. The translation q[1] is expressed in meters. |
Definition at line 139 of file vpAfma4.cpp.
References vpAfma4::get_fMc().
|
inherited |
Get max joint values.
Definition at line 557 of file vpAfma4.cpp.
References vpAfma4::_joint_max.
|
inherited |
Get min joint values.
Definition at line 541 of file vpAfma4.cpp.
References vpAfma4::_joint_min.
|
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(), vpSimulatorPioneer::setVelocity(), vpRobotPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotKinova::setVelocity(), vpRobotFlirPtu::setVelocity(), vpSimulatorAfma6::setVelocity(), vpSimulatorViper850::setVelocity(), 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(), vpSimulatorPioneer::setVelocity(), vpRobotPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotKinova::setVelocity(), vpRobotFlirPtu::setVelocity(), vpSimulatorAfma6::setVelocity(), vpSimulatorViper850::setVelocity(), setVelocity(), vpRobotAfma6::setVelocity(), vpRobotFranka::setVelocity(), vpRobotViper650::setVelocity(), and vpRobotViper850::setVelocity().
|
inherited |
Return the current robot position in the specified frame.
Definition at line 216 of file vpRobot.cpp.
References vpRobot::getPosition().
|
virtual |
Get the current position of the robot.
Similar as getPosition(const vpRobot::vpControlFrameType frame, vpColVector &, double &).
The difference is here that the timestamp is not used.
Implements vpRobot.
Definition at line 1068 of file vpRobotAfma4.cpp.
Referenced by setVelocity().
void vpRobotAfma4::getPosition | ( | const vpRobot::vpControlFrameType | frame, |
vpColVector & | position, | ||
double & | timestamp | ||
) |
Get the current position of the robot.
frame | : Control frame type in which to get the position, either :
|
position | : Measured position of the robot:
|
timestamp | : Time in second since last robot power on. |
vpRobotException::lowLevelError | : If the position cannot be get from the low level controller. |
Definition at line 994 of file vpRobotAfma4.cpp.
References vpRobot::ARTICULAR_FRAME, vpRxyzVector::buildFrom(), vpRobot::CAMERA_FRAME, vpRobot::END_EFFECTOR_FRAME, vpHomogeneousMatrix::extract(), vpAfma4::get_fMc(), vpRobotException::lowLevelError, vpRobot::MIXT_FRAME, vpAfma4::njoint, vpRobot::REFERENCE_FRAME, vpColVector::resize(), and vpERROR_TRACE.
double vpRobotAfma4::getPositioningVelocity | ( | void | ) |
Get the maximal velocity percentage used for a position control.
Definition at line 679 of file vpRobotAfma4.cpp.
bool vpRobotAfma4::getPowerState | ( | void | ) |
Get the robot power state indication if power is on or off.
vpRobotException::lowLevelError | : If the low level controller returns an error. |
Definition at line 496 of file vpRobotAfma4.cpp.
References vpRobotException::lowLevelError, and vpERROR_TRACE.
|
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(), setPosition(), vpSimulatorViper850::setPosition(), vpRobotAfma6::setPosition(), vpRobotFranka::setPosition(), vpRobotViper650::setPosition(), vpRobotViper850::setPosition(), vpRobotPtu46::setRobotState(), vpRobotBiclops::setRobotState(), vpRobotFlirPtu::setRobotState(), vpSimulatorAfma6::setRobotState(), vpSimulatorViper850::setRobotState(), setRobotState(), vpRobotAfma6::setRobotState(), vpRobotFranka::setRobotState(), vpRobotViper650::setRobotState(), vpRobotViper850::setRobotState(), vpRobotTemplate::setVelocity(), vpRobotBiclops::setVelocity(), vpRobotPtu46::setVelocity(), vpSimulatorCamera::setVelocity(), vpRobotCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotFlirPtu::setVelocity(), vpRobotKinova::setVelocity(), vpSimulatorAfma6::setVelocity(), vpSimulatorViper850::setVelocity(), setVelocity(), vpRobotAfma6::setVelocity(), vpRobotFranka::setVelocity(), vpRobotViper650::setVelocity(), vpRobotViper850::setVelocity(), vpRobotFlirPtu::stopMotion(), vpSimulatorAfma6::stopMotion(), vpSimulatorViper850::stopMotion(), vpRobotFranka::stopMotion(), vpRobotViper650::stopMotion(), and vpRobotViper850::stopMotion().
double vpRobotAfma4::getTime | ( | ) | const |
Returns the robot controller current time (in second) since last robot power on.
Definition at line 927 of file vpRobotAfma4.cpp.
void vpRobotAfma4::getVelocity | ( | const vpRobot::vpControlFrameType | frame, |
vpColVector & | velocity | ||
) |
Get robot velocities.
The behavior is the same than getVelocity(const vpRobot::vpControlFrameType, vpColVector &, double &) except that the timestamp is not returned.
Definition at line 1422 of file vpRobotAfma4.cpp.
Referenced by getVelocity().
void vpRobotAfma4::getVelocity | ( | const vpRobot::vpControlFrameType | frame, |
vpColVector & | velocity, | ||
double & | timestamp | ||
) |
Get the robot velocities.
frame | : Frame in wich velocities are mesured. |
velocity | : Measured velocities. Translations are expressed in m/s and rotations in rad/s. |
timestamp | : Time in second since last robot power on. |
Definition at line 1316 of file vpRobotAfma4.cpp.
References vpRobot::ARTICULAR_FRAME, vpRobot::CAMERA_FRAME, vpRobot::END_EFFECTOR_FRAME, vpAfma4::get_fMc(), vpExponentialMap::inverse(), vpHomogeneousMatrix::inverse(), vpRobotException::lowLevelError, vpRobot::MIXT_FRAME, vpAfma4::njoint, vpRobot::REFERENCE_FRAME, vpColVector::resize(), vpERROR_TRACE, and vpRobotException::wrongStateError.
vpColVector vpRobotAfma4::getVelocity | ( | const vpRobot::vpControlFrameType | frame | ) |
Get robot velocities.
The behavior is the same than getVelocity(const vpRobot::vpControlFrameType, double &) except that the timestamp is not returned.
Definition at line 1483 of file vpRobotAfma4.cpp.
References getVelocity().
vpColVector vpRobotAfma4::getVelocity | ( | const vpRobot::vpControlFrameType | frame, |
double & | timestamp | ||
) |
Get the robot velocities.
frame | : Frame in wich velocities are mesured. |
timestamp | : Time in second since last robot power on. |
Definition at line 1467 of file vpRobotAfma4.cpp.
References getVelocity().
|
virtual |
Initialise the connection with the MotionBox or low level controller, power on the robot and wait 1 sec before returning to be sure the initialisation is done.
Implements vpRobot.
Definition at line 190 of file vpRobotAfma4.cpp.
References vpAfma4::_joint_max, vpAfma4::_joint_min, vpRobotException::constructionError, vpColVector::resize(), vpRobot::verbose_, and vpERROR_TRACE.
Referenced by vpRobotAfma4().
void vpRobotAfma4::move | ( | const char * | filename | ) |
Moves the robot to the joint position specified in the filename. The positioning velocity is set to 10% of the robot maximal velocity.
filename | File containing a joint position. |
Definition at line 1661 of file vpRobotAfma4.cpp.
References vpRobot::ARTICULAR_FRAME, readPosFile(), setPosition(), setPositioningVelocity(), setRobotState(), and vpRobot::STATE_POSITION_CONTROL.
void vpRobotAfma4::powerOff | ( | void | ) |
Power off the robot.
vpRobotException::lowLevelError | : If the low level controller returns an error during robot stopping. |
Definition at line 462 of file vpRobotAfma4.cpp.
References vpRobotException::communicationError, and vpERROR_TRACE.
void vpRobotAfma4::powerOn | ( | void | ) |
Power on the robot.
vpRobotException::lowLevelError | : If the low level controller returns an error during robot power on. |
Definition at line 395 of file vpRobotAfma4.cpp.
References vpRobotException::lowLevelError, and vpERROR_TRACE.
Referenced by setRobotState().
|
static |
Read joint positions in a specific Afma4 position file.
This position file has to start with a header. The six joint positions are given after the "R:" keyword. The first 3 values correspond to the joint translations X,Y,Z expressed in meters. The 3 last values correspond to the joint rotations A,B,C expressed in degres to be more representative for the user. Theses values are then converted in radians in q. The character "#" starting a line indicates a comment.
A typical content of such a file is given below:
filename | : Name of the position file to read. |
q | : Joint positions: X,Y,A,B. Translations Y is expressed in meters, while joint rotations X,A,B in radians. |
The code below shows how to read a position from a file and move the robot to this position.
Definition at line 1543 of file vpRobotAfma4.cpp.
References vpAfma4::njoint, vpMath::rad(), vpColVector::resize(), and vpIoTools::splitChain().
Referenced by move(), and 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 163 of file vpRobot.cpp.
References vpException::dimensionError, and vpArray2D< Type >::size().
Referenced by vpRobotTemplate::setVelocity(), vpSimulatorCamera::setVelocity(), vpRobotCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpRobotPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotFlirPtu::setVelocity(), vpRobotKinova::setVelocity(), setVelocity(), vpRobotAfma6::setVelocity(), vpRobotFranka::setVelocity(), vpRobotViper650::setVelocity(), and vpRobotViper850::setVelocity().
|
static |
Save joint (articular) positions in a specific Afma4 position file.
This position file starts with a header on the first line. After convertion of the rotations in degrees, the joint position q is written on a line starting with the keyword "R: ". See readPosFile() documentation for an example of such a file.
filename | : Name of the position file to create. |
q | : Joint positions: X,Y,A,B. Translations Y is expressed in meters, while joint rotations X,A,B in radians. |
Definition at line 1626 of file vpRobotAfma4.cpp.
References vpMath::deg().
|
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().
|
virtual |
Move to an absolute position with a given percent of max velocity. The percent of max velocity is to set with setPositioningVelocity().
This method owerloads setPosition(const vpRobot::vpControlFrameType, const vpColVector &).
position | : The joint positions to reach. position[0] corresponds to the first rotation of the turret around the vertical axis (joint 1 with value ), while position[1] corresponds to the vertical translation (joint 2 with value ), while position[2] and position[3] correspond to the pan and tilt of the camera (respectively joint 4 and 5 with values and ). Rotations position[0], position[2] and position[3] are expressed in radians. The translation q[1] is expressed in meters. |
frame | : Frame in which the position is expressed. |
vpRobotException::lowLevelError | : vpRobot::MIXT_FRAME and vpRobot::END_EFFECTOR_FRAME not implemented. |
vpRobotException::positionOutOfRangeError | : The requested position is out of range. |
vpRobotException::lowLevelError | : If the requested frame (vpRobot::REFERENCE_FRAME, vpRobot::CAMERA_FRAME, vpRobot::END_EFFECTOR_FRAME or vpRobot::MIXT_FRAME) are requested since they are not implemented. |
vpRobotException::positionOutOfRangeError | : The requested position is out of range. |
To catch the exception if the position is out of range, modify the code like:
Implements vpRobot.
Definition at line 753 of file vpRobotAfma4.cpp.
References vpRobot::ARTICULAR_FRAME, vpRobot::CAMERA_FRAME, vpArray2D< Type >::data, vpRobot::END_EFFECTOR_FRAME, vpRobot::getRobotState(), vpArray2D< Type >::getRows(), vpRobotException::lowLevelError, vpRobot::MIXT_FRAME, vpAfma4::njoint, vpRobotException::positionOutOfRangeError, vpRobot::REFERENCE_FRAME, setRobotState(), vpRobot::STATE_POSITION_CONTROL, and vpERROR_TRACE.
Referenced by move(), and setPosition().
void vpRobotAfma4::setPosition | ( | const vpRobot::vpControlFrameType | frame, |
const double | q1, | ||
const double | q2, | ||
const double | q4, | ||
const double | q5 | ||
) |
Move to an absolute position with a given percent of max velocity. The percent of max velocity is to set with setPositioningVelocity().
This method owerloads setPosition(const vpRobot::vpControlFrameType, const vpColVector &).
q1,q2,q4,q5 | : The four joint positions to reach. q1 corresponds to the first rotation (joint 1 with value ) of the turret around the vertical axis, while q2 corresponds to the vertical translation (joint 2 with value ), while q4 and q5 correspond to the pan and tilt of the camera (respectively joint 4 and 5 with values and ). Rotations q1, q4 and q5 are expressed in radians. The translation q2 is expressed in meters. |
frame | : Frame in which the position is expressed. |
vpRobotException::lowLevelError | : vpRobot::MIXT_FRAME and vpRobot::END_EFFECTOR_FRAME not implemented. |
vpRobotException::positionOutOfRangeError | : The requested position is out of range. |
Definition at line 862 of file vpRobotAfma4.cpp.
References vpAfma4::njoint, setPosition(), and vpERROR_TRACE.
void vpRobotAfma4::setPosition | ( | const char * | filename | ) |
Move to an absolute joint position with a given percent of max velocity. The robot state is set to position control. The percent of max velocity is to set with setPositioningVelocity(). The position to reach is defined in the position file.
filename | : Name of the position file to read. The readPosFile() documentation shows a typical content of such a position file. |
This method has the same behavior than the sample code given below;
vpRobotException::lowLevelError | : vpRobot::MIXT_FRAME and vpRobot::END_EFFECTOR_FRAME not implemented. |
vpRobotException::positionOutOfRangeError | : The requested position is out of range. |
Definition at line 908 of file vpRobotAfma4.cpp.
References vpRobot::ARTICULAR_FRAME, vpRobotException::lowLevelError, readPosFile(), setPosition(), setRobotState(), vpRobot::STATE_POSITION_CONTROL, and vpERROR_TRACE.
void vpRobotAfma4::setPositioningVelocity | ( | double | velocity | ) |
Set the maximal velocity percentage to use for a position control.
The default positioning velocity is defined by vpRobotAfma4::defaultPositioningVelocity. This method allows to change this default positioning velocity
velocity | : Percentage of the maximal velocity. Values should be in ]0:100]. |
Definition at line 672 of file vpRobotAfma4.cpp.
Referenced by move().
|
protectedinherited |
Definition at line 207 of file vpRobot.cpp.
Referenced by vpSimulatorAfma6::init(), vpSimulatorViper850::init(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpSimulatorAfma6::setVelocity(), and vpSimulatorViper850::setVelocity().
|
virtual |
Change the robot state.
newState | : New requested robot state. |
Reimplemented from vpRobot.
Definition at line 324 of file vpRobotAfma4.cpp.
References vpRobot::getRobotState(), powerOn(), vpRobot::setRobotState(), vpRobot::STATE_POSITION_CONTROL, vpRobot::STATE_STOP, and vpRobot::STATE_VELOCITY_CONTROL.
Referenced by move(), setPosition(), stopMotion(), vpRobotAfma4(), and ~vpRobotAfma4().
|
virtual |
Apply a velocity to the robot.
frame | : Control frame in which the velocity is expressed. Velocities could be expressed in the joint space or in the camera frame. The reference frame and mixt frame are not implemented. |
vel | : Velocity vector. Translation velocities are expressed in m/s while rotation velocities in rad/s. The size of this vector may be 4 (the number of dof) if frame is set to vpRobot::ARTICULAR_FRAME. The size of this vector is 2 when the control is in the camera frame (frame is than set to vpRobot::CAMERA_FRAME). |
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(). |
Implements vpRobot.
Definition at line 1127 of file vpRobotAfma4.cpp.
References vpAfma4::_eMc, vpRobot::ARTICULAR_FRAME, vpVelocityTwistMatrix::buildFrom(), vpRobot::CAMERA_FRAME, vpArray2D< Type >::data, vpRobot::eJe, vpRobot::END_EFFECTOR_FRAME, vpHomogeneousMatrix::extract(), vpAfma4::get_fJe_inverse(), vpAfma4::get_fMe(), vpRobot::getMaxRotationVelocity(), vpRobot::getMaxTranslationVelocity(), getPosition(), vpRobot::getRobotState(), vpArray2D< Type >::getRows(), vpRobot::MIXT_FRAME, vpAfma4::njoint, vpRobot::REFERENCE_FRAME, vpRobot::saturateVelocities(), vpRobot::STATE_VELOCITY_CONTROL, vpERROR_TRACE, and vpRobotException::wrongStateError.
|
inlineinherited |
Definition at line 159 of file vpRobot.h.
Referenced by vpRobotAfma4(), vpRobotAfma6::vpRobotAfma6(), vpRobotViper650::vpRobotViper650(), and vpRobotViper850::vpRobotViper850().
void vpRobotAfma4::stopMotion | ( | void | ) |
Stop the robot and set the robot state to vpRobot::STATE_STOP.
vpRobotException::lowLevelError | : If the low level controller returns an error during robot stopping. |
Definition at line 373 of file vpRobotAfma4.cpp.
References vpRobotException::lowLevelError, setRobotState(), vpRobot::STATE_STOP, and vpERROR_TRACE.
|
protectedinherited |
Definition at line 146 of file vpAfma4.h.
Referenced by vpAfma4::get_eJe(), vpAfma4::get_fJe(), vpAfma4::get_fJe_inverse(), vpAfma4::get_fMe(), and vpAfma4::vpAfma4().
|
protectedinherited |
Definition at line 147 of file vpAfma4.h.
Referenced by vpAfma4::get_eJe(), vpAfma4::get_fJe(), vpAfma4::get_fJe_inverse(), vpAfma4::get_fMe(), and vpAfma4::vpAfma4().
|
protectedinherited |
Definition at line 148 of file vpAfma4.h.
Referenced by vpAfma4::get_fMe(), and vpAfma4::vpAfma4().
|
protectedinherited |
Definition at line 156 of file vpAfma4.h.
Referenced by vpAfma4::get_cMe(), vpAfma4::get_fMc(), setVelocity(), and vpAfma4::vpAfma4().
|
protectedinherited |
Definition at line 154 of file vpAfma4.h.
Referenced by vpAfma4::vpAfma4().
|
protectedinherited |
Definition at line 153 of file vpAfma4.h.
Referenced by vpAfma4::vpAfma4().
|
protectedinherited |
Definition at line 149 of file vpAfma4.h.
Referenced by vpAfma4::getJointMax(), init(), and vpAfma4::vpAfma4().
|
protectedinherited |
Definition at line 150 of file vpAfma4.h.
Referenced by vpAfma4::getJointMin(), init(), and vpAfma4::vpAfma4().
|
protectedinherited |
Definition at line 112 of file vpRobot.h.
Referenced by vpRobot::operator=(), vpRobotCamera::vpRobotCamera(), vpSimulatorCamera::vpSimulatorCamera(), vpSimulatorPioneer::vpSimulatorPioneer(), and vpSimulatorPioneerPan::vpSimulatorPioneerPan().
|
static |
Default positioning velocity in percentage of the maximum velocity. This value is set to 15. The member function setPositioningVelocity() allows to change this value.
Definition at line 218 of file vpRobotAfma4.h.
Referenced by vpRobotAfma4().
|
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=(), setVelocity(), vpRobotCamera::vpRobotCamera(), and vpSimulatorCamera::vpSimulatorCamera().
|
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::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::vpSimulatorPioneer(), and vpSimulatorPioneerPan::vpSimulatorPioneerPan().
|
protectedinherited |
Definition at line 98 of file vpRobot.h.
Referenced by vpRobot::getMaxRotationVelocity(), vpRobotTemplate::init(), vpRobotFlirPtu::init(), vpRobotKinova::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(), vpRobotFlirPtu::init(), and vpRobotKinova::init().
|
protectedinherited |
Definition at line 96 of file vpRobot.h.
Referenced by vpRobot::getMaxTranslationVelocity(), vpRobotTemplate::init(), vpRobotFlirPtu::init(), vpRobotKinova::init(), vpRobot::operator=(), and vpRobot::setMaxTranslationVelocity().
|
staticprotectedinherited |
Definition at line 97 of file vpRobot.h.
Referenced by vpRobotTemplate::init(), vpRobotFlirPtu::init(), and vpRobotKinova::init().
|
protectedinherited |
number of degrees of freedom
Definition at line 102 of file vpRobot.h.
Referenced by vpRobotKinova::getJointPosition(), vpRobotTemplate::init(), vpRobotFlirPtu::init(), vpRobotKinova::init(), vpRobot::operator=(), vpRobotKinova::setDoF(), vpRobotKinova::setJointVelocity(), vpRobotKinova::setPosition(), vpRobotTemplate::setVelocity(), vpRobotFlirPtu::setVelocity(), vpRobotKinova::setVelocity(), vpRobotCamera::vpRobotCamera(), vpRobotFranka::vpRobotFranka(), vpSimulatorCamera::vpSimulatorCamera(), vpSimulatorPioneer::vpSimulatorPioneer(), and vpSimulatorPioneerPan::vpSimulatorPioneerPan().
|
staticinherited |
Number of joint.
Definition at line 142 of file vpAfma4.h.
Referenced by get_cVf(), get_eJe(), get_fJe(), getDisplacement(), getPosition(), getVelocity(), readPosFile(), setPosition(), and setVelocity().
|
protectedinherited |
Definition at line 114 of file vpRobot.h.
Referenced by vpRobot::operator=(), vpRobotCamera::vpRobotCamera(), vpSimulatorCamera::vpSimulatorCamera(), vpSimulatorPioneer::vpSimulatorPioneer(), vpSimulatorPioneerPan::vpSimulatorPioneerPan(), and vpRobot::~vpRobot().
|
protectedinherited |
Definition at line 113 of file vpRobot.h.
Referenced by vpRobot::operator=(), vpRobotCamera::vpRobotCamera(), vpSimulatorCamera::vpSimulatorCamera(), vpSimulatorPioneer::vpSimulatorPioneer(), vpSimulatorPioneerPan::vpSimulatorPioneerPan(), and vpRobot::~vpRobot().
|
protectedinherited |
Definition at line 116 of file vpRobot.h.
Referenced by init(), vpRobotAfma6::init(), vpRobotViper650::init(), vpRobotViper850::init(), vpRobot::operator=(), vpRobotAfma4(), vpRobotAfma6::vpRobotAfma6(), vpRobotViper650::vpRobotViper650(), and vpRobotViper850::vpRobotViper850().