Visual Servoing Platform
version 3.6.1 under development (2024-11-21)
|
#include <visp3/robot/vpRobotAfma6.h>
Public Types | |
enum | vpAfma6ToolType { TOOL_CCMOP , TOOL_GRIPPER , TOOL_VACUUM , TOOL_GENERIC_CAMERA , TOOL_INTEL_D435_CAMERA , TOOL_CUSTOM } |
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 | |
VP_EXPLICIT | vpRobotAfma6 (bool verbose=true) |
virtual | ~vpRobotAfma6 (void) |
bool | checkJointLimits (vpColVector &jointsStatus) |
void | closeGripper () |
void | getDisplacement (vpRobot::vpControlFrameType frame, vpColVector &displacement) |
void | getPosition (const vpRobot::vpControlFrameType frame, vpColVector &position) VP_OVERRIDE |
void | getPosition (const vpRobot::vpControlFrameType frame, vpColVector &position, double ×tamp) |
void | getPosition (const vpRobot::vpControlFrameType frame, vpPoseVector &position) |
void | getPosition (const vpRobot::vpControlFrameType frame, vpPoseVector &position, double ×tamp) |
double | getPositioningVelocity (void) |
bool | getPowerState () |
double | getTime () const |
void | getVelocity (const vpRobot::vpControlFrameType frame, vpColVector &velocity) |
void | getVelocity (const vpRobot::vpControlFrameType frame, vpColVector &velocity, double ×tamp) |
vpColVector | getVelocity (const vpRobot::vpControlFrameType frame) |
vpColVector | getVelocity (const vpRobot::vpControlFrameType frame, double ×tamp) |
void | get_cMe (vpHomogeneousMatrix &_cMe) const |
void | get_cVe (vpVelocityTwistMatrix &_cVe) const |
void | get_eJe (vpMatrix &_eJe) VP_OVERRIDE |
void | get_fJe (vpMatrix &_fJe) VP_OVERRIDE |
void | init (void) |
void | init (vpAfma6::vpAfma6ToolType tool, const vpHomogeneousMatrix &eMc) |
void | init (vpAfma6::vpAfma6ToolType tool, const std::string &filename) |
void | init (vpAfma6::vpAfma6ToolType tool, vpCameraParameters::vpCameraParametersProjType projModel=vpCameraParameters::perspectiveProjWithoutDistortion) |
void | move (const std::string &filename) |
void | move (const std::string &filename, double velocity) |
void | openGripper () |
void | powerOn () |
void | powerOff () |
void | setPosition (const vpRobot::vpControlFrameType frame, const vpPoseVector &pose) |
void | setPosition (const vpRobot::vpControlFrameType frame, const vpColVector &position) VP_OVERRIDE |
void | setPosition (const vpRobot::vpControlFrameType frame, double pos1, double pos2, double pos3, double pos4, double pos5, double pos6) |
void | setPosition (const std::string &filename) |
void | setPositioningVelocity (double velocity) |
void | set_eMc (const vpHomogeneousMatrix &eMc) |
vpRobot::vpRobotStateType | setRobotState (vpRobot::vpRobotStateType newState) |
void | setVelocity (const vpRobot::vpControlFrameType frame, const vpColVector &velocity) VP_OVERRIDE |
void | stopMotion () |
Inherited functionalities from vpAfma6 | |
void | init (const std::string &camera_extrinsic_parameters) |
void | init (const std::string &camera_extrinsic_parameters, const std::string &camera_intrinsic_parameters) |
vpHomogeneousMatrix | getForwardKinematics (const vpColVector &q) const |
int | getInverseKinematics (const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &nearest=true, const bool &verbose=false) const |
vpHomogeneousMatrix | get_eMc () const |
vpHomogeneousMatrix | get_fMc (const vpColVector &q) const |
void | get_fMc (const vpColVector &q, vpHomogeneousMatrix &fMc) const |
void | get_fMe (const vpColVector &q, vpHomogeneousMatrix &fMe) const |
void | get_eJe (const vpColVector &q, vpMatrix &eJe) const |
void | get_fJe (const vpColVector &q, vpMatrix &fJe) const |
vpAfma6ToolType | getToolType () const |
vpCameraParameters::vpCameraParametersProjType | getCameraParametersProjType () const |
void | getCameraParameters (vpCameraParameters &cam, const unsigned int &image_width, const unsigned int &image_height) const |
void | getCameraParameters (vpCameraParameters &cam, const vpImage< unsigned char > &I) const |
void | getCameraParameters (vpCameraParameters &cam, const vpImage< vpRGBa > &I) const |
vpColVector | getJointMin () const |
vpColVector | getJointMax () const |
double | getCoupl56 () const |
double | getLong56 () const |
void | parseConfigFile (const std::string &filename) |
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) |
void | setVerbose (bool verbose) |
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) |
Protected Member Functions | |
Protected Member Functions Inherited from vpRobot | |
vpControlFrameType | setRobotFrame (vpRobot::vpControlFrameType newFrame) |
vpControlFrameType | getRobotFrame (void) const |
Protected Attributes | |
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 |
Protected Member Functions Inherited from vpAfma6 | |
static const unsigned int | njoint = 6 |
double | _coupl_56 |
double | _long_56 |
double | _joint_max [6] |
double | _joint_min [6] |
vpTranslationVector | _etc |
vpRxyzVector | _erc |
vpHomogeneousMatrix | _eMc |
vpAfma6ToolType | tool_current |
vpCameraParameters::vpCameraParametersProjType | projModel |
void | setToolType (vpAfma6::vpAfma6ToolType tool) |
Control of Irisa's gantry robot named Afma6.
Implementation of the vpRobot class in order to control Irisa's Afma6 robot. This robot is a gantry robot with six degrees of freedom manufactured in 1992 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 ring light is attached around the camera. The control of this ring light is possible throw the vpRingLight class. A CCMOP gripper is also mounted on the end-effector. The pneumatic control of this gripper is possible throw the openGripper() or closeGripper() member functions.
This class allows to control the Afma6 gantry robot in position and velocity:
End-effector frame (vpRobot::END_EFFECTOR_FRAME) is 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 direct and inverse kinematics models are implemented in the vpAfma6 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 obtained with a projection model without distortion. To set the robot kinematics with the eMc matrix obtained with a camera perspective model including distortion you need to initialize the robot with:
You can get the intrinsic camera parameters of the image I acquired with the camera, with:
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 vpRobotAfma6::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 211 of file vpRobotAfma6.h.
|
inherited |
List of possible tools that can be attached to the robot end-effector.
|
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.
vpRobotAfma6::vpRobotAfma6 | ( | bool | verbose = true | ) |
The only available constructor.
This constructor calls init() to initialise the connection with the MotionBox or low level controller, send the default eMc homogeneous matrix, 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.
To set the extrinsic camera parameters related to the eMc matrix obtained with a camera perspective projection model including the distortion, use the code below:
Now, you can get the intrinsic camera parameters of the image I acquired with the camera, with:
Definition at line 157 of file vpRobotAfma6.cpp.
References defaultPositioningVelocity, init(), setRobotState(), vpRobot::setVerbose(), vpRobot::STATE_STOP, and vpRobot::verbose_.
|
virtual |
Destructor.
Free allocated resources.
Definition at line 567 of file vpRobotAfma6.cpp.
References setRobotState(), and vpRobot::STATE_STOP.
bool vpRobotAfma6::checkJointLimits | ( | vpColVector & | jointsStatus | ) |
Test the joints of the robot to detect if one or more is at its limit.
jointsStatus | : A vector (size 6) of the status of the joints. For each joint, the value is equal to 1 if the joint is at its maximal limit, -1 if the joint is at its minimal value and 0 otherwise. |
Definition at line 2307 of file vpRobotAfma6.cpp.
References vpRobotException::lowLevelError, vpAfma6::njoint, and vpColVector::resize().
void vpRobotAfma6::closeGripper | ( | ) |
Close the pneumatic CCMOP gripper.
Definition at line 2188 of file vpRobotAfma6.cpp.
References vpRobotException::lowLevelError.
void vpRobotAfma6::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 824 of file vpRobotAfma6.cpp.
References vpAfma6::get_cMe().
Referenced by setVelocity().
void vpRobotAfma6::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 806 of file vpRobotAfma6.cpp.
References vpVelocityTwistMatrix::buildFrom(), and vpAfma6::get_cMe().
|
inherited |
Get the robot jacobian expressed in the end-effector frame.
q | : Articular joint position of the robot. q[0], q[1], q[2] correspond to the first 3 translations expressed in meter, while q[3], q[4] and q[5] correspond to the 3 successives rotations expressed in radians. |
eJe | : Robot jacobian expressed in the end-effector frame. |
Definition at line 941 of file vpAfma6.cpp.
References vpAfma6::_coupl_56, vpAfma6::_long_56, and vpArray2D< Type >::resize().
Referenced by get_eJe().
|
virtual |
Get the robot jacobian expressed in the end-effector frame.
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 836 of file vpRobotAfma6.cpp.
References vpRobot::eJe, vpAfma6::get_eJe(), and vpAfma6::njoint.
|
inherited |
Get the geometric transformation between the end-effector frame and the camera or tool frame. This transformation is constant and correspond to the extrinsic camera parameters estimated by calibration.
Definition at line 908 of file vpAfma6.cpp.
References vpAfma6::_eMc.
|
inherited |
Get the robot jacobian expressed in the robot reference frame also called fix frame.
where is the coupling factor between join 5 and 6.
q | : Articular joint position of the robot. q[0], q[1], q[2] correspond to the first 3 translations expressed in meter, while q[3], q[4] and q[5] correspond to the 3 successives rotations expressed in radians. |
fJe | : Robot jacobian expressed in the robot reference frame. |
Definition at line 1011 of file vpAfma6.cpp.
References vpAfma6::_coupl_56, vpAfma6::_long_56, and vpArray2D< Type >::resize().
Referenced by get_fJe().
|
virtual |
Get the robot jacobian expressed in the robot reference frame also called fix frame.
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 881 of file vpRobotAfma6.cpp.
References vpRobot::fJe, vpAfma6::get_fJe(), and vpAfma6::njoint.
|
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 six joints.
This method is the same than getForwardKinematics(const vpColVector & q).
q | : Articular position of the six joints: q[0], q[1], q[2] correspond to the first 3 translations expressed in meter, while q[3], q[4] and q[5] correspond to the 3 successives rotations expressed in radians. |
Definition at line 784 of file vpAfma6.cpp.
Referenced by getDisplacement(), vpAfma6::getForwardKinematics(), getPosition(), getVelocity(), and setPosition().
|
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 six joints.
q | : Articular joint position of the robot. q[0], q[1], q[2] correspond to the first 3 translations expressed in meter, while q[3], q[4] and q[5] correspond to the 3 successives rotations expressed in radians. |
fMc | The homogeneous matrix corresponding to the direct geometric model which expresses the transformation between the fix frame and the camera frame (fMc). |
Definition at line 811 of file vpAfma6.cpp.
References vpAfma6::_eMc, and vpAfma6::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 six joints.
q | : Articular joint position of the robot. q[0], q[1], q[2] correspond to the first 3 translations expressed in meter, while q[3], q[4] and q[5] correspond to the 3 successives rotations expressed in radians. |
fMe | The homogeneous matrix corresponding to the direct geometric model which expresses the transformation between the fix frame and the end effector frame (fMe). |
Definition at line 844 of file vpAfma6.cpp.
References vpAfma6::_coupl_56, and vpAfma6::_long_56.
Referenced by vpAfma6::get_fMc().
|
inherited |
Get the current intrinsic camera parameters obtained by calibration.
cam | : In output, camera parameters to fill. |
image_width | : Image width used to compute camera calibration. |
image_height | : Image height used to compute camera calibration. |
The code below shows how to get the camera parameters of the camera attached to the robot.
vpRobotException::readingParametersError | : If the camera parameters are not found. |
Definition at line 1269 of file vpAfma6.cpp.
References vpAfma6::CONST_CAMERA_AFMA6_FILENAME, vpAfma6::CONST_CCMOP_CAMERA_NAME, vpAfma6::CONST_GENERIC_CAMERA_NAME, vpAfma6::CONST_GRIPPER_CAMERA_NAME, vpAfma6::CONST_INTEL_D435_CAMERA_NAME, vpAfma6::CONST_VACUUM_CAMERA_NAME, vpAfma6::getToolType(), vpCameraParameters::initPersProjWithDistortion(), vpCameraParameters::initPersProjWithoutDistortion(), vpException::notImplementedError, vpXmlParserCamera::parse(), vpCameraParameters::perspectiveProjWithDistortion, vpCameraParameters::perspectiveProjWithoutDistortion, vpAfma6::projModel, vpCameraParameters::ProjWithKannalaBrandtDistortion, vpRobotException::readingParametersError, vpXmlParserCamera::SEQUENCE_OK, vpAfma6::TOOL_CCMOP, vpAfma6::TOOL_GENERIC_CAMERA, vpAfma6::TOOL_GRIPPER, vpAfma6::TOOL_INTEL_D435_CAMERA, and vpAfma6::TOOL_VACUUM.
Referenced by vpAfma6::getCameraParameters().
|
inherited |
Get the current intrinsic camera parameters obtained by calibration.
Camera parameters are read from /udd/fspindle/robot/Afma6/current/include/const_camera_Afma6.xml
cam | : In output, camera parameters to fill. |
I | : A B&W image send by the current camera in use. |
vpRobotException::readingParametersError | : If the camera parameters are not found. |
Definition at line 1515 of file vpAfma6.cpp.
References vpAfma6::getCameraParameters(), vpImage< Type >::getHeight(), and vpImage< Type >::getWidth().
|
inherited |
Get the current intrinsic camera parameters obtained by calibration.
Camera parameters are read from /udd/fspindle/robot/Afma6/current/include/const_camera_Afma6.xml
cam | : In output, camera parameters to fill. |
I | : A color image send by the current camera in use. |
vpRobotException::readingParametersError | : If the camera parameters are not found. |
Definition at line 1566 of file vpAfma6.cpp.
References vpAfma6::getCameraParameters(), vpImage< Type >::getHeight(), and vpImage< Type >::getWidth().
|
inlineinherited |
|
inherited |
Return the coupling factor between join 5 and 6.
Definition at line 1082 of file vpAfma6.cpp.
References vpAfma6::_coupl_56.
|
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
|
In camera or reference frame, rotations are expressed with the Euler Rxyz representation.
Implements vpRobot.
Definition at line 2218 of file vpRobotAfma6.cpp.
References vpRobot::ARTICULAR_FRAME, vpRxyzVector::buildFrom(), vpRobot::CAMERA_FRAME, vpRobot::END_EFFECTOR_FRAME, vpHomogeneousMatrix::extract(), vpAfma6::get_fMc(), vpHomogeneousMatrix::inverse(), vpRobotException::lowLevelError, vpRobot::MIXT_FRAME, vpAfma6::njoint, vpRobot::REFERENCE_FRAME, and vpColVector::resize().
|
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 six joints.
This method is the same than get_fMc(const vpColVector & q).
q | : Articular position of the six joints: q[0], q[1], q[2] correspond to the first 3 translations expressed in meter, while q[3], q[4] and q[5] correspond to the 3 successives rotations expressed in radians. |
Definition at line 519 of file vpAfma6.cpp.
References vpAfma6::get_fMc().
|
inherited |
Compute the inverse kinematics (inverse geometric model).
By inverse kinematics we mean here the six articular values of the joint positions given the position and the orientation of the camera frame relative to the base frame.
fMc | : Homogeneous matrix describing the transformation from base frame to the camera frame. |
q | : In input, the current articular joint position of the robot. In output, the solution of the inverse kinematics. Articular position of the six joints: q[0], q[1], q[2] correspond to the first 3 translations expressed in meter, while q[3], q[4] and q[5] correspond to the 3 successives rotations expressed in radians. |
nearest | : true to return the nearest solution to q. false to return the farest. |
verbose | : Activates printings when no solution is found. |
The code below shows how to compute the inverse geometric model:
Definition at line 603 of file vpAfma6.cpp.
References vpAfma6::_coupl_56, vpAfma6::_eMc, vpAfma6::_joint_max, vpAfma6::_joint_min, vpAfma6::_long_56, vpMath::deg(), vpArray2D< Type >::getRows(), vpHomogeneousMatrix::inverse(), vpAfma6::njoint, vpMath::rad(), and vpColVector::resize().
Referenced by setPosition().
|
inherited |
Get max joint values.
Definition at line 1068 of file vpAfma6.cpp.
References vpAfma6::_joint_max.
|
inherited |
Get min joint values.
Definition at line 1052 of file vpAfma6.cpp.
References vpAfma6::_joint_min.
|
inherited |
Return the distance between join 5 and 6.
Definition at line 1090 of file vpAfma6.cpp.
References vpAfma6::_long_56.
|
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(), vpRobotPioneer::setVelocity(), vpRobotTemplate::setVelocity(), vpRobotUniversalRobots::setVelocity(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotAfma4::setVelocity(), 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(), vpRobotPioneer::setVelocity(), vpRobotTemplate::setVelocity(), vpRobotUniversalRobots::setVelocity(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotAfma4::setVelocity(), 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().
|
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 1534 of file vpRobotAfma6.cpp.
Referenced by getPosition().
void vpRobotAfma6::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 1450 of file vpRobotAfma6.cpp.
References vpRobot::ARTICULAR_FRAME, vpRxyzVector::buildFrom(), vpRobot::CAMERA_FRAME, vpRobot::END_EFFECTOR_FRAME, vpHomogeneousMatrix::extract(), vpAfma6::get_fMc(), vpRobotException::lowLevelError, vpRobot::MIXT_FRAME, vpAfma6::njoint, vpRobot::REFERENCE_FRAME, and vpColVector::resize().
void vpRobotAfma6::getPosition | ( | const vpRobot::vpControlFrameType | frame, |
vpPoseVector & | position | ||
) |
Get the current position of the robot.
Similar as getPosition(const vpRobot::vpControlFrameType frame, vpPoseVector &, double &).
The difference is here that the timestamp is not used.
Definition at line 1577 of file vpRobotAfma6.cpp.
References getPosition().
void vpRobotAfma6::getPosition | ( | const vpRobot::vpControlFrameType | frame, |
vpPoseVector & | position, | ||
double & | timestamp | ||
) |
Get the current position of the robot. Similar as : void getPosition (const vpRobot::vpControlFrameType frame, vpColVector &position) as the difference the position is returned using a ThetaU representation.
Definition at line 1549 of file vpRobotAfma6.cpp.
References getPosition().
double vpRobotAfma6::getPositioningVelocity | ( | void | ) |
Get the maximal velocity percentage used for a position control.
Definition at line 939 of file vpRobotAfma6.cpp.
bool vpRobotAfma6::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 776 of file vpRobotAfma6.cpp.
References vpRobotException::lowLevelError.
|
inlineprotectedinherited |
|
inlinevirtualinherited |
Definition at line 155 of file vpRobot.h.
Referenced by vpRobotBiclops::getPosition(), vpRobotBiclops::getVelocity(), vpSimulatorCamera::setPosition(), vpRobotAfma4::setPosition(), setPosition(), vpRobotFranka::setPosition(), vpRobotUniversalRobots::setPosition(), vpRobotViper650::setPosition(), vpRobotViper850::setPosition(), vpRobotBiclops::setPosition(), vpRobotPololuPtu::setPosition(), vpRobotPtu46::setPosition(), vpRobotBiclops::setRobotState(), vpRobotPololuPtu::setRobotState(), vpRobotAfma4::setRobotState(), 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(), setVelocity(), vpRobotViper650::setVelocity(), vpRobotViper850::setVelocity(), vpRobotFlirPtu::stopMotion(), vpRobotFranka::stopMotion(), vpRobotViper650::stopMotion(), and vpRobotViper850::stopMotion().
double vpRobotAfma6::getTime | ( | ) | const |
Returns the robot controller current time (in second) since last robot power on.
Definition at line 1517 of file vpRobotAfma6.cpp.
|
inlineinherited |
Get the current tool type.
Definition at line 169 of file vpAfma6.h.
Referenced by vpAfma6::getCameraParameters().
vpColVector vpRobotAfma6::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 1954 of file vpRobotAfma6.cpp.
References getVelocity().
vpColVector vpRobotAfma6::getVelocity | ( | const vpRobot::vpControlFrameType | frame, |
double & | timestamp | ||
) |
Get the robot velocities.
frame | : Frame in which velocities are measured. |
timestamp | : Time in second since last robot power on. |
Definition at line 1938 of file vpRobotAfma6.cpp.
References getVelocity().
void vpRobotAfma6::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 1891 of file vpRobotAfma6.cpp.
Referenced by getVelocity().
void vpRobotAfma6::getVelocity | ( | const vpRobot::vpControlFrameType | frame, |
vpColVector & | velocity, | ||
double & | timestamp | ||
) |
Get the robot velocities.
frame | : Frame in which velocities are measured. |
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 1780 of file vpRobotAfma6.cpp.
References vpRobot::ARTICULAR_FRAME, vpThetaUVector::buildFrom(), vpRobot::CAMERA_FRAME, vpHomogeneousMatrix::extract(), vpException::functionNotImplementedError, vpAfma6::get_fMc(), vpHomogeneousMatrix::inverse(), vpExponentialMap::inverse(), vpRobotException::lowLevelError, vpRobot::MIXT_FRAME, vpAfma6::njoint, vpRobot::REFERENCE_FRAME, and vpColVector::resize().
|
inherited |
Read files containing the constant parameters related to the robot tools in order to set the end-effector to tool transformation.
camera_extrinsic_parameters | : Filename containing the camera extrinsic parameters. |
Definition at line 227 of file vpAfma6.cpp.
References vpAfma6::parseConfigFile().
|
inherited |
Read files containing the constant parameters related to the robot kinematics and to the end-effector to camera transformation.
camera_extrinsic_parameters | : Filename containing the constant parameters of the robot kinematics transformation. |
camera_intrinsic_parameters | : Filename containing the camera extrinsic parameters. |
Definition at line 175 of file vpAfma6.cpp.
References vpAfma6::parseConfigFile().
|
virtual |
Initialise the connection with the MotionBox or low level controller, send the default eMc homogeneous matrix, power on the robot and wait 1 sec before returning to be sure the initialisation is done.
Implements vpRobot.
Definition at line 226 of file vpRobotAfma6.cpp.
References vpAfma6::_joint_max, vpAfma6::_joint_min, vpRobotException::constructionError, vpAfma6::defaultTool, vpColVector::resize(), and vpRobot::verbose_.
Referenced by vpRobotAfma6().
void vpRobotAfma6::init | ( | vpAfma6::vpAfma6ToolType | tool, |
const std::string & | filename | ||
) |
Initialize the robot kinematics (set the eMc homogeneous parameters in the low level controller) from a file and also get the joint limits from the low-level controller.
tool | : Tool to use. |
filename | : Path of the configuration file containing the transformation between the end-effector frame and the tool frame. |
To set the transformation parameters related to the matrix, use the code below:
The configuration file should have the form below:
Definition at line 529 of file vpRobotAfma6.cpp.
References vpAfma6::_coupl_56, vpAfma6::_erc, vpAfma6::_etc, vpAfma6::_joint_max, vpAfma6::_joint_min, vpAfma6::_long_56, vpAfma6::init(), and vpAfma6::setToolType().
void vpRobotAfma6::init | ( | vpAfma6::vpAfma6ToolType | tool, |
const vpHomogeneousMatrix & | eMc | ||
) |
Initialize the robot kinematics with user defined parameters (set the eMc homogeneous parameters in the low level controller) and also get the joint limits from the low-level controller.
tool | : Tool to use. |
eMc | : Transformation between the end-effector frame and the tool frame. |
To set the transformation parameters related to the matrix, use the code below:
Definition at line 447 of file vpRobotAfma6.cpp.
References vpAfma6::_coupl_56, vpAfma6::_erc, vpAfma6::_etc, vpAfma6::_joint_max, vpAfma6::_joint_min, vpAfma6::_long_56, vpAfma6::init(), and vpAfma6::setToolType().
void vpRobotAfma6::init | ( | vpAfma6::vpAfma6ToolType | tool, |
vpCameraParameters::vpCameraParametersProjType | projModel = vpCameraParameters::perspectiveProjWithoutDistortion |
||
) |
Initialize the robot kinematics with the extrinsic calibration parameters associated to a specific camera (set the eMc homogeneous parameters in the low level controller) and also get the joint limits from the low-level controller.
The eMc parameters depend on the camera and the projection model in use.
tool | : Tool to use. |
projModel | : Projection model associated to the camera. |
To set the extrinsic camera parameters related to the eMc matrix obtained with a camera perspective projection model including the distortion, use the code below:
Now, you can get the intrinsic camera parameters of the image I acquired with the camera, with:
Definition at line 346 of file vpRobotAfma6.cpp.
References vpAfma6::_coupl_56, vpAfma6::_erc, vpAfma6::_etc, vpAfma6::_joint_max, vpAfma6::_joint_min, vpAfma6::_long_56, vpAfma6::init(), vpAfma6::projModel, and vpAfma6::setToolType().
void vpRobotAfma6::move | ( | const std::string & | 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 to reach. |
Definition at line 2131 of file vpRobotAfma6.cpp.
References vpRobot::ARTICULAR_FRAME, readPosFile(), setPosition(), setPositioningVelocity(), setRobotState(), and vpRobot::STATE_POSITION_CONTROL.
void vpRobotAfma6::move | ( | const std::string & | filename, |
double | velocity | ||
) |
Moves the robot to the joint position specified in the filename with a specified positioning velocity.
filename | : File containing a joint position to reach. |
velocity | : Percentage of the maximal velocity. Values should be in ]0:100]. |
Definition at line 2153 of file vpRobotAfma6.cpp.
References vpRobot::ARTICULAR_FRAME, readPosFile(), setPosition(), setPositioningVelocity(), setRobotState(), and vpRobot::STATE_POSITION_CONTROL.
void vpRobotAfma6::openGripper | ( | ) |
Open the pneumatic CCMOP gripper.
Definition at line 2169 of file vpRobotAfma6.cpp.
References vpRobotException::lowLevelError.
|
inherited |
This function gets the robot constant parameters from a file.
filename | : File name containing the robot constant parameters, like max/min joint values, distance between 5 and 6 axis, coupling factor between axis 5 and 6, and the hand-to-eye homogeneous matrix. |
Definition at line 1102 of file vpAfma6.cpp.
References vpAfma6::_coupl_56, vpAfma6::_eMc, vpAfma6::_erc, vpAfma6::_etc, vpAfma6::_joint_max, vpAfma6::_joint_min, vpAfma6::_long_56, vpHomogeneousMatrix::buildFrom(), and vpRobotException::readingParametersError.
Referenced by vpAfma6::init().
void vpRobotAfma6::powerOff | ( | void | ) |
Power off the robot.
vpRobotException::lowLevelError | : If the low level controller returns an error during robot stopping. |
Definition at line 742 of file vpRobotAfma6.cpp.
References vpRobotException::lowLevelError.
void vpRobotAfma6::powerOn | ( | void | ) |
Power on the robot.
vpRobotException::lowLevelError | : If the low level controller returns an error during robot power on. |
Definition at line 672 of file vpRobotAfma6.cpp.
References vpRobotException::lowLevelError.
Referenced by setRobotState().
|
static |
Read joint positions in a specific Afma6 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,Z,A,B,C. Translations X,Y,Z are expressed in meters, while joint rotations A,B,C in radians. |
The code below shows how to read a position from a file and move the robot to this position.
Definition at line 2012 of file vpRobotAfma6.cpp.
References vpAfma6::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 164 of file vpRobot.cpp.
References vpException::dimensionError, and vpArray2D< Type >::size().
Referenced by vpRobotFlirPtu::setVelocity(), vpRobotFranka::setVelocity(), vpRobotKinova::setVelocity(), vpRobotPioneer::setVelocity(), vpRobotTemplate::setVelocity(), vpRobotUniversalRobots::setVelocity(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotAfma4::setVelocity(), setVelocity(), vpRobotViper650::setVelocity(), and vpRobotViper850::setVelocity().
|
static |
Save joint (articular) positions in a specific Afma6 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,Z,A,B,C] to save in the filename. Translations X,Y,Z are expressed in meters, while rotations A,B,C in radians. |
Definition at line 2096 of file vpRobotAfma6.cpp.
References vpMath::deg().
|
virtual |
Set the geometric transformation between the end-effector frame and the tool frame in the low level controller.
eMc | : Transformation between the end-effector frame and the tool frame. |
Reimplemented from vpAfma6.
Definition at line 390 of file vpRobotAfma6.cpp.
References vpAfma6::_erc, vpAfma6::_etc, and vpAfma6::set_eMc().
|
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.
void vpRobotAfma6::setPosition | ( | const std::string & | 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 1381 of file vpRobotAfma6.cpp.
References vpRobot::ARTICULAR_FRAME, vpRobotException::lowLevelError, readPosFile(), setPosition(), setRobotState(), and vpRobot::STATE_POSITION_CONTROL.
|
virtual |
Move to an absolute position with a given percent of max velocity. The percent of max velocity is to set with setPositioningVelocity(). The position to reach can be specified in joint coordinates, in the camera frame or in the reference frame.
position | : A six dimension vector corresponding to the position to reach. All the positions are expressed in meters for the translations and radians for the rotations. If the position is out of range, an exception is provided. |
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. |
To catch the exception if the position is out of range, modify the code like:
Implements vpRobot.
Definition at line 1124 of file vpRobotAfma6.cpp.
References vpRobot::ARTICULAR_FRAME, vpRobot::CAMERA_FRAME, vpRobot::END_EFFECTOR_FRAME, vpAfma6::get_fMc(), vpAfma6::getInverseKinematics(), vpRobot::getRobotState(), vpRobotException::lowLevelError, vpRobot::MIXT_FRAME, vpAfma6::njoint, vpRobotException::positionOutOfRangeError, vpRobot::REFERENCE_FRAME, setRobotState(), and vpRobot::STATE_POSITION_CONTROL.
void vpRobotAfma6::setPosition | ( | const vpRobot::vpControlFrameType | frame, |
const vpPoseVector & | pose | ||
) |
Move the robot to an absolute cartesian position with a given percent of max velocity. The percent of max velocity is to set with setPositioningVelocity(). The position to reach can only be specified in camera frame or in the reference frame. In joint, an exception is thrown.
pose | : A six dimension pose vector corresponding to the position to reach. The three first parameters are the translations in meter, the three last parameters are the rotations expressed as a theta u vector in radians. If the position is out of range, an exception is provided. |
frame | : Frame in which the position is expressed. |
vpRobotException::lowLevelError | : vpRobot::MIXT_FRAME, vpRobot::END_EFFECTOR_FRAME and vpRobot::ARTICULAR_FRAME 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:
Definition at line 1018 of file vpRobotAfma6.cpp.
References vpRobot::ARTICULAR_FRAME, vpRotationMatrix::buildFrom(), vpRxyzVector::buildFrom(), and vpRobotException::lowLevelError.
Referenced by move(), and setPosition().
void vpRobotAfma6::setPosition | ( | const vpRobot::vpControlFrameType | frame, |
double | pos1, | ||
double | pos2, | ||
double | pos3, | ||
double | pos4, | ||
double | pos5, | ||
double | pos6 | ||
) |
Move to an absolute position with a given percent of max velocity. The percent of max velocity is to set with setPositioningVelocity(). The position to reach can be specified in joint coordinates, in the camera frame or in the reference frame.
This method owerloads setPosition(const vpRobot::vpControlFrameType, const vpColVector &).
pos1,pos2,pos3,pos4,pos5,pos6 | : The six coordinates of the position to reach. All the positions are expressed in meters for the translations and radians for the rotations. |
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 1317 of file vpRobotAfma6.cpp.
References setPosition().
void vpRobotAfma6::setPositioningVelocity | ( | double | velocity | ) |
Set the maximal velocity percentage to use for a position control.
The default positioning velocity is defined by vpRobotAfma6::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 932 of file vpRobotAfma6.cpp.
Referenced by move().
|
protectedinherited |
Definition at line 208 of file vpRobot.cpp.
Referenced by vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), and vpSimulatorPioneerPan::setVelocity().
|
virtual |
Change the robot state.
newState | : New requested robot state. |
Reimplemented from vpRobot.
Definition at line 600 of file vpRobotAfma6.cpp.
References vpRobot::getRobotState(), powerOn(), vpRobot::setRobotState(), vpRobot::STATE_POSITION_CONTROL, vpRobot::STATE_STOP, and vpRobot::STATE_VELOCITY_CONTROL.
Referenced by move(), setPosition(), stopMotion(), vpRobotAfma6(), and ~vpRobotAfma6().
|
inlineprotectedinherited |
Set the current tool type.
Definition at line 194 of file vpAfma6.h.
Referenced by vpAfma6::init(), and init().
|
virtual |
Apply a velocity to the robot.
frame | : Control frame in which the velocity is expressed. Velocities could be expressed in articular, camera frame, reference frame or mixt frame. |
vel | : Velocity vector. Translation velocities are expressed in m/s while rotation velocities in rad/s. The size of this vector is always 6. |
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 1646 of file vpRobotAfma6.cpp.
References vpRobot::ARTICULAR_FRAME, vpRobot::CAMERA_FRAME, vpArray2D< Type >::data, vpRobot::END_EFFECTOR_FRAME, get_cMe(), vpRobot::getMaxRotationVelocity(), vpRobot::getMaxTranslationVelocity(), vpRobot::getRobotState(), vpRobot::MIXT_FRAME, vpAfma6::njoint, vpRobot::REFERENCE_FRAME, vpRobot::saturateVelocities(), vpRobot::STATE_VELOCITY_CONTROL, and vpRobotException::wrongStateError.
|
inlineinherited |
Definition at line 170 of file vpRobot.h.
Referenced by vpRobotAfma4::vpRobotAfma4(), vpRobotAfma6(), vpRobotViper650::vpRobotViper650(), and vpRobotViper850::vpRobotViper850().
void vpRobotAfma6::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 650 of file vpRobotAfma6.cpp.
References vpRobotException::lowLevelError, setRobotState(), and vpRobot::STATE_STOP.
|
protectedinherited |
Definition at line 201 of file vpAfma6.h.
Referenced by vpAfma6::get_eJe(), vpAfma6::get_fJe(), vpAfma6::get_fMe(), vpAfma6::getCoupl56(), vpAfma6::getInverseKinematics(), init(), vpAfma6::parseConfigFile(), and vpAfma6::vpAfma6().
|
protectedinherited |
Definition at line 209 of file vpAfma6.h.
Referenced by vpAfma6::get_cMe(), vpAfma6::get_eMc(), vpAfma6::get_fMc(), vpAfma6::getInverseKinematics(), vpAfma6::init(), vpAfma6::parseConfigFile(), vpAfma6::set_eMc(), and vpAfma6::vpAfma6().
|
protectedinherited |
Definition at line 207 of file vpAfma6.h.
Referenced by vpAfma6::init(), init(), vpAfma6::parseConfigFile(), vpAfma6::set_eMc(), and set_eMc().
|
protectedinherited |
Definition at line 206 of file vpAfma6.h.
Referenced by vpAfma6::init(), init(), vpAfma6::parseConfigFile(), vpAfma6::set_eMc(), and set_eMc().
|
protectedinherited |
Definition at line 203 of file vpAfma6.h.
Referenced by vpAfma6::getInverseKinematics(), vpAfma6::getJointMax(), init(), vpAfma6::parseConfigFile(), and vpAfma6::vpAfma6().
|
protectedinherited |
Definition at line 204 of file vpAfma6.h.
Referenced by vpAfma6::getInverseKinematics(), vpAfma6::getJointMin(), init(), vpAfma6::parseConfigFile(), and vpAfma6::vpAfma6().
|
protectedinherited |
Definition at line 202 of file vpAfma6.h.
Referenced by vpAfma6::get_eJe(), vpAfma6::get_fJe(), vpAfma6::get_fMe(), vpAfma6::getInverseKinematics(), vpAfma6::getLong56(), init(), vpAfma6::parseConfigFile(), and vpAfma6::vpAfma6().
|
protectedinherited |
Definition at line 114 of file vpRobot.h.
Referenced by vpRobot::operator=().
|
staticinherited |
File where constant parameters in relation with the robot are stored: joint max, min, coupling factor between 4 ant 5 joint, distance between 5 and 6 joint, transformation eMc between end-effector and camera frame.
Definition at line 84 of file vpAfma6.h.
Referenced by vpAfma6::init().
|
staticinherited |
Definition at line 95 of file vpAfma6.h.
Referenced by vpAfma6::getCameraParameters().
|
staticinherited |
Name of the camera attached to the CCMOP tool (vpAfma6ToolType::TOOL_CCMOP).
Definition at line 101 of file vpAfma6.h.
Referenced by vpAfma6::getCameraParameters().
|
staticinherited |
Definition at line 86 of file vpAfma6.h.
Referenced by vpAfma6::init().
|
staticinherited |
Definition at line 85 of file vpAfma6.h.
Referenced by vpAfma6::init().
|
staticinherited |
Definition at line 94 of file vpAfma6.h.
Referenced by vpAfma6::init().
|
staticinherited |
Definition at line 93 of file vpAfma6.h.
Referenced by vpAfma6::init().
|
staticinherited |
Definition at line 88 of file vpAfma6.h.
Referenced by vpAfma6::init().
|
staticinherited |
Definition at line 87 of file vpAfma6.h.
Referenced by vpAfma6::init().
|
staticinherited |
Definition at line 92 of file vpAfma6.h.
Referenced by vpAfma6::init().
|
staticinherited |
Definition at line 91 of file vpAfma6.h.
Referenced by vpAfma6::init().
|
staticinherited |
Definition at line 90 of file vpAfma6.h.
Referenced by vpAfma6::init().
|
staticinherited |
Definition at line 89 of file vpAfma6.h.
Referenced by vpAfma6::init().
|
staticinherited |
Name of the generic camera attached to the robot hand (vpAfma6ToolType::TOOL_GENERIC_CAMERA).
Definition at line 116 of file vpAfma6.h.
Referenced by vpAfma6::getCameraParameters().
|
staticinherited |
Name of the camera attached to the 2 fingers gripper tool (vpAfma6ToolType::TOOL_GRIPPER).
Definition at line 106 of file vpAfma6.h.
Referenced by vpAfma6::getCameraParameters().
|
staticinherited |
Name of the Intel D435 camera attached to the robot hand (vpAfma6ToolType::TOOL_INTEL_D435_CAMERA).
Definition at line 122 of file vpAfma6.h.
Referenced by vpAfma6::getCameraParameters().
|
staticinherited |
Name of the camera attached to the vacuum gripper tool (vpAfma6ToolType::TOOL_VACUUM).
Definition at line 111 of file vpAfma6.h.
Referenced by vpAfma6::getCameraParameters().
|
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 252 of file vpRobotAfma6.h.
Referenced by vpRobotAfma6().
|
staticinherited |
Default tool attached to the robot end effector.
Definition at line 136 of file vpAfma6.h.
Referenced by vpAfma6::init(), and init().
|
protectedinherited |
robot Jacobian expressed in the end-effector frame
Definition at line 106 of file vpRobot.h.
Referenced by vpRobotFlirPtu::get_eJe(), 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 |
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(), 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=().
|
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().
|
staticinherited |
Number of joint.
Definition at line 198 of file vpAfma6.h.
Referenced by checkJointLimits(), get_eJe(), get_fJe(), getDisplacement(), vpAfma6::getInverseKinematics(), getPosition(), getVelocity(), readPosFile(), setPosition(), and setVelocity().
|
protectedinherited |
Definition at line 215 of file vpAfma6.h.
Referenced by vpAfma6::getCameraParameters(), vpAfma6::init(), and init().
|
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 |
|
protectedinherited |
Definition at line 118 of file vpRobot.h.
Referenced by vpRobotAfma4::init(), init(), vpRobotViper650::init(), vpRobotViper850::init(), vpRobot::operator=(), vpRobotAfma4::vpRobotAfma4(), vpRobotAfma6(), vpRobotViper650::vpRobotViper650(), and vpRobotViper850::vpRobotViper850().