Visual Servoing Platform  version 3.5.1 under development (2023-09-22)

#include <visp3/robot/vpAfma6.h>

+ Inheritance diagram for vpAfma6:

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 ()
 

Static Public Attributes

static const std::string CONST_AFMA6_FILENAME
 
static const std::string CONST_EMC_CCMOP_WITHOUT_DISTORTION_FILENAME
 
static const std::string CONST_EMC_CCMOP_WITH_DISTORTION_FILENAME
 
static const std::string CONST_EMC_GRIPPER_WITHOUT_DISTORTION_FILENAME
 
static const std::string CONST_EMC_GRIPPER_WITH_DISTORTION_FILENAME
 
static const std::string CONST_EMC_VACUUM_WITHOUT_DISTORTION_FILENAME
 
static const std::string CONST_EMC_VACUUM_WITH_DISTORTION_FILENAME
 
static const std::string CONST_EMC_INTEL_D435_WITHOUT_DISTORTION_FILENAME
 
static const std::string CONST_EMC_INTEL_D435_WITH_DISTORTION_FILENAME
 
static const std::string CONST_EMC_GENERIC_WITHOUT_DISTORTION_FILENAME
 
static const std::string CONST_EMC_GENERIC_WITH_DISTORTION_FILENAME
 
static const std::string CONST_CAMERA_AFMA6_FILENAME
 
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 char *const CONST_INTEL_D435_CAMERA_NAME = "Intel-D435"
 
static const vpAfma6ToolType defaultTool = TOOL_CCMOP
 

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)
 

Detailed Description

Modelisation of Irisa's gantry robot named Afma6.

In this modelization, different frames have to be considered.

  • $ {\cal F}_f $: the reference frame, also called world frame
  • $ {\cal F}_e $: the end-effector frame located at the intersection of the 3 rotations.
  • $ {\cal F}_c $: the camera or tool frame, with $^f{\bf M}_c = ^f{\bf M}_e \; ^e{\bf M}_c $ where $ ^e{\bf M}_c $ is the result of a calibration stage. We can also consider a custom tool TOOL_CUSTOM and set this tool during robot initialisation or using set_eMc().
Examples
testAfma6.cpp.

Definition at line 75 of file vpAfma6.h.

Member Enumeration Documentation

◆ vpAfma6ToolType

List of possible tools that can be attached to the robot end-effector.

Enumerator
TOOL_CCMOP 

Pneumatic CCMOP gripper.

TOOL_GRIPPER 

Pneumatic gripper with 2 fingers.

TOOL_VACUUM 

Pneumatic vaccum gripper.

TOOL_GENERIC_CAMERA 

A generic camera.

TOOL_INTEL_D435_CAMERA 

Intel D435 camera

TOOL_CUSTOM 

A user defined tool.

Definition at line 123 of file vpAfma6.h.

Constructor & Destructor Documentation

◆ vpAfma6()

vpAfma6::vpAfma6 ( )

Default constructor.

Definition at line 118 of file vpAfma6.cpp.

References _coupl_56, _eMc, _joint_max, _joint_min, _long_56, vpHomogeneousMatrix::eye(), and init().

◆ ~vpAfma6()

virtual vpAfma6::~vpAfma6 ( )
inlinevirtual

Destructor that does nothing.

Definition at line 138 of file vpAfma6.h.

Member Function Documentation

◆ get_cMe()

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.

Parameters
cMe: Transformation between the camera frame and the end-effector frame.

Definition at line 887 of file vpAfma6.cpp.

References _eMc, and vpHomogeneousMatrix::inverse().

Referenced by vpRobotAfma6::get_cMe(), vpSimulatorAfma6::get_cMe(), vpRobotAfma6::get_cVe(), vpSimulatorAfma6::get_cVe(), and get_cVe().

◆ 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.

Parameters
cVe: Twist transformation.

Definition at line 909 of file vpAfma6.cpp.

References vpVelocityTwistMatrix::buildFrom(), and get_cMe().

◆ get_eJe()

void vpAfma6::get_eJe ( const vpColVector q,
vpMatrix eJe 
) const

Get the robot jacobian expressed in the end-effector frame.

Parameters
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 931 of file vpAfma6.cpp.

References _coupl_56, _long_56, and vpArray2D< Type >::resize().

Referenced by vpSimulatorAfma6::computeArticularVelocity(), vpRobotAfma6::get_eJe(), vpSimulatorAfma6::get_eJe(), and vpSimulatorAfma6::getVelocity().

◆ get_eMc()

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.

Returns
Transformation between the end-effector frame and the camera frame.

Definition at line 898 of file vpAfma6.cpp.

References _eMc.

◆ get_fJe()

void vpAfma6::get_fJe ( const vpColVector q,
vpMatrix fJe 
) const

Get the robot jacobian expressed in the robot reference frame also called fix frame.

\[ {^f}J_e = \left(\begin{array}{cccccc} 1 & 0 & 0 & -Ls4 & 0 & 0 \\ 0 & 1 & 0 & Lc4 & 0 & 0 \\ 0 & 0 & 1 & 0 & 0 & 0 \\ 0 & 0 & 0 & 0 & c4+\gamma s4c5 & -s4c5 \\ 0 & 0 & 0 & 0 & s4-\gamma c4c5 & c4c5 \\ 0 & 0 & 0 & 1 & -gamma s5 & s5 \\ \end{array} \right) \]

where $\gamma$ is the coupling factor between join 5 and 6.

Parameters
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 1001 of file vpAfma6.cpp.

References _coupl_56, _long_56, and vpArray2D< Type >::resize().

Referenced by vpSimulatorAfma6::computeArticularVelocity(), vpRobotAfma6::get_fJe(), vpSimulatorAfma6::get_fJe(), and vpSimulatorAfma6::getVelocity().

◆ get_fMc() [1/2]

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).

Parameters
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.
Returns
The homogeneous matrix corresponding to the direct geometric model which expresses the transformation between the base frame and the camera frame (fMc).
See also
getForwardKinematics(const vpColVector & q)

Definition at line 774 of file vpAfma6.cpp.

Referenced by vpSimulatorAfma6::compute_fMi(), vpRobotAfma6::getDisplacement(), getForwardKinematics(), vpRobotAfma6::getPosition(), vpSimulatorAfma6::getPosition(), vpRobotAfma6::getVelocity(), vpRobotAfma6::setPosition(), and vpSimulatorAfma6::setPosition().

◆ get_fMc() [2/2]

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.

Parameters
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.
fMcThe homogeneous matrix corresponding to the direct geometric model which expresses the transformation between the fix frame and the camera frame (fMc).

Definition at line 801 of file vpAfma6.cpp.

References _eMc, and get_fMe().

◆ get_fMe()

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.

Parameters
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.
fMeThe 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 834 of file vpAfma6.cpp.

References _coupl_56, and _long_56.

Referenced by get_fMc().

◆ getCameraParameters() [1/3]

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.

Warning
This method needs XML library to parse the file defined in vpAfma6::CONST_CAMERA_AFMA6_FILENAME and containing the camera parameters.
Thid method needs also an access to the files containing the camera parameters in XML format. This access is available if VISP_HAVE_AFMA6_DATA macro is defined in include/visp3/core/vpConfig.h file.
  • If VISP_HAVE_AFMA6_DATA is defined, this method gets the camera parameters from const_camera_Afma6.xml config file.
  • If this macro is not defined, this method sets the camera parameters to default one.
Parameters
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.

#include <visp3/core/vpCameraParameters.h>
#include <visp3/core/vpImage.h>
#include <visp3/robot/vpRobotAfma6.h>
#include <visp3/sensor/vp1394TwoGrabber.h>
int main()
{
#if defined(VISP_HAVE_DC1394) && defined(VISP_HAVE_AFMA6)
// Acquire an image to update image structure
g.acquire(I) ;
vpRobotAfma6 robot;
// Get the intrinsic camera parameters depending on the image size
// Camera parameters are read from
// /udd/fspindle/robot/Afma6/current/include/const_camera_Afma6.xml
// if VISP_HAVE_AFMA6_DATA macro is defined in vpConfig.h file
try {
robot.getCameraParameters (cam, I.getWidth(), I.getHeight());
}
catch(...) {
std::cout << "Cannot get camera parameters for image: " << I.getWidth() << " x " << I.getHeight() << std::endl;
}
std::cout << "Camera parameters: " << cam << std::endl;
#endif
}
Class for firewire ieee1394 video devices using libdc1394-2.x api.
void acquire(vpImage< unsigned char > &I)
Generic class defining intrinsic camera parameters.
unsigned int getWidth() const
Definition: vpImage.h:242
unsigned int getHeight() const
Definition: vpImage.h:184
Control of Irisa's gantry robot named Afma6.
Definition: vpRobotAfma6.h:209
Exceptions
vpRobotException::readingParametersError: If the camera parameters are not found.
Examples
testAfma6.cpp, and testRobotAfma6.cpp.

Definition at line 1255 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, TOOL_VACUUM, vpERROR_TRACE, and vpTRACE.

Referenced by getCameraParameters().

◆ getCameraParameters() [2/3]

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

Parameters
cam: In output, camera parameters to fill.
I: A B&W image send by the current camera in use.
#include <visp3/core/vpCameraParameters.h>
#include <visp3/core/vpImage.h>
#include <visp3/robot/vpRobotAfma6.h>
#include <visp3/sensor/vp1394TwoGrabber.h>
int main()
{
#if defined(VISP_HAVE_DC1394) && defined(VISP_HAVE_AFMA6)
// Acquire an image to update image structure
g.acquire(I) ;
vpRobotAfma6 robot;
// Get the intrinsic camera parameters depending on the image size
try {
robot.getCameraParameters (cam, I);
}
catch(...) {
std::cout << "Cannot get camera parameters for image: " << I.getWidth() << " x " << I.getHeight() << std::endl;
}
std::cout << "Camera parameters: " << cam << std::endl;
#endif
}
Exceptions
vpRobotException::readingParametersError: If the camera parameters are not found.

Definition at line 1492 of file vpAfma6.cpp.

References getCameraParameters(), vpImage< Type >::getHeight(), and vpImage< Type >::getWidth().

◆ getCameraParameters() [3/3]

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

Parameters
cam: In output, camera parameters to fill.
I: A color image send by the current camera in use.
#include <visp3/core/vpCameraParameters.h>
#include <visp3/core/vpImage.h>
#include <visp3/robot/vpRobotAfma6.h>
#include <visp3/sensor/vp1394TwoGrabber.h>
int main()
{
#if defined(VISP_HAVE_DC1394) && defined(VISP_HAVE_AFMA6)
// Acquire an image to update image structure
g.acquire(I) ;
vpRobotAfma6 robot;
// Get the intrinsic camera parameters depending on the image size
try {
robot.getCameraParameters (cam, I);
}
catch(...) {
std::cout << "Cannot get camera parameters for image: " << I.getWidth() << " x " << I.getHeight() << std::endl;
}
std::cout << "Camera parameters: " << cam << std::endl;
#endif
}
Exceptions
vpRobotException::readingParametersError: If the camera parameters are not found.

Definition at line 1539 of file vpAfma6.cpp.

References getCameraParameters(), vpImage< Type >::getHeight(), and vpImage< Type >::getWidth().

◆ getCameraParametersProjType()

vpCameraParameters::vpCameraParametersProjType vpAfma6::getCameraParametersProjType ( ) const
inline

Get the current camera model projection type.

Definition at line 168 of file vpAfma6.h.

◆ getCoupl56()

double vpAfma6::getCoupl56 ( ) const

Return the coupling factor between join 5 and 6.

Returns
Coupling factor between join 5 and 6.

Definition at line 1072 of file vpAfma6.cpp.

References _coupl_56.

◆ getForwardKinematics()

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).

Parameters
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.
Returns
The homogeneous matrix corresponding to the direct geometric model which expresses the transformation between the base frame and the camera frame (fMc).
See also
get_fMc(const vpColVector & q)
getInverseKinematics()

Definition at line 519 of file vpAfma6.cpp.

References get_fMc().

◆ getInverseKinematics()

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.

Parameters
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.
Returns
The number of solutions (1 or 2) of the inverse geometric model. O, if no solution can be found.

The code below shows how to compute the inverse geometric model:

#include <visp3/core/vpColVector.h>
#include <visp3/core/vpHomogeneousMatrix.h>
#include <visp3/robot/vpRobotAfma6.h>
int main()
{
#ifdef VISP_HAVE_AFMA6
vpColVector q1(6), q2(6);
vpRobotAfma6 robot;
// Get the current articular position of the robot
robot.getPosition(vpRobot::ARTICULAR_FRAME, q1);
// Compute the pose of the camera in the reference frame using the
// direct geometric model
fMc = robot.getForwardKinematics(q1);
// this is similar to fMc = robot.get_fMc(q1);
// or robot.get_fMc(q1, fMc);
// Compute the inverse geometric model
int nbsol; // number of solutions (0, 1 or 2) of the inverse geometric model
// get the nearest solution to the current articular position
nbsol = robot.getInverseKinematics(fMc, q1, true);
if (nbsol == 0)
std::cout << "No solution of the inverse geometric model " << std::endl;
else if (nbsol >= 1)
std::cout << "First solution: " << q1 << std::endl;
if (nbsol == 2) {
// Compute the other solution of the inverse geometric model
q2 = q1;
robot.getInverseKinematics(fMc, q2, false);
std::cout << "Second solution: " << q2 << std::endl;
}
#endif
}
Implementation of column vector and the associated operations.
Definition: vpColVector.h:167
Implementation of an homogeneous matrix and operations on such kind of matrices.
@ ARTICULAR_FRAME
Definition: vpRobot.h:76
See also
getForwardKinematics()

Definition at line 599 of file vpAfma6.cpp.

References _coupl_56, _eMc, _joint_max, _joint_min, _long_56, vpMath::deg(), vpArray2D< Type >::getRows(), vpHomogeneousMatrix::inverse(), njoint, vpMath::rad(), vpColVector::resize(), and vpTRACE.

Referenced by vpSimulatorAfma6::initialiseCameraRelativeToObject(), vpRobotAfma6::setPosition(), and vpSimulatorAfma6::setPosition().

◆ getJointMax()

vpColVector vpAfma6::getJointMax ( ) const

Get max joint values.

Returns
Maximal joint values for the 6 dof X,Y,Z,A,B,C. Translation X,Y,Z are expressed in meters. Rotation A,B,C in radians.

Definition at line 1058 of file vpAfma6.cpp.

References _joint_max.

◆ getJointMin()

vpColVector vpAfma6::getJointMin ( ) const

Get min joint values.

Returns
Minimal joint values for the 6 dof X,Y,Z,A,B,C. Translation X,Y,Z are expressed in meters. Rotation A,B,C in radians.

Definition at line 1042 of file vpAfma6.cpp.

References _joint_min.

◆ getLong56()

double vpAfma6::getLong56 ( ) const

Return the distance between join 5 and 6.

Returns
Distance between join 5 and 6.

Definition at line 1080 of file vpAfma6.cpp.

References _long_56.

◆ getToolType()

vpAfma6ToolType vpAfma6::getToolType ( ) const
inline

Get the current tool type.

Definition at line 166 of file vpAfma6.h.

Referenced by vpSimulatorAfma6::getCameraParameters(), getCameraParameters(), and vpSimulatorAfma6::initArms().

◆ init() [1/6]

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.

Parameters
camera_extrinsic_parameters: Filename containing the camera extrinsic parameters.

Definition at line 227 of file vpAfma6.cpp.

References parseConfigFile().

◆ init() [2/6]

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.

Parameters
camera_extrinsic_parameters: Filename containing the constant parameters of the robot kinematics $^e{\bf M}_c $ transformation.
camera_intrinsic_parameters: Filename containing the camera extrinsic parameters.

Definition at line 175 of file vpAfma6.cpp.

References parseConfigFile().

◆ init() [3/6]

void vpAfma6::init ( void  )

Initialize the robot with the default tool vpAfma6::defaultTool.

Examples
testAfma6.cpp.

Definition at line 157 of file vpAfma6.cpp.

References defaultTool.

Referenced by init(), vpRobotAfma6::init(), and vpAfma6().

◆ init() [4/6]

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 ( $^e{\bf M}c$). This last parameter is loaded from a file.

Parameters
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:

# Start with any number of consecutive lines
# beginning with the symbol '#'
#
# The 3 following lines contain the name of the camera,
# the rotation parameters of the geometric transformation
# using the Euler angles in degrees with convention XYZ and
# the translation parameters expressed in meters
CAMERA CameraName
eMc_ROT_XYZ 10.0 -90.0 20.0
eMc_TRANS_XYZ 0.05 0.01 0.06
See also
init(vpAfma6::vpToolType, vpCameraParameters::vpCameraParametersProjType), init(vpAfma6::vpToolType, const vpHomogeneousMatrix&)

Definition at line 212 of file vpAfma6.cpp.

References parseConfigFile(), and setToolType().

◆ init() [5/6]

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 ( $^e{\bf M}c$).

Parameters
tool: Type of tool in use.
eMc: Homogeneous matrix representation of the transformation between the end-effector frame and the tool frame.
See also
init(vpAfma6::vpAfma6ToolType, vpCameraParameters::vpCameraParametersProjType), init(vpAfma6::vpAfma6ToolType, const std::string&)

Definition at line 247 of file vpAfma6.cpp.

References set_eMc(), and setToolType().

◆ init() [6/6]

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.

Warning
If the macro VISP_HAVE_AFMA6_DATA is defined in vpConfig.h this function reads the camera extrinsic parameters from the file corresponding to the specified camera type and projection type. Otherwise corresponding default parameters are loaded.
Parameters
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, TOOL_VACUUM, and vpERROR_TRACE.

◆ parseConfigFile()

void vpAfma6::parseConfigFile ( const std::string &  filename)

This function gets the robot constant parameters from a file.

Parameters
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 1092 of file vpAfma6.cpp.

References _coupl_56, _eMc, _erc, _etc, _joint_max, _joint_min, _long_56, vpHomogeneousMatrix::buildFrom(), and vpRobotException::readingParametersError.

Referenced by init().

◆ set_eMc()

void vpAfma6::set_eMc ( const vpHomogeneousMatrix eMc)
virtual

Set the geometric transformation between the end-effector frame and the tool frame (commonly a camera).

Parameters
eMc: Transformation between the end-effector frame and the tool frame.

Reimplemented in vpRobotAfma6.

Definition at line 1186 of file vpAfma6.cpp.

References _eMc, _erc, _etc, vpRxyzVector::buildFrom(), and vpHomogeneousMatrix::getTranslationVector().

Referenced by init(), and vpRobotAfma6::set_eMc().

◆ setToolType()

void vpAfma6::setToolType ( vpAfma6::vpAfma6ToolType  tool)
inlineprotected

Set the current tool type.

Definition at line 191 of file vpAfma6.h.

Referenced by init(), vpRobotAfma6::init(), and vpSimulatorAfma6::init().

Friends And Related Function Documentation

◆ operator<<

VISP_EXPORT std::ostream& operator<< ( std::ostream &  os,
const vpAfma6 afma6 
)
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.

Parameters
os: Output stream.
afma6: Robot parameters.

Definition at line 1553 of file vpAfma6.cpp.

Member Data Documentation

◆ _coupl_56

double vpAfma6::_coupl_56
protected

◆ _eMc

◆ _erc

vpRxyzVector vpAfma6::_erc
protected

◆ _etc

◆ _joint_max

◆ _joint_min

◆ _long_56

double vpAfma6::_long_56
protected

◆ CONST_AFMA6_FILENAME

const std::string vpAfma6::CONST_AFMA6_FILENAME
static
Initial value:
=
std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_Afma6.cnf")

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, tranformation eMc between end-effector and camera frame.

Definition at line 82 of file vpAfma6.h.

Referenced by init().

◆ CONST_CAMERA_AFMA6_FILENAME

const std::string vpAfma6::CONST_CAMERA_AFMA6_FILENAME
static
Initial value:
=
std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_camera_Afma6.xml")

Definition at line 93 of file vpAfma6.h.

Referenced by getCameraParameters().

◆ CONST_CCMOP_CAMERA_NAME

const char *const vpAfma6::CONST_CCMOP_CAMERA_NAME = "Dragonfly2-8mm-ccmop"
static

Name of the camera attached to the CCMOP tool (vpAfma6ToolType::TOOL_CCMOP).

Definition at line 99 of file vpAfma6.h.

Referenced by vpSimulatorAfma6::getCameraParameters(), and getCameraParameters().

◆ CONST_EMC_CCMOP_WITH_DISTORTION_FILENAME

const std::string vpAfma6::CONST_EMC_CCMOP_WITH_DISTORTION_FILENAME
static
Initial value:
=
std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_eMc_ccmop_with_distortion_Afma6.cnf")

Definition at line 84 of file vpAfma6.h.

Referenced by init().

◆ CONST_EMC_CCMOP_WITHOUT_DISTORTION_FILENAME

const std::string vpAfma6::CONST_EMC_CCMOP_WITHOUT_DISTORTION_FILENAME
static
Initial value:
=
std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_eMc_ccmop_without_distortion_Afma6.cnf")

Definition at line 83 of file vpAfma6.h.

Referenced by init().

◆ CONST_EMC_GENERIC_WITH_DISTORTION_FILENAME

const std::string vpAfma6::CONST_EMC_GENERIC_WITH_DISTORTION_FILENAME
static
Initial value:
=
std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_eMc_generic_with_distortion_Afma6.cnf")

Definition at line 92 of file vpAfma6.h.

Referenced by init().

◆ CONST_EMC_GENERIC_WITHOUT_DISTORTION_FILENAME

const std::string vpAfma6::CONST_EMC_GENERIC_WITHOUT_DISTORTION_FILENAME
static
Initial value:
=
std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_eMc_generic_without_distortion_Afma6.cnf")

Definition at line 91 of file vpAfma6.h.

Referenced by init().

◆ CONST_EMC_GRIPPER_WITH_DISTORTION_FILENAME

const std::string vpAfma6::CONST_EMC_GRIPPER_WITH_DISTORTION_FILENAME
static
Initial value:
=
std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_eMc_gripper_with_distortion_Afma6.cnf")

Definition at line 86 of file vpAfma6.h.

Referenced by init().

◆ CONST_EMC_GRIPPER_WITHOUT_DISTORTION_FILENAME

const std::string vpAfma6::CONST_EMC_GRIPPER_WITHOUT_DISTORTION_FILENAME
static
Initial value:
=
std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_eMc_gripper_without_distortion_Afma6.cnf")

Definition at line 85 of file vpAfma6.h.

Referenced by init().

◆ CONST_EMC_INTEL_D435_WITH_DISTORTION_FILENAME

const std::string vpAfma6::CONST_EMC_INTEL_D435_WITH_DISTORTION_FILENAME
static
Initial value:
=
std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_eMc_Intel_D435_with_distortion_Afma6.cnf")

Definition at line 90 of file vpAfma6.h.

Referenced by init().

◆ CONST_EMC_INTEL_D435_WITHOUT_DISTORTION_FILENAME

const std::string vpAfma6::CONST_EMC_INTEL_D435_WITHOUT_DISTORTION_FILENAME
static
Initial value:
=
std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_eMc_Intel_D435_without_distortion_Afma6.cnf")

Definition at line 89 of file vpAfma6.h.

Referenced by init().

◆ CONST_EMC_VACUUM_WITH_DISTORTION_FILENAME

const std::string vpAfma6::CONST_EMC_VACUUM_WITH_DISTORTION_FILENAME
static
Initial value:
=
std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_eMc_vacuum_with_distortion_Afma6.cnf")

Definition at line 88 of file vpAfma6.h.

Referenced by init().

◆ CONST_EMC_VACUUM_WITHOUT_DISTORTION_FILENAME

const std::string vpAfma6::CONST_EMC_VACUUM_WITHOUT_DISTORTION_FILENAME
static
Initial value:
=
std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_eMc_vacuum_without_distortion_Afma6.cnf")

Definition at line 87 of file vpAfma6.h.

Referenced by init().

◆ CONST_GENERIC_CAMERA_NAME

const char *const vpAfma6::CONST_GENERIC_CAMERA_NAME = "Generic-camera"
static

Name of the generic camera attached to the robot hand (vpAfma6ToolType::TOOL_GENERIC_CAMERA).

Definition at line 114 of file vpAfma6.h.

Referenced by getCameraParameters().

◆ CONST_GRIPPER_CAMERA_NAME

const char *const vpAfma6::CONST_GRIPPER_CAMERA_NAME = "Dragonfly2-6mm-gripper"
static

Name of the camera attached to the 2 fingers gripper tool (vpAfma6ToolType::TOOL_GRIPPER).

Definition at line 104 of file vpAfma6.h.

Referenced by vpSimulatorAfma6::getCameraParameters(), and getCameraParameters().

◆ CONST_INTEL_D435_CAMERA_NAME

const char *const vpAfma6::CONST_INTEL_D435_CAMERA_NAME = "Intel-D435"
static

Name of the Intel D435 camera attached to the robot hand (vpAfma6ToolType::TOOL_INTEL_D435_CAMERA).

Definition at line 120 of file vpAfma6.h.

Referenced by getCameraParameters().

◆ CONST_VACUUM_CAMERA_NAME

const char *const vpAfma6::CONST_VACUUM_CAMERA_NAME = "Dragonfly2-6mm-vacuum"
static

Name of the camera attached to the vacuum gripper tool (vpAfma6ToolType::TOOL_VACUUM).

Definition at line 109 of file vpAfma6.h.

Referenced by getCameraParameters().

◆ defaultTool

const vpAfma6::vpAfma6ToolType vpAfma6::defaultTool = TOOL_CCMOP
static

Default tool attached to the robot end effector.

Definition at line 133 of file vpAfma6.h.

Referenced by init(), and vpRobotAfma6::init().

◆ njoint

◆ projModel

vpCameraParameters::vpCameraParametersProjType vpAfma6::projModel
protected

Definition at line 212 of file vpAfma6.h.

Referenced by getCameraParameters(), init(), vpRobotAfma6::init(), and vpSimulatorAfma6::init().

◆ tool_current

vpAfma6ToolType vpAfma6::tool_current
protected

Current tool in use.

Definition at line 210 of file vpAfma6.h.