ViSP  2.9.0

#include <vpAfma6.h>

+ Inheritance diagram for vpAfma6:

Public Types

enum  vpAfma6ToolType { TOOL_CCMOP, TOOL_GRIPPER, TOOL_VACUUM, TOOL_GENERIC_CAMERA }
 

Public Member Functions

 vpAfma6 ()
 
virtual ~vpAfma6 ()
 
void init (void)
 
void init (const char *paramAfma6, const char *paramCamera)
 
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_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
 
void parseConfigFile (const char *filename)
 
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
 

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)
 

Detailed Description

Modelisation of Irisa's gantry robot named Afma6.

Examples:
testAfma6.cpp.

Definition at line 69 of file vpAfma6.h.

Member Enumeration Documentation

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.

Definition at line 108 of file vpAfma6.h.

Constructor & Destructor Documentation

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

virtual vpAfma6::~vpAfma6 ( )
inlinevirtual

Destructor that does nothing.

Definition at line 122 of file vpAfma6.h.

Member Function Documentation

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

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

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

\[ {^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 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).

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 succesives 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)
Examples:
testRobotAfma6Pose.cpp.

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.

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 succesives 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 773 of file vpAfma6.cpp.

References _eMc, and 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 succesives 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 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.

Warning
This method needs XML library to parse the file defined in vpAfma6::CONST_CAMERA_AFMA6_FILENAME and containing the camera parameters. If XML is detected by ViSP, VISP_HAVE_XML2 macro is defined in include/visp/vpConfig.h file.
Thid method needs also an access to the file located on Inria's NAS server and containing the camera parameters in XML format. This access is available if VISP_HAVE_ACCESS_TO_NAS macro is defined in include/visp/vpConfig.h file.
  • If VISP_HAVE_ACCESS_TO_NAS and VISP_HAVE_XML2 macros are defined, this method gets the camera parameters from /udd/fspindle/robot/Afma6/current/include/const_camera_Afma6.xml config file.
  • If these two macros are not defined, this method set 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 <visp/vpImage.h>
#include <visp/vp1394TwoGrabber.h>
#include <visp/vpRobotAfma6.h>
#include <visp/vpCameraParameters.h>
int main()
{
#if defined(VISP_HAVE_DC1394_2) && 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_ACCESS_TO_NAS and VISP_HAVE_XML2 macros are 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
}
Exceptions
vpRobotException::readingParametersError: If the camera parameters are not found.
Examples:
servoAfma62DhalfCamVelocity.cpp, servoAfma6Cylinder2DCamVelocity.cpp, servoAfma6Cylinder2DCamVelocitySecondaryTask.cpp, servoAfma6Ellipse2DCamVelocity.cpp, servoAfma6FourPoints2DArtVelocity.cpp, servoAfma6FourPoints2DCamVelocityInteractionCurrent.cpp, servoAfma6FourPoints2DCamVelocityInteractionDesired.cpp, servoAfma6Line2DCamVelocity.cpp, servoAfma6Point2DArtVelocity.cpp, servoAfma6Point2DCamVelocity.cpp, servoAfma6Points2DCamVelocityEyeToHand.cpp, servoAfma6Segment2DCamVelocity.cpp, servoAfma6SquareLines2DCamVelocity.cpp, servoAfma6TwoLines2DCamVelocity.cpp, testAfma6.cpp, testRobotAfma6.cpp, and testRobotAfma6Pose.cpp.

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

Parameters
cam: In output, camera parameters to fill.
I: A B&W image send by the current camera in use.
#include <visp/vpImage.h>
#include <visp/vp1394TwoGrabber.h>
#include <visp/vpRobotAfma6.h>
#include <visp/vpCameraParameters.h>
int main()
{
#if defined(VISP_HAVE_DC1394_2) && 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 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

Parameters
cam: In output, camera parameters to fill.
I: A color image send by the current camera in use.
#include <visp/vpConfig.h>
#include <visp/vpImage.h>
#include <visp/vp1394TwoGrabber.h>
#include <visp/vpRobotAfma6.h>
#include <visp/vpCameraParameters.h>
int main()
{
#if defined(VISP_HAVE_DC1394_2) && 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 1516 of file vpAfma6.cpp.

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

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

Get the current camera model projection type.

Definition at line 154 of file vpAfma6.h.

double vpAfma6::getCoupl56 ( ) const

Return the coupling factor between join 5 and 6.

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

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

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 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.
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 <visp/vpConfig.h>
#include <visp/vpColVector.h>
#include <visp/vpHomogeneousMatrix.h>
#include <visp/vpRobotAfma6.h>
int main()
{
#ifdef VISP_HAVE_AFMA6
vpColVector q1(6), q2(6);
vpRobotAfma6 robot;
// Get the current articular position of the robot
// 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
}
See also
getForwardKinematics()

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.

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

References _joint_max.

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

References _joint_min.

double vpAfma6::getLong56 ( ) const

Return the distance between join 5 and 6.

Returns
Distance between join 5 and 6.

Definition at line 1054 of file vpAfma6.cpp.

References _long_56.

vpAfma6ToolType vpAfma6::getToolType ( ) const
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.

Examples:
testAfma6.cpp.

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.

Warning
This function is only available if the macro VISP_HAVE_ACCESS_TO_NAS is defined in vpConfig.h.
Parameters
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::parseConfigFile ( const char *  filename)

This function gets the robot constant parameters from a file.

Warning
This function is only available if the macro VISP_HAVE_ACCESS_TO_NAS is defined in vpConfig.h.
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 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().

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

Set the current tool type.

Definition at line 174 of file vpAfma6.h.

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

Friends And Related Function Documentation

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

Member Data Documentation

double vpAfma6::_coupl_56
protected
vpRxyzVector vpAfma6::_erc
protected

Definition at line 190 of file vpAfma6.h.

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

vpTranslationVector vpAfma6::_etc
protected

Definition at line 189 of file vpAfma6.h.

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

double vpAfma6::_long_56
protected
const char *const vpAfma6::CONST_AFMA6_FILENAME = "/udd/fspindle/robot/Afma6/current/include/const_Afma6.cnf"
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, tranformation eMc between end-effector and camera frame.

Definition at line 76 of file vpAfma6.h.

Referenced by init().

const char *const vpAfma6::CONST_CAMERA_AFMA6_FILENAME = "/udd/fspindle/robot/Afma6/current/include/const_camera_Afma6.xml"
static

Definition at line 85 of file vpAfma6.h.

Referenced by getCameraParameters().

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 90 of file vpAfma6.h.

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

const char *const vpAfma6::CONST_EMC_CCMOP_WITH_DISTORTION_FILENAME = "/udd/fspindle/robot/Afma6/current/include/const_eMc_ccmop_with_distortion_Afma6.cnf"
static

Definition at line 78 of file vpAfma6.h.

Referenced by init().

const char *const vpAfma6::CONST_EMC_CCMOP_WITHOUT_DISTORTION_FILENAME = "/udd/fspindle/robot/Afma6/current/include/const_eMc_ccmop_without_distortion_Afma6.cnf"
static

Definition at line 77 of file vpAfma6.h.

Referenced by init().

const char *const vpAfma6::CONST_EMC_GENERIC_WITH_DISTORTION_FILENAME = "/udd/fspindle/robot/Afma6/current/include/const_eMc_generic_with_distortion_Afma6.cnf"
static

Definition at line 84 of file vpAfma6.h.

Referenced by init().

const char *const vpAfma6::CONST_EMC_GENERIC_WITHOUT_DISTORTION_FILENAME = "/udd/fspindle/robot/Afma6/current/include/const_eMc_generic_without_distortion_Afma6.cnf"
static

Definition at line 83 of file vpAfma6.h.

Referenced by init().

const char *const vpAfma6::CONST_EMC_GRIPPER_WITH_DISTORTION_FILENAME = "/udd/fspindle/robot/Afma6/current/include/const_eMc_gripper_with_distortion_Afma6.cnf"
static

Definition at line 80 of file vpAfma6.h.

Referenced by init().

const char *const vpAfma6::CONST_EMC_GRIPPER_WITHOUT_DISTORTION_FILENAME = "/udd/fspindle/robot/Afma6/current/include/const_eMc_gripper_without_distortion_Afma6.cnf"
static

Definition at line 79 of file vpAfma6.h.

Referenced by init().

const char *const vpAfma6::CONST_EMC_VACUUM_WITH_DISTORTION_FILENAME = "/udd/fspindle/robot/Afma6/current/include/const_eMc_vacuum_with_distortion_Afma6.cnf"
static

Definition at line 82 of file vpAfma6.h.

Referenced by init().

const char *const vpAfma6::CONST_EMC_VACUUM_WITHOUT_DISTORTION_FILENAME = "/udd/fspindle/robot/Afma6/current/include/const_eMc_vacuum_without_distortion_Afma6.cnf"
static

Definition at line 81 of file vpAfma6.h.

Referenced by init().

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 105 of file vpAfma6.h.

Referenced by getCameraParameters().

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 95 of file vpAfma6.h.

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

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 100 of file vpAfma6.h.

Referenced by getCameraParameters().

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

Default tool attached to the robot end effector.

Definition at line 117 of file vpAfma6.h.

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

vpCameraParameters::vpCameraParametersProjType vpAfma6::projModel
protected

Definition at line 198 of file vpAfma6.h.

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

vpAfma6ToolType vpAfma6::tool_current
protected

Current tool in use.

Definition at line 196 of file vpAfma6.h.