Afma6

class Afma6(self)

Bases: pybind11_object

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

Default constructor.

Methods

__init__

Default constructor.

getCameraParameters

Overloaded function.

getCameraParametersProjType

Get the current camera model projection type.

getCoupl56

Return the coupling factor between join 5 and 6.

getForwardKinematics

Compute the forward kinematics (direct geometric model) as an homogeneous matrix.

getInverseKinematics

Compute the inverse kinematics (inverse geometric model).

getJointMax

Get max joint values.

getJointMin

Get min joint values.

getLong56

Return the distance between join 5 and 6.

getToolType

Get the current tool type.

get_cMe

Get the geometric transformation between the camera frame and the end-effector frame.

get_cVe

Get the twist transformation from camera frame to end-effector frame.

get_eJe

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

get_eMc

Get the geometric transformation between the end-effector frame and the camera or tool frame.

get_fJe

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

get_fMc

Overloaded function.

get_fMe

Compute the forward kinematics (direct geometric model) as an homogeneous matrix.

init

Overloaded function.

parseConfigFile

This function gets the robot constant parameters from a file.

set_eMc

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

Inherited Methods

Operators

__doc__

__init__

Default constructor.

__module__

__repr__

Attributes

CONST_AFMA6_FILENAME

CONST_CAMERA_AFMA6_FILENAME

CONST_CCMOP_CAMERA_NAME

CONST_EMC_CCMOP_WITHOUT_DISTORTION_FILENAME

CONST_EMC_CCMOP_WITH_DISTORTION_FILENAME

CONST_EMC_GENERIC_WITHOUT_DISTORTION_FILENAME

CONST_EMC_GENERIC_WITH_DISTORTION_FILENAME

CONST_EMC_GRIPPER_WITHOUT_DISTORTION_FILENAME

CONST_EMC_GRIPPER_WITH_DISTORTION_FILENAME

CONST_EMC_INTEL_D435_WITHOUT_DISTORTION_FILENAME

CONST_EMC_INTEL_D435_WITH_DISTORTION_FILENAME

CONST_EMC_VACUUM_WITHOUT_DISTORTION_FILENAME

CONST_EMC_VACUUM_WITH_DISTORTION_FILENAME

CONST_GENERIC_CAMERA_NAME

CONST_GRIPPER_CAMERA_NAME

CONST_INTEL_D435_CAMERA_NAME

CONST_VACUUM_CAMERA_NAME

TOOL_CCMOP

TOOL_CUSTOM

TOOL_GENERIC_CAMERA

TOOL_GRIPPER

TOOL_INTEL_D435_CAMERA

TOOL_VACUUM

__annotations__

defaultTool

njoint

class Afma6ToolType(self, value: int)

Bases: pybind11_object

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

Values:

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

__and__(self, other: object) object
__eq__(self, other: object) bool
__ge__(self, other: object) bool
__getstate__(self) int
__gt__(self, other: object) bool
__hash__(self) int
__index__(self) int
__init__(self, value: int)
__int__(self) int
__invert__(self) object
__le__(self, other: object) bool
__lt__(self, other: object) bool
__ne__(self, other: object) bool
__or__(self, other: object) object
__rand__(self, other: object) object
__ror__(self, other: object) object
__rxor__(self, other: object) object
__setstate__(self, state: int) None
__xor__(self, other: object) object
property name : str
__init__(self)

Default constructor.

getCameraParameters(*args, **kwargs)

Overloaded function.

  1. getCameraParameters(self: visp._visp.robot.Afma6, cam: visp._visp.core.CameraParameters, image_width: int, image_height: int) -> None

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.

Warning

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.

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)
  vpImage<unsigned char> I;
  vp1394TwoGrabber g;

  // Acquire an image to update image structure
  g.acquire(I) ;

  vpRobotAfma6 robot;
  vpCameraParameters cam ;
  // 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
}
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.

  1. getCameraParameters(self: visp._visp.robot.Afma6, cam: visp._visp.core.CameraParameters, I: visp._visp.core.ImageGray) -> None

Get the current intrinsic camera parameters obtained by calibration.

Camera parameters are read from /udd/fspindle/robot/Afma6/current/include/const_camera_Afma6.xml

#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)
  vpImage<unsigned char> I;
  vp1394TwoGrabber g;

  // Acquire an image to update image structure
  g.acquire(I) ;

  vpRobotAfma6 robot;
  vpCameraParameters cam ;
  // 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
}
Parameters:
cam

In output, camera parameters to fill.

I

A B&W image send by the current camera in use.

  1. getCameraParameters(self: visp._visp.robot.Afma6, cam: visp._visp.core.CameraParameters, I: visp._visp.core.ImageRGBa) -> None

Get the current intrinsic camera parameters obtained by calibration.

Camera parameters are read from /udd/fspindle/robot/Afma6/current/include/const_camera_Afma6.xml

#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)
  vpImage<vpRGBa> I;
  vp1394TwoGrabber g;

  // Acquire an image to update image structure
  g.acquire(I) ;

  vpRobotAfma6 robot;
  vpCameraParameters cam ;
  // 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
}
Parameters:
cam

In output, camera parameters to fill.

I

A color image send by the current camera in use.

getCameraParametersProjType(self) visp._visp.core.CameraParameters.CameraParametersProjType

Get the current camera model projection type.

getCoupl56(self) float

Return the coupling factor between join 5 and 6.

Returns:

Coupling factor between join 5 and 6.

getForwardKinematics(self, q: visp._visp.core.ColVector) visp._visp.core.HomogeneousMatrix

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

Note

See get_fMc(const vpColVector & q)

Note

See getInverseKinematics()

Parameters:
q: visp._visp.core.ColVector

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

getInverseKinematics(self, fMc: visp._visp.core.HomogeneousMatrix, q: visp._visp.core.ColVector, nearest: bool = true, verbose: bool = false) int

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.

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);
  vpHomogeneousMatrix fMc;

  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
}

Note

See getForwardKinematics()

Parameters:
fMc: visp._visp.core.HomogeneousMatrix

Homogeneous matrix describing the transformation from base frame to the camera frame.

q: visp._visp.core.ColVector

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: bool = true

true to return the nearest solution to q. false to return the farest.

verbose: bool = false

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.

getJointMax(self) visp._visp.core.ColVector

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.

getJointMin(self) visp._visp.core.ColVector

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.

getLong56(self) float

Return the distance between join 5 and 6.

Returns:

Distance between join 5 and 6.

getToolType(self) visp._visp.robot.Afma6.Afma6ToolType

Get the current tool type.

get_cMe(self, cMe: visp._visp.core.HomogeneousMatrix) None

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: visp._visp.core.HomogeneousMatrix

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

get_cVe(self, cVe: visp._visp.core.VelocityTwistMatrix) None

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: visp._visp.core.VelocityTwistMatrix

Twist transformation.

get_eJe(self, q: visp._visp.core.ColVector, eJe: visp._visp.core.Matrix) None

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

Parameters:
q: visp._visp.core.ColVector

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: visp._visp.core.Matrix

Robot jacobian expressed in the end-effector frame.

get_eMc(self) visp._visp.core.HomogeneousMatrix

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.

get_fJe(self, q: visp._visp.core.ColVector, fJe: visp._visp.core.Matrix) None

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

\[\begin{split}{^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) \end{split}\]

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

Parameters:
q: visp._visp.core.ColVector

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: visp._visp.core.Matrix

Robot jacobian expressed in the robot reference frame.

get_fMc(*args, **kwargs)

Overloaded function.

  1. get_fMc(self: visp._visp.robot.Afma6, q: visp._visp.core.ColVector) -> visp._visp.core.HomogeneousMatrix

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

Note

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

  1. get_fMc(self: visp._visp.robot.Afma6, q: visp._visp.core.ColVector, fMc: visp._visp.core.HomogeneousMatrix) -> None

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.

fMc

The homogeneous matrix corresponding to the direct geometric model which expresses the transformation between the fix frame and the camera frame (fMc).

get_fMe(self, q: visp._visp.core.ColVector, fMe: visp._visp.core.HomogeneousMatrix) None

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: visp._visp.core.ColVector

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: visp._visp.core.HomogeneousMatrix

The homogeneous matrix corresponding to the direct geometric model which expresses the transformation between the fix frame and the end effector frame (fMe).

init(*args, **kwargs)

Overloaded function.

  1. init(self: visp._visp.robot.Afma6) -> None

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

  1. init(self: visp._visp.robot.Afma6, camera_extrinsic_parameters: str) -> None

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.

  1. init(self: visp._visp.robot.Afma6, camera_extrinsic_parameters: str, camera_intrinsic_parameters: str) -> None

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.

  1. init(self: visp._visp.robot.Afma6, tool: visp._visp.robot.Afma6.Afma6ToolType, filename: str) -> None

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.

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

Note

See init (vpAfma6::vpToolType, vpCameraParameters::vpCameraParametersProjType ), init (vpAfma6::vpToolType, const vpHomogeneousMatrix &)

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.

  1. init(self: visp._visp.robot.Afma6, tool: visp._visp.robot.Afma6.Afma6ToolType, eMc_: visp._visp.core.HomogeneousMatrix) -> None

Set the type of tool attached to the robot and the transformation between the end-effector and the tool ( \(^e{\bf M}c\) ).

Note

See init ( vpAfma6::vpAfma6ToolType , vpCameraParameters::vpCameraParametersProjType ), init(vpAfma6::vpAfma6ToolType, const std::string&)

Parameters:
tool

Type of tool in use.

  1. init(self: visp._visp.robot.Afma6, tool: visp._visp.robot.Afma6.Afma6ToolType, projModel: visp._visp.core.CameraParameters.CameraParametersProjType) -> None

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.

parseConfigFile(self, filename: str) None

This function gets the robot constant parameters from a file.

Parameters:
filename: str

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.

set_eMc(self, eMc: visp._visp.core.HomogeneousMatrix) None

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

Parameters:
eMc: visp._visp.core.HomogeneousMatrix

Transformation between the end-effector frame and the tool frame.