ViSP
2.10.0
|
#include <vpAfma6.h>
Public Types | |
enum | vpAfma6ToolType { TOOL_CCMOP, TOOL_GRIPPER, TOOL_VACUUM, TOOL_GENERIC_CAMERA } |
Static Public Attributes | |
static const char *const | CONST_AFMA6_FILENAME = "/udd/fspindle/robot/Afma6/current/include/const_Afma6.cnf" |
static const char *const | CONST_EMC_CCMOP_WITHOUT_DISTORTION_FILENAME = "/udd/fspindle/robot/Afma6/current/include/const_eMc_ccmop_without_distortion_Afma6.cnf" |
static const char *const | CONST_EMC_CCMOP_WITH_DISTORTION_FILENAME = "/udd/fspindle/robot/Afma6/current/include/const_eMc_ccmop_with_distortion_Afma6.cnf" |
static const char *const | CONST_EMC_GRIPPER_WITHOUT_DISTORTION_FILENAME = "/udd/fspindle/robot/Afma6/current/include/const_eMc_gripper_without_distortion_Afma6.cnf" |
static const char *const | CONST_EMC_GRIPPER_WITH_DISTORTION_FILENAME = "/udd/fspindle/robot/Afma6/current/include/const_eMc_gripper_with_distortion_Afma6.cnf" |
static const char *const | CONST_EMC_VACUUM_WITHOUT_DISTORTION_FILENAME = "/udd/fspindle/robot/Afma6/current/include/const_eMc_vacuum_without_distortion_Afma6.cnf" |
static const char *const | CONST_EMC_VACUUM_WITH_DISTORTION_FILENAME = "/udd/fspindle/robot/Afma6/current/include/const_eMc_vacuum_with_distortion_Afma6.cnf" |
static const char *const | CONST_EMC_GENERIC_WITHOUT_DISTORTION_FILENAME = "/udd/fspindle/robot/Afma6/current/include/const_eMc_generic_without_distortion_Afma6.cnf" |
static const char *const | CONST_EMC_GENERIC_WITH_DISTORTION_FILENAME = "/udd/fspindle/robot/Afma6/current/include/const_eMc_generic_with_distortion_Afma6.cnf" |
static const char *const | CONST_CAMERA_AFMA6_FILENAME = "/udd/fspindle/robot/Afma6/current/include/const_camera_Afma6.xml" |
static const char *const | CONST_CCMOP_CAMERA_NAME = "Dragonfly2-8mm-ccmop" |
static const char *const | CONST_GRIPPER_CAMERA_NAME = "Dragonfly2-6mm-gripper" |
static const char *const | CONST_VACUUM_CAMERA_NAME = "Dragonfly2-6mm-vacuum" |
static const char *const | CONST_GENERIC_CAMERA_NAME = "Generic-camera" |
static const vpAfma6ToolType | defaultTool = TOOL_CCMOP |
static const unsigned int | njoint = 6 |
Protected Member Functions | |
void | setToolType (vpAfma6::vpAfma6ToolType tool) |
Protected Attributes | |
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 |
Friends | |
VISP_EXPORT std::ostream & | operator<< (std::ostream &os, const vpAfma6 &afma6) |
Modelisation of Irisa's gantry robot named Afma6.
vpAfma6::vpAfma6 | ( | ) |
Default constructor.
Definition at line 156 of file vpAfma6.cpp.
References _coupl_56, _eMc, _joint_max, _joint_min, _long_56, init(), and vpHomogeneousMatrix::setIdentity().
|
inlinevirtual |
void vpAfma6::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 861 of file vpAfma6.cpp.
References _eMc, and vpHomogeneousMatrix::inverse().
Referenced by vpSimulatorAfma6::get_cMe(), vpRobotAfma6::get_cMe(), get_cVe(), vpSimulatorAfma6::get_cVe(), and vpRobotAfma6::get_cVe().
void vpAfma6::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 876 of file vpAfma6.cpp.
References vpVelocityTwistMatrix::buildFrom(), and get_cMe().
void vpAfma6::get_eJe | ( | const vpColVector & | q, |
vpMatrix & | eJe | ||
) | const |
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 succesives rotations expressed in radians. |
eJe | : Robot jacobian expressed in the end-effector frame. |
Definition at line 899 of file vpAfma6.cpp.
References _coupl_56, _long_56, and vpMatrix::resize().
Referenced by vpSimulatorAfma6::computeArticularVelocity(), vpSimulatorAfma6::get_eJe(), vpRobotAfma6::get_eJe(), and vpSimulatorAfma6::getVelocity().
void vpAfma6::get_fJe | ( | const vpColVector & | q, |
vpMatrix & | fJe | ||
) | const |
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 succesives rotations expressed in radians. |
fJe | : Robot jacobian expressed in the robot reference frame. |
Definition at line 968 of file vpAfma6.cpp.
References _coupl_56, _long_56, and vpMatrix::resize().
Referenced by vpSimulatorAfma6::computeArticularVelocity(), vpSimulatorAfma6::get_fJe(), vpRobotAfma6::get_fJe(), and vpSimulatorAfma6::getVelocity().
vpHomogeneousMatrix vpAfma6::get_fMc | ( | const vpColVector & | q | ) | const |
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 succesives rotations expressed in radians. |
Definition at line 745 of file vpAfma6.cpp.
Referenced by vpSimulatorAfma6::compute_fMi(), vpRobotAfma6::getDisplacement(), getForwardKinematics(), vpSimulatorAfma6::getPosition(), vpRobotAfma6::getPosition(), vpRobotAfma6::getVelocity(), vpSimulatorAfma6::setPosition(), and vpRobotAfma6::setPosition().
void vpAfma6::get_fMc | ( | const vpColVector & | q, |
vpHomogeneousMatrix & | fMc | ||
) | const |
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 succesives 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 773 of file vpAfma6.cpp.
void vpAfma6::get_fMe | ( | const vpColVector & | q, |
vpHomogeneousMatrix & | fMe | ||
) | const |
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 succesives 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 807 of file vpAfma6.cpp.
References _coupl_56, and _long_56.
Referenced by get_fMc().
void vpAfma6::getCameraParameters | ( | vpCameraParameters & | cam, |
const unsigned int & | image_width, | ||
const unsigned int & | image_height | ||
) | const |
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 1248 of file vpAfma6.cpp.
References CONST_CAMERA_AFMA6_FILENAME, CONST_CCMOP_CAMERA_NAME, CONST_GENERIC_CAMERA_NAME, CONST_GRIPPER_CAMERA_NAME, CONST_VACUUM_CAMERA_NAME, getToolType(), vpCameraParameters::initPersProjWithDistortion(), vpCameraParameters::initPersProjWithoutDistortion(), vpXmlParserCamera::parse(), vpCameraParameters::perspectiveProjWithDistortion, vpCameraParameters::perspectiveProjWithoutDistortion, projModel, vpRobotException::readingParametersError, vpXmlParserCamera::SEQUENCE_OK, TOOL_CCMOP, TOOL_GENERIC_CAMERA, TOOL_GRIPPER, TOOL_VACUUM, vpERROR_TRACE, and vpTRACE.
Referenced by getCameraParameters().
void vpAfma6::getCameraParameters | ( | vpCameraParameters & | cam, |
const vpImage< unsigned char > & | I | ||
) | const |
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 1467 of file vpAfma6.cpp.
References getCameraParameters(), vpImage< Type >::getHeight(), and vpImage< Type >::getWidth().
void vpAfma6::getCameraParameters | ( | vpCameraParameters & | cam, |
const vpImage< vpRGBa > & | I | ||
) | const |
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 1516 of file vpAfma6.cpp.
References getCameraParameters(), vpImage< Type >::getHeight(), and vpImage< Type >::getWidth().
|
inline |
double vpAfma6::getCoupl56 | ( | ) | const |
Return the coupling factor between join 5 and 6.
Definition at line 1042 of file vpAfma6.cpp.
References _coupl_56.
vpHomogeneousMatrix vpAfma6::getForwardKinematics | ( | const vpColVector & | q | ) | const |
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 succesives rotations expressed in radians. |
Definition at line 482 of file vpAfma6.cpp.
References get_fMc().
int vpAfma6::getInverseKinematics | ( | const vpHomogeneousMatrix & | fMc, |
vpColVector & | q, | ||
const bool & | nearest = true , |
||
const bool & | verbose = false |
||
) | const |
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 succesives 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 564 of file vpAfma6.cpp.
References _coupl_56, _eMc, _joint_max, _joint_min, _long_56, vpMath::deg(), vpMatrix::getRows(), vpHomogeneousMatrix::inverse(), njoint, vpMath::rad(), vpColVector::resize(), and vpTRACE.
Referenced by vpSimulatorAfma6::initialiseCameraRelativeToObject(), vpSimulatorAfma6::setPosition(), and vpRobotAfma6::setPosition().
vpColVector vpAfma6::getJointMax | ( | ) | const |
Get max joint values.
Definition at line 1027 of file vpAfma6.cpp.
References _joint_max.
vpColVector vpAfma6::getJointMin | ( | ) | const |
Get min joint values.
Definition at line 1010 of file vpAfma6.cpp.
References _joint_min.
double vpAfma6::getLong56 | ( | ) | const |
Return the distance between join 5 and 6.
Definition at line 1054 of file vpAfma6.cpp.
References _long_56.
|
inline |
Get the current tool type.
Definition at line 150 of file vpAfma6.h.
Referenced by getCameraParameters(), vpSimulatorAfma6::getCameraParameters(), and vpSimulatorAfma6::initArms().
void vpAfma6::init | ( | void | ) |
Initialize the robot with the default tool vpAfma6::defaultTool.
Definition at line 199 of file vpAfma6.cpp.
References defaultTool.
Referenced by init(), vpRobotAfma6::init(), and vpAfma6().
void vpAfma6::init | ( | const char * | paramAfma6, |
const char * | paramCamera | ||
) |
Read files containing the constant parameters related to the robot kinematics and to the end-effector to camera transformation.
paramAfma6 | : Filename containing the constant parameters of the robot kinematics. |
paramCamera | : Filename containing the camera extrinsic parameters. |
Definition at line 221 of file vpAfma6.cpp.
References parseConfigFile().
void vpAfma6::init | ( | vpAfma6::vpAfma6ToolType | tool, |
vpCameraParameters::vpCameraParametersProjType | proj_model = vpCameraParameters::perspectiveProjWithoutDistortion |
||
) |
Get the constant parameters related to the robot kinematics and to the end-effector to camera transformation (eMc) corresponding to the camera extrinsic parameters. These last parameters depend on the camera and projection model in use.
tool | : Camera in use. |
proj_model | : Projection model of the camera. |
Definition at line 247 of file vpAfma6.cpp.
References _eMc, _erc, _etc, vpHomogeneousMatrix::buildFrom(), CONST_AFMA6_FILENAME, CONST_EMC_CCMOP_WITH_DISTORTION_FILENAME, CONST_EMC_CCMOP_WITHOUT_DISTORTION_FILENAME, CONST_EMC_GENERIC_WITH_DISTORTION_FILENAME, CONST_EMC_GENERIC_WITHOUT_DISTORTION_FILENAME, CONST_EMC_GRIPPER_WITH_DISTORTION_FILENAME, CONST_EMC_GRIPPER_WITHOUT_DISTORTION_FILENAME, CONST_EMC_VACUUM_WITH_DISTORTION_FILENAME, CONST_EMC_VACUUM_WITHOUT_DISTORTION_FILENAME, init(), vpCameraParameters::perspectiveProjWithDistortion, vpCameraParameters::perspectiveProjWithoutDistortion, projModel, vpMath::rad(), setToolType(), TOOL_CCMOP, TOOL_GENERIC_CAMERA, TOOL_GRIPPER, TOOL_VACUUM, and vpERROR_TRACE.
void vpAfma6::parseConfigFile | ( | const char * | filename | ) |
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 homogenous matrix. |
Definition at line 1074 of file vpAfma6.cpp.
References _coupl_56, _eMc, _erc, _etc, _joint_max, _joint_min, _long_56, vpHomogeneousMatrix::buildFrom(), vpRobotException::readingParametersError, and vpERROR_TRACE.
Referenced by init().
|
inlineprotected |
Set the current tool type.
Definition at line 174 of file vpAfma6.h.
Referenced by init(), vpSimulatorAfma6::init(), and vpRobotAfma6::init().
|
friend |
Print on the output stream os the robot parameters (joint min/max, distance between axis 5 and 6, coupling factor between axis 5 and 6, hand-to-eye homogeneous matrix.
os | : Output stream. |
afma6 | : Robot parameters. |
Definition at line 1532 of file vpAfma6.cpp.
|
protected |
Definition at line 184 of file vpAfma6.h.
Referenced by get_eJe(), get_fJe(), get_fMe(), getCoupl56(), getInverseKinematics(), vpRobotAfma6::init(), parseConfigFile(), and vpAfma6().
|
protected |
Definition at line 192 of file vpAfma6.h.
Referenced by vpSimulatorAfma6::computeArticularVelocity(), get_cMe(), get_fMc(), getInverseKinematics(), vpSimulatorAfma6::getVelocity(), init(), vpSimulatorAfma6::init(), parseConfigFile(), and vpAfma6().
|
protected |
Definition at line 190 of file vpAfma6.h.
Referenced by init(), vpSimulatorAfma6::init(), vpRobotAfma6::init(), and parseConfigFile().
|
protected |
Definition at line 189 of file vpAfma6.h.
Referenced by init(), vpSimulatorAfma6::init(), vpRobotAfma6::init(), and parseConfigFile().
|
protected |
Definition at line 186 of file vpAfma6.h.
Referenced by getInverseKinematics(), getJointMax(), vpSimulatorAfma6::init(), vpRobotAfma6::init(), vpSimulatorAfma6::isInJointLimit(), parseConfigFile(), vpSimulatorAfma6::setJointLimit(), vpSimulatorAfma6::updateArticularPosition(), and vpAfma6().
|
protected |
Definition at line 187 of file vpAfma6.h.
Referenced by getInverseKinematics(), getJointMin(), vpSimulatorAfma6::init(), vpRobotAfma6::init(), vpSimulatorAfma6::isInJointLimit(), parseConfigFile(), vpSimulatorAfma6::setJointLimit(), vpSimulatorAfma6::updateArticularPosition(), and vpAfma6().
|
protected |
Definition at line 185 of file vpAfma6.h.
Referenced by vpSimulatorAfma6::compute_fMi(), get_eJe(), get_fJe(), get_fMe(), getInverseKinematics(), getLong56(), vpRobotAfma6::init(), parseConfigFile(), and vpAfma6().
|
static |
|
static |
Definition at line 85 of file vpAfma6.h.
Referenced by getCameraParameters().
|
static |
Name of the camera attached to the CCMOP tool (vpAfma6ToolType::TOOL_CCMOP).
Definition at line 90 of file vpAfma6.h.
Referenced by getCameraParameters(), and vpSimulatorAfma6::getCameraParameters().
|
static |
|
static |
|
static |
|
static |
|
static |
|
static |
|
static |
|
static |
|
static |
Name of the generic camera attached to the robot hand (vpAfma6ToolType::TOOL_GENERIC_CAMERA).
Definition at line 105 of file vpAfma6.h.
Referenced by getCameraParameters().
|
static |
Name of the camera attached to the 2 fingers gripper tool (vpAfma6ToolType::TOOL_GRIPPER).
Definition at line 95 of file vpAfma6.h.
Referenced by getCameraParameters(), and vpSimulatorAfma6::getCameraParameters().
|
static |
Name of the camera attached to the vacuum gripper tool (vpAfma6ToolType::TOOL_VACUUM).
Definition at line 100 of file vpAfma6.h.
Referenced by getCameraParameters().
|
static |
Default tool attached to the robot end effector.
Definition at line 117 of file vpAfma6.h.
Referenced by init(), and vpRobotAfma6::init().
|
static |
Number of joint.
Definition at line 176 of file vpAfma6.h.
Referenced by vpRobotAfma6::checkJointLimits(), vpRobotAfma6::get_eJe(), vpRobotAfma6::get_fJe(), vpRobotAfma6::getDisplacement(), getInverseKinematics(), vpRobotAfma6::getPosition(), vpRobotAfma6::getVelocity(), vpSimulatorAfma6::init(), vpSimulatorAfma6::readPosFile(), vpRobotAfma6::readPosFile(), vpRobotAfma6::setPosition(), and vpRobotAfma6::setVelocity().
|
protected |
Definition at line 198 of file vpAfma6.h.
Referenced by getCameraParameters(), init(), and vpSimulatorAfma6::init().
|
protected |