RobotAfma6

class RobotAfma6(self, verbose: bool = true)

Bases: Afma6, Robot

Control of Irisa’s gantry robot named Afma6.

Implementation of the vpRobot class in order to control Irisa’s Afma6 robot. This robot is a gantry robot with six degrees of freedom manufactured in 1992 by the french Afma-Robots company. In 2008, the low level controller change for a more recent Adept technology based on the MotionBlox controller. A firewire camera is mounted on the end-effector to allow eye-in-hand visual servoing. The control of this camera is achieved by the vp1394TwoGrabber class. A ring light is attached around the camera. The control of this ring light is possible throw the vpRingLight class. A CCMOP gripper is also mounted on the end-effector. The pneumatic control of this gripper is possible throw the openGripper() or closeGripper() member functions.

This class allows to control the Afma6 gantry robot in position and velocity:

  • in the joint space ( vpRobot::ARTICULAR_FRAME ),

  • in the fixed reference frame ( vpRobot::REFERENCE_FRAME ),

  • in the camera frame ( vpRobot::CAMERA_FRAME ),

  • or in a mixed frame ( vpRobot::MIXT_FRAME ) where translations are expressed in the reference frame and rotations in the camera frame.

End-effector frame ( vpRobot::END_EFFECTOR_FRAME ) is not implemented.

All the translations are expressed in meters for positions and m/s for the velocities. Rotations are expressed in radians for the positions, and rad/s for the rotation velocities.

The direct and inverse kinematics models are implemented in the vpAfma6 class.

Warning

A Ctrl-C, a segmentation fault or other system errors are catched by this class to stop the robot.

To communicate with the robot, you may first create an instance of this class by calling the default constructor:

#include <visp3/robot/vpRobotAfma6.h>

#ifdef VISP_HAVE_AFMA6
int main()
{
  vpRobotAfma6 robot;
}
#else
int main() {}
#endif

This initialize the robot kinematics with the eMc extrinsic camera parameters obtained with a projection model without distortion. To set the robot kinematics with the eMc matrix obtained with a camera perspective model including distortion you need to initialize the robot with:

// Set the extrinsic camera parameters obtained with a perpective
// projection model including a distortion parameter
robot.init(vpAfma6::TOOL_CCMOP, vpCameraParameters::perspectiveProjWithDistortion);

You can get the intrinsic camera parameters of the image I acquired with the camera, with:

vpCameraParameters cam;
robot.getCameraParameters(cam, I);
// In cam, you get the intrinsic parameters of the projection model
// with distortion.

To control the robot in position, you may set the controller to position control and than send the position to reach in a specific frame like here in the joint space:

vpColVector q(6);
// Set a joint position
q[0] = 0.1; // x axis, in meter
q[1] = 0.2; // y axis, in meter
q[2] = 0.3; // z axis, in meter
q[3] = M_PI/8; // rotation around A axis, in rad
q[4] = M_PI/4; // rotation around B axis, in rad
q[5] = M_PI;   // rotation around C axis, in rad

// Initialize the controller to position control
robot.setRobotState(vpRobot::STATE_POSITION_CONTROL);

// Moves the robot in the joint space
robot.setPosition(vpRobot::ARTICULAR_FRAME, q);

The robot moves to the specified position with the default positioning velocity vpRobotAfma6::defaultPositioningVelocity . The setPositioningVelocity() method allows to change the maximal velocity used to reach the desired position.

// Set the max velocity to 40%
robot.setPositioningVelocity(40);

// Moves the robot in the joint space
robot.setPosition(vpRobot::ARTICULAR_FRAME, q);

To control the robot in velocity, you may set the controller to velocity control and than send the velocities. To end the velocity control and stop the robot you have to set the controller to the stop state. Here is an example of a velocity control in the joint space:

vpColVector qvel(6);
// Set a joint velocity
qvel[0] = 0.1;    // x axis, in m/s
qvel[1] = 0.2;    // y axis, in m/s
qvel[2] = 0;      // z axis, in m/s
qvel[3] = M_PI/8; // rotation around A axis, in rad/s
qvel[4] = 0;      // rotation around B axis, in rad/s
qvel[5] = 0;      // rotation around C axis, in rad/s

// Initialize the controller to position control
robot.setRobotState(vpRobot::STATE_VELOCITY_CONTROL);

while (...) {
  // Apply a velocity in the joint space
  robot.setVelocity(vpRobot::ARTICULAR_FRAME, qvel);

  // Compute new velocities qvel...
}

// Stop the robot
robot.setRobotState(vpRobot::STATE_STOP)

There is also possible to measure the robot current position with getPosition() method and the robot current velocities with the getVelocity() method.

For convenience, there is also the ability to read/write joint positions from a position file with readPosFile() and writePosFile() methods.

The only available constructor.

This constructor calls init() to initialise the connection with the MotionBox or low level controller, send the default eMc homogeneous matrix, power on the robot and wait 1 sec before returning to be sure the initialisation is done.

It also set the robot state to vpRobot::STATE_STOP .

To set the extrinsic camera parameters related to the eMc matrix obtained with a camera perspective projection model including the distortion, use the code below:

vpRobotAfma6 robot;
// Set the extrinsic camera parameters obtained with a perpective
// projection model including a distortion parameter
robot.init(vpAfma6::TOOL_CCMOP,
vpCameraParameters::perspectiveProjWithDistortion); 

Now, you can get the intrinsic camera parameters of the image I acquired with the camera, with:

vpCameraParameters cam;
robot.getCameraParameters(cam, I);
// In cam, you get the intrinsic parameters of the projection model
// with distortion.

Note

See vpCameraParameters , init (vpAfma6::vpAfma6CameraRobotType, vpCameraParameters::vpCameraParametersProjType )

Methods

__init__

The only available constructor.

checkJointLimits

Test the joints of the robot to detect if one or more is at its limit.

closeGripper

Close the pneumatic CCMOP gripper.

getDisplacement

Get the robot displacement since the last call of this method.

getPosition

Overloaded function.

getPositioningVelocity

Get the maximal velocity percentage used for a position control.

getPowerState

Get the robot power state indication if power is on or off.

getTime

Returns the robot controller current time (in second) since last robot power on.

getVelocity

Overloaded function.

get_cMe

Overloaded function.

get_cVe

Overloaded function.

get_eJe

Overloaded function.

get_fJe

Overloaded function.

init

Overloaded function.

move

Overloaded function.

openGripper

Open the pneumatic CCMOP gripper.

powerOff

Power off the robot.

powerOn

Power on the robot.

readPosFile

Read joint positions in a specific Afma6 position file.

savePosFile

Save joint (articular) positions in a specific Afma6 position file.

setPosition

Overloaded function.

setPositioningVelocity

Set the maximal velocity percentage to use for a position control.

setRobotState

Overloaded function.

setVelocity

set_eMc

Overloaded function.

stopMotion

Stop the robot and set the robot state to vpRobot::STATE_STOP .

Inherited Methods

TOOL_GRIPPER

setMaxTranslationVelocity

Set the maximal translation velocity that can be sent to the robot during a velocity control.

CONST_CCMOP_CAMERA_NAME

CONST_CAMERA_AFMA6_FILENAME

CONST_EMC_VACUUM_WITH_DISTORTION_FILENAME

END_EFFECTOR_FRAME

CAMERA_FRAME

saturateVelocities

Saturate velocities.

getInverseKinematics

Compute the inverse kinematics (inverse geometric model).

CONST_VACUUM_CAMERA_NAME

get_fMc

Overloaded function.

CONST_GENERIC_CAMERA_NAME

getCameraParameters

Overloaded function.

CONST_EMC_GENERIC_WITH_DISTORTION_FILENAME

STATE_ACCELERATION_CONTROL

RobotStateType

Robot control frames.

TOOL_CCMOP

TOOL_GENERIC_CAMERA

JOINT_STATE

TOOL_CUSTOM

STATE_POSITION_CONTROL

CONST_EMC_INTEL_D435_WITH_DISTORTION_FILENAME

CONST_EMC_VACUUM_WITHOUT_DISTORTION_FILENAME

Afma6ToolType

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

getMaxRotationVelocity

Get the maximal rotation velocity that can be sent to the robot during a velocity control.

CONST_EMC_GRIPPER_WITHOUT_DISTORTION_FILENAME

STATE_FORCE_TORQUE_CONTROL

get_eMc

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

getNDof

Return robot degrees of freedom number.

MIXT_FRAME

getJointMin

Get min joint values.

TOOL_INTEL_D435_CAMERA

CONST_GRIPPER_CAMERA_NAME

getLong56

Return the distance between join 5 and 6.

parseConfigFile

This function gets the robot constant parameters from a file.

getCoupl56

Return the coupling factor between join 5 and 6.

get_fMe

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

TOOL_VACUUM

ARTICULAR_FRAME

STATE_STOP

ControlFrameType

Robot control frames.

getToolType

Get the current tool type.

STATE_VELOCITY_CONTROL

CONST_EMC_GRIPPER_WITH_DISTORTION_FILENAME

CONST_INTEL_D435_CAMERA_NAME

getRobotState

setVerbose

CONST_AFMA6_FILENAME

defaultTool

setMaxRotationVelocity

Set the maximal rotation velocity that can be sent to the robot during a velocity control.

TOOL_FRAME

CONST_EMC_CCMOP_WITH_DISTORTION_FILENAME

CONST_EMC_CCMOP_WITHOUT_DISTORTION_FILENAME

getCameraParametersProjType

Get the current camera model projection type.

getForwardKinematics

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

CONST_EMC_INTEL_D435_WITHOUT_DISTORTION_FILENAME

getJointMax

Get max joint values.

getMaxTranslationVelocity

Get the maximal translation velocity that can be sent to the robot during a velocity control.

njoint

REFERENCE_FRAME

CONST_EMC_GENERIC_WITHOUT_DISTORTION_FILENAME

Operators

__doc__

__init__

The only available constructor.

__module__

Attributes

ARTICULAR_FRAME

CAMERA_FRAME

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

END_EFFECTOR_FRAME

JOINT_STATE

MIXT_FRAME

REFERENCE_FRAME

STATE_ACCELERATION_CONTROL

STATE_FORCE_TORQUE_CONTROL

STATE_POSITION_CONTROL

STATE_STOP

STATE_VELOCITY_CONTROL

TOOL_CCMOP

TOOL_CUSTOM

TOOL_FRAME

TOOL_GENERIC_CAMERA

TOOL_GRIPPER

TOOL_INTEL_D435_CAMERA

TOOL_VACUUM

__annotations__

defaultPositioningVelocity

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
class ControlFrameType(self, value: int)

Bases: pybind11_object

Robot control frames.

Values:

  • REFERENCE_FRAME: Corresponds to a fixed reference frame attached to the robot structure.

  • ARTICULAR_FRAME: Corresponds to the joint state. This value is deprecated. You should rather use vpRobot::JOINT_STATE .

  • JOINT_STATE: Corresponds to the joint state.

  • END_EFFECTOR_FRAME: Corresponds to robot end-effector frame.

  • CAMERA_FRAME: Corresponds to a frame attached to the camera mounted on the robot end-effector.

  • TOOL_FRAME: Corresponds to a frame attached to the tool (camera, gripper…) mounted on the robot end-effector. This value is equal to vpRobot::CAMERA_FRAME .

  • MIXT_FRAME: Corresponds to a “virtual” frame where translations are expressed in the reference frame, and rotations in the camera frame.

__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
class RobotStateType(self, value: int)

Bases: pybind11_object

Robot control frames.

Values:

  • REFERENCE_FRAME: Corresponds to a fixed reference frame attached to the robot structure.

  • ARTICULAR_FRAME: Corresponds to the joint state. This value is deprecated. You should rather use vpRobot::JOINT_STATE .

  • JOINT_STATE: Corresponds to the joint state.

  • END_EFFECTOR_FRAME: Corresponds to robot end-effector frame.

  • CAMERA_FRAME: Corresponds to a frame attached to the camera mounted on the robot end-effector.

  • TOOL_FRAME: Corresponds to a frame attached to the tool (camera, gripper…) mounted on the robot end-effector. This value is equal to vpRobot::CAMERA_FRAME .

  • MIXT_FRAME: Corresponds to a “virtual” frame where translations are expressed in the reference frame, and rotations in the camera frame.

__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, verbose: bool = true)

The only available constructor.

This constructor calls init() to initialise the connection with the MotionBox or low level controller, send the default eMc homogeneous matrix, power on the robot and wait 1 sec before returning to be sure the initialisation is done.

It also set the robot state to vpRobot::STATE_STOP .

To set the extrinsic camera parameters related to the eMc matrix obtained with a camera perspective projection model including the distortion, use the code below:

vpRobotAfma6 robot;
// Set the extrinsic camera parameters obtained with a perpective
// projection model including a distortion parameter
robot.init(vpAfma6::TOOL_CCMOP,
vpCameraParameters::perspectiveProjWithDistortion); 

Now, you can get the intrinsic camera parameters of the image I acquired with the camera, with:

vpCameraParameters cam;
robot.getCameraParameters(cam, I);
// In cam, you get the intrinsic parameters of the projection model
// with distortion.

Note

See vpCameraParameters , init (vpAfma6::vpAfma6CameraRobotType, vpCameraParameters::vpCameraParametersProjType )

checkJointLimits(self, jointsStatus: visp._visp.core.ColVector) bool

Test the joints of the robot to detect if one or more is at its limit.

Parameters:
jointsStatus: visp._visp.core.ColVector

A vector (size 6) of the status of the joints. For each joint, the value is equal to 1 if the joint is at its maximal limit, -1 if the joint is at its minimal value and 0 otherwise.

Returns:

false if at least one joint is at one of its limit.

closeGripper(self) None

Close the pneumatic CCMOP gripper.

Note

See openGripper()

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.

getDisplacement(self, frame: visp._visp.robot.Robot.ControlFrameType, displacement: visp._visp.core.ColVector) None

Get the robot displacement since the last call of this method.

Warning

This functionnality is not implemented for the moment in the reference and mixt frames. It is only available in the joint space ( vpRobot::ARTICULAR_FRAME ) and in the camera frame ( vpRobot::CAMERA_FRAME ).

In camera or reference frame, rotations are expressed with the Euler Rxyz representation.

Parameters:
frame: visp._visp.robot.Robot.ControlFrameType

The frame in which the measured displacement is expressed.

displacement: visp._visp.core.ColVector

<unparsed orderedlist <doxmlparser.compound.docListType object at 0x7ff6921173d0>>

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.

getMaxRotationVelocity(self) float

Get the maximal rotation velocity that can be sent to the robot during a velocity control.

Returns:

Maximum rotation velocity expressed in rad/s.

getMaxTranslationVelocity(self) float

Get the maximal translation velocity that can be sent to the robot during a velocity control.

Returns:

Maximum translational velocity expressed in m/s.

getNDof(self) int

Return robot degrees of freedom number.

getPosition(*args, **kwargs)

Overloaded function.

  1. getPosition(self: visp._visp.robot.RobotAfma6, frame: visp._visp.robot.Robot.ControlFrameType, position: visp._visp.core.ColVector) -> None

  2. getPosition(self: visp._visp.robot.RobotAfma6, frame: visp._visp.robot.Robot.ControlFrameType, position: visp._visp.core.ColVector, timestamp: float) -> float

  3. getPosition(self: visp._visp.robot.RobotAfma6, frame: visp._visp.robot.Robot.ControlFrameType, position: visp._visp.core.PoseVector) -> None

  4. getPosition(self: visp._visp.robot.RobotAfma6, frame: visp._visp.robot.Robot.ControlFrameType, position: visp._visp.core.PoseVector, timestamp: float) -> float

  5. getPosition(self: visp._visp.robot.Robot, frame: visp._visp.robot.Robot.ControlFrameType) -> visp._visp.core.ColVector

getPositioningVelocity(self) float

Get the maximal velocity percentage used for a position control.

Note

See setPositioningVelocity()

getPowerState(self) bool

Get the robot power state indication if power is on or off.

Note

See powerOn() , powerOff()

Returns:

true if power is on. false if power is off

getRobotState(self) visp._visp.robot.Robot.RobotStateType
getTime(self) float

Returns the robot controller current time (in second) since last robot power on.

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

Get the current tool type.

getVelocity(*args, **kwargs)

Overloaded function.

  1. getVelocity(self: visp._visp.robot.RobotAfma6, frame: visp._visp.robot.Robot.ControlFrameType, velocity: visp._visp.core.ColVector) -> None

  2. getVelocity(self: visp._visp.robot.RobotAfma6, frame: visp._visp.robot.Robot.ControlFrameType, velocity: visp._visp.core.ColVector, timestamp: float) -> float

  3. getVelocity(self: visp._visp.robot.RobotAfma6, frame: visp._visp.robot.Robot.ControlFrameType) -> visp._visp.core.ColVector

  4. getVelocity(self: visp._visp.robot.RobotAfma6, frame: visp._visp.robot.Robot.ControlFrameType, timestamp: float) -> tuple[visp._visp.core.ColVector, float]

get_cMe(*args, **kwargs)

Overloaded function.

  1. get_cMe(self: visp._visp.robot.RobotAfma6, _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.

  1. get_cMe(self: visp._visp.robot.Afma6, 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

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

get_cVe(*args, **kwargs)

Overloaded function.

  1. get_cVe(self: visp._visp.robot.RobotAfma6, _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.

  1. get_cVe(self: visp._visp.robot.Afma6, 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

Twist transformation.

get_eJe(*args, **kwargs)

Overloaded function.

  1. get_eJe(self: visp._visp.robot.RobotAfma6, _eJe: visp._visp.core.Matrix) -> None

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

To compute eJe, we communicate with the low level controller to get the articular joint position of the robot.

  1. get_eJe(self: visp._visp.robot.Afma6, q: visp._visp.core.ColVector, eJe: visp._visp.core.Matrix) -> None

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.

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(*args, **kwargs)

Overloaded function.

  1. get_fJe(self: visp._visp.robot.RobotAfma6, _fJe: visp._visp.core.Matrix) -> None

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

To compute fJe, we communicate with the low level controller to get the articular joint position of the robot.

\[\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 & -s4c5 \\0 & 0 & 0 & 0 & s4 & c4c5 \\0 & 0 & 0 & 1 & 0 & s5 \\\end{array} \right) \end{split}\]
  1. get_fJe(self: visp._visp.robot.Afma6, 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

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.

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

Initialise the connection with the MotionBox or low level controller, send the default eMc homogeneous matrix, power on the robot and wait 1 sec before returning to be sure the initialisation is done.

Warning

This method sets the camera extrinsic parameters (matrix eMc) to the one obtained by calibration with a camera projection model without distortion by calling init(vpAfma6::defaultCameraRobot). If you want to set the extrinsic camera parameters to those obtained with a camera perspective model including the distortion you have to call the init(vpAfma6::vpAfma6CameraRobotType, vpCameraParameters::vpCameraParametersProjType ) method.

Note

See vpCameraParameters , init (vpAfma6::vpAfma6CameraRobotType, vpCameraParameters::vpCameraParametersProjType )

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

Initialize the robot kinematics with user defined parameters (set the eMc homogeneous parameters in the low level controller) and also get the joint limits from the low-level controller.

To set the transformation parameters related to the \(^e{\bf M}_c\) matrix, use the code below:

#include <visp3/robot/vpRobotAfma6.h>

int main()
{
#ifdef VISP_HAVE_AFMA6
  vpRobotAfma6 robot;

  // Set the transformation between the end-effector frame
  // and the tool frame.
  vpHomogeneousMatrix eMc(0.001, 0.0, 0.1, 0.0, 0.0, M_PI/2);

  robot.init(vpAfma6::TOOL_CUSTOM, eMc);
#endif
}

Note

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

Parameters:
tool

Tool to use.

eMc

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

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

Initialize the robot kinematics (set the eMc homogeneous parameters in the low level controller) from a file and also get the joint limits from the low-level controller.

To set the transformation parameters related to the \(^e{\bf M}_c\) matrix, use the code below:

#include <visp3/robot/vpRobotAfma6.h>

int main()
{
#ifdef VISP_HAVE_AFMA6
  vpRobotAfma6 robot;

  // Set the transformation between the end-effector frame
  // and the tool frame from a file
  std::string filename("./EffectorToolTransformation.cnf");

  robot.init(vpAfma6::TOOL_CUSTOM, filename);
#endif
}

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() , init ( vpAfma6::vpAfma6ToolType , vpCameraParameters::vpCameraParametersProjType ), init(vpAfma6::vpAfma6ToolType, const vpHomogeneousMatrix&)

Parameters:
tool

Tool to 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.RobotAfma6, tool: visp._visp.robot.Afma6.Afma6ToolType, projModel: visp._visp.core.CameraParameters.CameraParametersProjType) -> None

Initialize the robot kinematics with the extrinsic calibration parameters associated to a specific camera (set the eMc homogeneous parameters in the low level controller) and also get the joint limits from the low-level controller.

The eMc parameters depend on the camera and the projection model in use.

To set the extrinsic camera parameters related to the eMc matrix obtained with a camera perspective projection model including the distortion, use the code below:

vpRobotAfma6 robot;
// Set the extrinsic camera parameters obtained with a perpective
// projection model including a distortion parameter
robot.init(vpAfma6::TOOL_CCMOP,
vpCameraParameters::perspectiveProjWithDistortion); 

Now, you can get the intrinsic camera parameters of the image I acquired with the camera, with:

vpCameraParameters cam;
robot.getCameraParameters(cam, I);
// In cam, you get the intrinsic parameters of the projection model
// with distortion.

Note

See vpCameraParameters , init()

Parameters:
tool

Tool to use.

projModel

Projection model associated to the camera.

  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.

move(*args, **kwargs)

Overloaded function.

  1. move(self: visp._visp.robot.RobotAfma6, filename: str) -> None

Moves the robot to the joint position specified in the filename. The positioning velocity is set to 10% of the robot maximal velocity.

Note

See readPosFile() , move(const char *, const double)

Parameters:
filename

File containing a joint position to reach.

  1. move(self: visp._visp.robot.RobotAfma6, filename: str, velocity: float) -> None

Moves the robot to the joint position specified in the filename with a specified positioning velocity .

Note

See readPosFile() , move(const char *)

Parameters:
filename

File containing a joint position to reach.

velocity

Percentage of the maximal velocity. Values should be in ]0:100].

openGripper(self) None

Open the pneumatic CCMOP gripper.

Note

See closeGripper()

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.

powerOff(self) None

Power off the robot.

Note

See powerOn() , getPowerState()

powerOn(self) None

Power on the robot.

Note

See powerOff() , getPowerState()

static readPosFile(filename: str, q: visp._visp.core.ColVector) bool

Read joint positions in a specific Afma6 position file.

This position file has to start with a header. The six joint positions are given after the “R:” keyword. The first 3 values correspond to the joint translations X,Y,Z expressed in meters. The 3 last values correspond to the joint rotations A,B,C expressed in degres to be more representative for the user. Theses values are then converted in radians in q . The character “#” starting a line indicates a comment.

A typical content of such a file is given below:

#AFMA6 - Position - Version 2.01
# file: "myposition.pos "
#
# R: X Y Z A B C
# Joint position: X, Y, Z: translations in meters
#                 A, B, C: rotations in degrees
#

R: 0.1 0.3 -0.25 -80.5 80 0

The code below shows how to read a position from a file and move the robot to this position.

vpRobotAfma6 robot;
vpColVector q;        // Joint position
robot.readPosFile("myposition.pos", q); // Set the joint position from the file
robot.setRobotState(vpRobot::STATE_POSITION_CONTROL);

robot.setPositioningVelocity(5); // Positioning velocity set to 5%
robot.setPosition(vpRobot::ARTICULAR_FRAME, q); // Move to the joint position

Note

See savePosFile()

Parameters:
filename: str

Name of the position file to read.

q: visp._visp.core.ColVector

Joint positions: X,Y,Z,A,B,C. Translations X,Y,Z are expressed in meters, while joint rotations A,B,C in radians.

Returns:

true if the positions were successfully readen in the file. false, if an error occurs.

static saturateVelocities(v_in: visp._visp.core.ColVector, v_max: visp._visp.core.ColVector, verbose: bool = false) visp._visp.core.ColVector

Saturate velocities.

The code below shows how to use this static method in order to saturate a velocity skew vector.

#include <iostream>

#include <visp3/robot/vpRobot.h>

int main()
{
  // Set a velocity skew vector
  vpColVector v(6);
  v[0] = 0.1;               // vx in m/s
  v[1] = 0.2;               // vy
  v[2] = 0.3;               // vz
  v[3] = vpMath::rad(10);   // wx in rad/s
  v[4] = vpMath::rad(-10);  // wy
  v[5] = vpMath::rad(20);   // wz

  // Set the maximal allowed velocities
  vpColVector v_max(6);
  for (int i=0; i<3; i++)
    v_max[i] = 0.3;             // in translation (m/s)
  for (int i=3; i<6; i++)
    v_max[i] = vpMath::rad(10); // in rotation (rad/s)

  // Compute the saturated velocity skew vector
  vpColVector v_sat = vpRobot::saturateVelocities(v, v_max, true);

  std::cout << "v    : " << v.t() << std::endl;
  std::cout << "v max: " << v_max.t() << std::endl;
  std::cout << "v sat: " << v_sat.t() << std::endl;

  return 0;
}
Parameters:
v_in: visp._visp.core.ColVector

Vector of input velocities to saturate. Translation velocities should be expressed in m/s while rotation velocities in rad/s.

v_max: visp._visp.core.ColVector

Vector of maximal allowed velocities. Maximal translation velocities should be expressed in m/s while maximal rotation velocities in rad/s.

verbose: bool = false

Print a message indicating which axis causes the saturation.

Returns:

Saturated velocities.

static savePosFile(filename: str, q: visp._visp.core.ColVector) bool

Save joint (articular) positions in a specific Afma6 position file.

This position file starts with a header on the first line. After convertion of the rotations in degrees, the joint position q is written on a line starting with the keyword “R: “. See readPosFile() documentation for an example of such a file.

Note

See readPosFile()

Parameters:
filename: str

Name of the position file to create.

q: visp._visp.core.ColVector

Joint positions [X,Y,Z,A,B,C] to save in the filename. Translations X,Y,Z are expressed in meters, while rotations A,B,C in radians.

Returns:

true if the positions were successfully saved in the file. false, if an error occurs.

setMaxRotationVelocity(self, maxVr: float) None

Set the maximal rotation velocity that can be sent to the robot during a velocity control.

setMaxTranslationVelocity(self, maxVt: float) None

Set the maximal translation velocity that can be sent to the robot during a velocity control.

setPosition(*args, **kwargs)

Overloaded function.

  1. setPosition(self: visp._visp.robot.RobotAfma6, frame: visp._visp.robot.Robot.ControlFrameType, pose: visp._visp.core.PoseVector) -> None

  2. setPosition(self: visp._visp.robot.RobotAfma6, frame: visp._visp.robot.Robot.ControlFrameType, position: visp._visp.core.ColVector) -> None

  3. setPosition(self: visp._visp.robot.RobotAfma6, frame: visp._visp.robot.Robot.ControlFrameType, pos1: float, pos2: float, pos3: float, pos4: float, pos5: float, pos6: float) -> None

  4. setPosition(self: visp._visp.robot.RobotAfma6, filename: str) -> None

Move to an absolute joint position with a given percent of max velocity. The robot state is set to position control. The percent of max velocity is to set with setPositioningVelocity() . The position to reach is defined in the position file.

This method has the same behavior than the sample code given below;

#include <visp3/core/vpColVector.h>
#include <visp3/robot/vpRobotAfma6.h>

int main()
{
#ifdef VISP_HAVE_AFMA6
  vpRobotAfma6 robot;
  vpColVector q; // joint position

  robot.readPosFile("MyPositionFilename.pos", q);
  robot.setRobotState(vpRobot::STATE_POSITION_CONTROL);
  robot.setPosition(vpRobot::ARTICULAR_FRAME, q);

  return 0;
#endif
}

Note

See setPositioningVelocity()

Parameters:
filename

Name of the position file to read. The readPosFile() documentation shows a typical content of such a position file.

setPositioningVelocity(self, velocity: float) None

Set the maximal velocity percentage to use for a position control.

The default positioning velocity is defined by vpRobotAfma6::defaultPositioningVelocity . This method allows to change this default positioning velocity

vpColVector position(6);
position = 0; // position in meter and rad

vpRobotAfma6 robot;

robot.setRobotState(vpRobot::STATE_POSITION_CONTROL);

// Set the max velocity to 20%
robot.setPositioningVelocity(20);

// Moves the robot to the joint position [0,0,0,0,0,0]
robot.setPosition(vpRobot::ARTICULAR_FRAME, position);

Note

See getPositioningVelocity()

Parameters:
velocity: float

Percentage of the maximal velocity. Values should be in ]0:100].

setRobotState(*args, **kwargs)

Overloaded function.

  1. setRobotState(self: visp._visp.robot.RobotAfma6, newState: visp._visp.robot.Robot.RobotStateType) -> visp._visp.robot.Robot.RobotStateType

Change the robot state.

Parameters:
newState

New requested robot state.

  1. setRobotState(self: visp._visp.robot.Robot, newState: visp._visp.robot.Robot.RobotStateType) -> visp._visp.robot.Robot.RobotStateType

setVelocity(self, frame: visp._visp.robot.Robot.ControlFrameType, velocity: visp._visp.core.ColVector) None
setVerbose(self, verbose: bool) None
set_eMc(*args, **kwargs)

Overloaded function.

  1. set_eMc(self: visp._visp.robot.RobotAfma6, eMc: visp._visp.core.HomogeneousMatrix) -> None

Set the geometric transformation between the end-effector frame and the tool frame in the low level controller.

Warning

This function overwrite the transformation parameters that were potentially set using one of the init functions

Parameters:
eMc

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

  1. set_eMc(self: visp._visp.robot.Afma6, eMc: visp._visp.core.HomogeneousMatrix) -> None

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.

stopMotion(self) None

Stop the robot and set the robot state to vpRobot::STATE_STOP .