Visual Servoing Platform
version 3.6.1 under development (2024-12-04)
|
#include <visp3/robot/vpAfma6.h>
Public Types | |
enum | vpAfma6ToolType { TOOL_CCMOP , TOOL_GRIPPER , TOOL_VACUUM , TOOL_GENERIC_CAMERA , TOOL_INTEL_D435_CAMERA , TOOL_CUSTOM } |
Public Member Functions | |
vpAfma6 () | |
virtual | ~vpAfma6 () |
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) |
Inherited functionalities from vpAfma6 | |
void | init (void) |
void | init (const std::string &camera_extrinsic_parameters) |
void | init (const std::string &camera_extrinsic_parameters, const std::string &camera_intrinsic_parameters) |
void | init (vpAfma6::vpAfma6ToolType tool, const std::string &filename) |
void | init (vpAfma6::vpAfma6ToolType tool, const vpHomogeneousMatrix &eMc_) |
void | init (vpAfma6::vpAfma6ToolType tool, vpCameraParameters::vpCameraParametersProjType projModel=vpCameraParameters::perspectiveProjWithoutDistortion) |
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_fMe (const vpColVector &q, vpHomogeneousMatrix &fMe) const |
void | get_fMc (const vpColVector &q, vpHomogeneousMatrix &fMc) const |
void | get_cMe (vpHomogeneousMatrix &cMe) const |
void | get_cVe (vpVelocityTwistMatrix &cVe) 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) |
virtual void | set_eMc (const vpHomogeneousMatrix &eMc) |
VISP_EXPORT std::ostream & | operator<< (std::ostream &os, const vpAfma6 &afma6) |
Modelization of Irisa's gantry robot named Afma6.
In this modelization, different frames have to be considered.
List of possible tools that can be attached to the robot end-effector.
vpAfma6::vpAfma6 | ( | ) |
Default constructor.
Definition at line 119 of file vpAfma6.cpp.
References _coupl_56, _eMc, _joint_max, _joint_min, _long_56, vpHomogeneousMatrix::eye(), and init().
|
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 897 of file vpAfma6.cpp.
References _eMc, and vpHomogeneousMatrix::inverse().
Referenced by vpRobotAfma6::get_cMe(), vpRobotAfma6::get_cVe(), and 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 919 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 successives rotations expressed in radians. |
eJe | : Robot jacobian expressed in the end-effector frame. |
Definition at line 941 of file vpAfma6.cpp.
References _coupl_56, _long_56, and vpArray2D< Type >::resize().
Referenced by vpRobotAfma6::get_eJe().
vpHomogeneousMatrix vpAfma6::get_eMc | ( | ) | const |
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 _eMc.
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 successives rotations expressed in radians. |
fJe | : Robot jacobian expressed in the robot reference frame. |
Definition at line 1011 of file vpAfma6.cpp.
References _coupl_56, _long_56, and vpArray2D< Type >::resize().
Referenced by vpRobotAfma6::get_fJe().
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 successives rotations expressed in radians. |
Definition at line 784 of file vpAfma6.cpp.
Referenced by vpRobotAfma6::getDisplacement(), getForwardKinematics(), vpRobotAfma6::getPosition(), vpRobotAfma6::getVelocity(), 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 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.
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 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 _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 1269 of file vpAfma6.cpp.
References CONST_CAMERA_AFMA6_FILENAME, CONST_CCMOP_CAMERA_NAME, CONST_GENERIC_CAMERA_NAME, CONST_GRIPPER_CAMERA_NAME, CONST_INTEL_D435_CAMERA_NAME, CONST_VACUUM_CAMERA_NAME, getToolType(), vpCameraParameters::initPersProjWithDistortion(), vpCameraParameters::initPersProjWithoutDistortion(), vpException::notImplementedError, vpXmlParserCamera::parse(), vpCameraParameters::perspectiveProjWithDistortion, vpCameraParameters::perspectiveProjWithoutDistortion, projModel, vpCameraParameters::ProjWithKannalaBrandtDistortion, vpRobotException::readingParametersError, vpXmlParserCamera::SEQUENCE_OK, TOOL_CCMOP, TOOL_GENERIC_CAMERA, TOOL_GRIPPER, TOOL_INTEL_D435_CAMERA, and TOOL_VACUUM.
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 1515 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 1566 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 1082 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 successives rotations expressed in radians. |
Definition at line 519 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 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 _coupl_56, _eMc, _joint_max, _joint_min, _long_56, vpMath::deg(), vpArray2D< Type >::getRows(), vpHomogeneousMatrix::inverse(), njoint, vpMath::rad(), and vpColVector::resize().
Referenced by vpRobotAfma6::setPosition().
vpColVector vpAfma6::getJointMax | ( | ) | const |
Get max joint values.
Definition at line 1068 of file vpAfma6.cpp.
References _joint_max.
vpColVector vpAfma6::getJointMin | ( | ) | const |
Get min joint values.
Definition at line 1052 of file vpAfma6.cpp.
References _joint_min.
double vpAfma6::getLong56 | ( | ) | const |
Return the distance between join 5 and 6.
Definition at line 1090 of file vpAfma6.cpp.
References _long_56.
|
inline |
Get the current tool type.
Definition at line 169 of file vpAfma6.h.
Referenced by getCameraParameters().
void vpAfma6::init | ( | const std::string & | camera_extrinsic_parameters | ) |
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 parseConfigFile().
void vpAfma6::init | ( | const std::string & | camera_extrinsic_parameters, |
const std::string & | camera_intrinsic_parameters | ||
) |
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 parseConfigFile().
void vpAfma6::init | ( | void | ) |
Initialize the robot with the default tool vpAfma6::defaultTool.
Definition at line 157 of file vpAfma6.cpp.
References defaultTool.
Referenced by init(), vpRobotAfma6::init(), and vpAfma6().
void vpAfma6::init | ( | vpAfma6::vpAfma6ToolType | tool, |
const std::string & | filename | ||
) |
Set the type of tool attached to the robot and transformation between the end-effector and the tool ( ). This last parameter is loaded from a file.
tool | : Type of tool in use. |
filename | : Path of the configuration file containing the transformation between the end-effector frame and the tool frame. |
The configuration file should have the form below:
Definition at line 212 of file vpAfma6.cpp.
References parseConfigFile(), and setToolType().
void vpAfma6::init | ( | vpAfma6::vpAfma6ToolType | tool, |
const vpHomogeneousMatrix & | eMc | ||
) |
Set the type of tool attached to the robot and the transformation between the end-effector and the tool ( ).
tool | : Type of tool in use. |
eMc | : Homogeneous matrix representation of the transformation between the end-effector frame and the tool frame. |
Definition at line 247 of file vpAfma6.cpp.
References set_eMc(), and setToolType().
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 270 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_INTEL_D435_WITH_DISTORTION_FILENAME, CONST_EMC_INTEL_D435_WITHOUT_DISTORTION_FILENAME, CONST_EMC_VACUUM_WITH_DISTORTION_FILENAME, CONST_EMC_VACUUM_WITHOUT_DISTORTION_FILENAME, init(), vpException::notImplementedError, vpCameraParameters::perspectiveProjWithDistortion, vpCameraParameters::perspectiveProjWithoutDistortion, projModel, vpCameraParameters::ProjWithKannalaBrandtDistortion, vpMath::rad(), setToolType(), TOOL_CCMOP, TOOL_CUSTOM, TOOL_GENERIC_CAMERA, TOOL_GRIPPER, TOOL_INTEL_D435_CAMERA, and TOOL_VACUUM.
void vpAfma6::parseConfigFile | ( | const std::string & | 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 homogeneous matrix. |
Definition at line 1102 of file vpAfma6.cpp.
References _coupl_56, _eMc, _erc, _etc, _joint_max, _joint_min, _long_56, vpHomogeneousMatrix::buildFrom(), and vpRobotException::readingParametersError.
Referenced by init().
|
virtual |
Set the geometric transformation between the end-effector frame and the tool frame (commonly a camera).
eMc | : Transformation between the end-effector frame and the tool frame. |
Reimplemented in vpRobotAfma6.
Definition at line 1196 of file vpAfma6.cpp.
References _eMc, _erc, _etc, vpRxyzVector::buildFrom(), and vpHomogeneousMatrix::getTranslationVector().
Referenced by init(), and vpRobotAfma6::set_eMc().
|
inlineprotected |
Set the current tool type.
Definition at line 194 of file vpAfma6.h.
Referenced by 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 1580 of file vpAfma6.cpp.
|
protected |
Definition at line 201 of file vpAfma6.h.
Referenced by get_eJe(), get_fJe(), get_fMe(), getCoupl56(), getInverseKinematics(), vpRobotAfma6::init(), parseConfigFile(), and vpAfma6().
|
protected |
Definition at line 209 of file vpAfma6.h.
Referenced by get_cMe(), get_eMc(), get_fMc(), getInverseKinematics(), init(), parseConfigFile(), set_eMc(), and vpAfma6().
|
protected |
Definition at line 207 of file vpAfma6.h.
Referenced by init(), vpRobotAfma6::init(), parseConfigFile(), set_eMc(), and vpRobotAfma6::set_eMc().
|
protected |
Definition at line 206 of file vpAfma6.h.
Referenced by init(), vpRobotAfma6::init(), parseConfigFile(), set_eMc(), and vpRobotAfma6::set_eMc().
|
protected |
Definition at line 203 of file vpAfma6.h.
Referenced by getInverseKinematics(), getJointMax(), vpRobotAfma6::init(), parseConfigFile(), and vpAfma6().
|
protected |
Definition at line 204 of file vpAfma6.h.
Referenced by getInverseKinematics(), getJointMin(), vpRobotAfma6::init(), parseConfigFile(), and vpAfma6().
|
protected |
Definition at line 202 of file vpAfma6.h.
Referenced by get_eJe(), get_fJe(), get_fMe(), getInverseKinematics(), getLong56(), vpRobotAfma6::init(), parseConfigFile(), and vpAfma6().
|
static |
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 init().
|
static |
Definition at line 95 of file vpAfma6.h.
Referenced by getCameraParameters().
|
static |
Name of the camera attached to the CCMOP tool (vpAfma6ToolType::TOOL_CCMOP).
Definition at line 101 of file vpAfma6.h.
Referenced by getCameraParameters().
|
static |
|
static |
|
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 116 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 106 of file vpAfma6.h.
Referenced by getCameraParameters().
|
static |
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 getCameraParameters().
|
static |
Name of the camera attached to the vacuum gripper tool (vpAfma6ToolType::TOOL_VACUUM).
Definition at line 111 of file vpAfma6.h.
Referenced by getCameraParameters().
|
static |
Default tool attached to the robot end effector.
Definition at line 136 of file vpAfma6.h.
Referenced by init(), and vpRobotAfma6::init().
|
static |
Number of joint.
Definition at line 198 of file vpAfma6.h.
Referenced by vpRobotAfma6::checkJointLimits(), vpRobotAfma6::get_eJe(), vpRobotAfma6::get_fJe(), vpRobotAfma6::getDisplacement(), getInverseKinematics(), vpRobotAfma6::getPosition(), vpRobotAfma6::getVelocity(), vpRobotAfma6::readPosFile(), vpRobotAfma6::setPosition(), and vpRobotAfma6::setVelocity().
|
protected |
Definition at line 215 of file vpAfma6.h.
Referenced by getCameraParameters(), init(), and vpRobotAfma6::init().
|
protected |