SimulatorAfma6

class SimulatorAfma6(*args, **kwargs)

Bases: RobotWireFrameSimulator, Afma6

Simulator of Irisa’s gantry robot named Afma6.

Implementation of the vpRobotWireFrameSimulator class in order to simulate Irisa’s Afma6 robot. This robot is a gantry robot with six degrees of freedom manufactured in 1992 by the french Afma-Robots company.

Warning

This class uses threading capabilities. Thus on Unix-like platforms, the libpthread third-party library need to be installed. On Windows, we use the native threading capabilities.

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.

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

#include <visp3/core/vpColVector.h>
#include <visp3/core/vpConfig.h>
#include <visp3/core/vpMath.h>
#include <visp3/robot/vpSimulatorAfma6.h>

int main()
{
  vpSimulatorAfma6 robot;

  robot.init(vpAfma6::TOOL_CCMOP, vpCameraParameters::perspectiveProjWithoutDistortion);

  vpColVector q(6);
  // Set a joint position
  q[0] = 0.1;             // Joint 1 position, in meter
  q[1] = 0.2;             // Joint 2 position, in meter
  q[2] = 0.3;             // Joint 3 position, in meter
  q[3] = M_PI/8;          // Joint 4 position, in rad
  q[4] = M_PI/4;          // Joint 5 position, in rad
  q[5] = M_PI;            // Joint 6 position, 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);

  return 0;
}

To control the robot in velocity, you may set the controller to velocity control and then 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:

#include <visp3/core/vpColVector.h>
#include <visp3/core/vpMath.h>
#include <visp3/robot/vpSimulatorAfma6.h>

int main()
{
  vpSimulatorAfma6 robot;

  robot.init(vpAfma6::TOOL_GRIPPER, vpCameraParameters::perspectiveProjWithoutDistortion);

  vpColVector qvel(6);
  // Set a joint velocity
  qvel[0] = 0.1;             // Joint 1 velocity in m/s
  qvel[1] = 0.1;             // Joint 2 velocity in m/s
  qvel[2] = 0.1;             // Joint 3 velocity in m/s
  qvel[3] = M_PI/8;          // Joint 4 velocity in rad/s
  qvel[4] = 0;               // Joint 5 velocity in rad/s
  qvel[5] = 0;               // Joint 6 velocity in rad/s

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

  for ( ; ; ) {
    // 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);

  return 0;
}

It 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 savePosFile() methods.

To know how this class can be used to achieve a visual servoing simulation, you can follow the tutorial-ibvs.

Overloaded function.

  1. __init__(self: visp._visp.robot.SimulatorAfma6) -> None

Basic constructor

  1. __init__(self: visp._visp.robot.SimulatorAfma6, display: bool) -> None

Constructor used to enable or disable the external view of the robot.

Methods

__init__

Overloaded function.

getCameraParameters

Overloaded function.

getDisplacement

getPosition

Overloaded function.

getPositioningVelocity

getVelocity

Overloaded function.

get_cMe

Overloaded function.

get_cVe

Overloaded function.

get_eJe

Overloaded function.

get_fJe

Overloaded function.

init

Overloaded function.

initialiseCameraRelativeToObject

This method enables to initialise the joint coordinates of the robot in order to position the camera relative to the object.

initialiseObjectRelativeToCamera

This method enables to initialise the pose between the object and the reference frame, in order to position the object relative to the camera.

move

Moves the robot to the joint position specified in the filename.

readPosFile

Read joint positions in a specific Afma6 position file.

savePosFile

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

setCameraParameters

Set the intrinsic camera parameters.

setJointLimit

This method enables to set the minimum and maximum joint limits for all the six axis of the robot.

setPosition

Overloaded function.

setPositioningVelocity

setRobotState

setVelocity

stopMotion

Stop the robot.

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

MODEL_3D

CONST_CAMERA_AFMA6_FILENAME

CONST_EMC_VACUUM_WITH_DISTORTION_FILENAME

END_EFFECTOR_FRAME

CAMERA_FRAME

setDesiredCameraPosition

Set the desired position of the robot's camera relative to the object.

saturateVelocities

Saturate velocities.

getInverseKinematics

Compute the inverse kinematics (inverse geometric model).

CONST_VACUUM_CAMERA_NAME

get_fMc

Overloaded function.

setDisplayRobotType

getSamplingTime

Return the sampling time.

set_eMc

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

CONST_GENERIC_CAMERA_NAME

CONST_EMC_GENERIC_WITH_DISTORTION_FILENAME

STATE_ACCELERATION_CONTROL

RobotStateType

Robot control frames.

I

TOOL_CCMOP

TOOL_GENERIC_CAMERA

JOINT_STATE

TOOL_CUSTOM

get_cMo

Get the pose between the object and the robot's camera.

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.

setSingularityManagement

Set the parameter which enable or disable the singularity management.

DisplayRobotType

Values:

getMaxRotationVelocity

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

getExternalCameraPosition

Get the external camera's position relative to the the world reference frame.

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

setGraphicsThickness

Specify the thickness of the graphics drawings.

ARTICULAR_FRAME

setConstantSamplingTimeMode

Set the flag used to force the sampling time in the thread computing the robot's displacement to a constant value; see setSamplingTime() .

STATE_STOP

initScene

Overloaded function.

ControlFrameType

Robot control frames.

set_fMo

Set the pose between the object and the fixed world frame.

get_fMo

Get the pose between the object and the fixed world frame.

getToolType

Get the current tool type.

setSamplingTime

Overloaded function.

setCurrentViewColor

Set the color used to display the object at the current position in the robot's camera view.

STATE_VELOCITY_CONTROL

setExternalCameraPosition

Set the external camera point of view.

CONST_EMC_GRIPPER_WITH_DISTORTION_FILENAME

CONST_INTEL_D435_CAMERA_NAME

getRobotState

setVerbose

Activates extra printings when the robot reaches joint limits...

MODEL_DH

getInternalView

Overloaded function.

setDesiredViewColor

Set the color used to display the object at the desired position in the robot's camera view.

CONST_AFMA6_FILENAME

defaultTool

TOOL_FRAME

setMaxRotationVelocity

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

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

getExternalCameraParameters

Get the parameters of the virtual external camera.

CONST_EMC_GENERIC_WITHOUT_DISTORTION_FILENAME

setCameraColor

Set the color used to display the camera in the external view.

Operators

__doc__

__init__

Overloaded function.

__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

I

JOINT_STATE

MIXT_FRAME

MODEL_3D

MODEL_DH

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

Bases: pybind11_object

Values:

  • MODEL_3D

  • MODEL_DH

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

Overloaded function.

  1. __init__(self: visp._visp.robot.SimulatorAfma6) -> None

Basic constructor

  1. __init__(self: visp._visp.robot.SimulatorAfma6, display: bool) -> None

Constructor used to enable or disable the external view of the robot.

getCameraParameters(*args, **kwargs)

Overloaded function.

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

Get the current intrinsic camera parameters obtained by calibration.

Warning

The image size must be : 640x480 !

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.SimulatorAfma6, cam: visp._visp.core.CameraParameters, I: visp._visp.core.ImageGray) -> None

Get the current intrinsic camera parameters obtained by calibration.

Warning

The image size must be : 640x480 !

Parameters:
cam

In output, camera parameters to fill.

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

Get the current intrinsic camera parameters obtained by calibration.

Warning

The image size must be : 640x480 !

Parameters:
cam

In output, camera parameters to fill.

  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
getExternalCameraParameters(self) visp._visp.core.CameraParameters

Get the parameters of the virtual external camera.

Returns:

It returns the camera parameters.

getExternalCameraPosition(self) visp._visp.core.HomogeneousMatrix

Get the external camera’s position relative to the the world reference frame.

Returns:

the main external camera position relative to the the world reference frame.

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

getInternalView(*args, **kwargs)

Overloaded function.

  1. getInternalView(self: visp._visp.robot.RobotWireFrameSimulator, I: visp._visp.core.ImageRGBa) -> None

Get the view of the camera’s robot.

According to the initialisation method you used, the current position and maybee the desired position of the object are displayed.

Warning

: The objects are displayed thanks to overlays. The image I is not modified.

  1. getInternalView(self: visp._visp.robot.RobotWireFrameSimulator, I: visp._visp.core.ImageGray) -> None

Get the view of the camera’s robot.

According to the initialisation method you used, the current position and maybee the desired position of the object are displayed.

Warning

: The objects are displayed thanks to overlays. The image I is not modified.

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.SimulatorAfma6, frame: visp._visp.robot.Robot.ControlFrameType, q: visp._visp.core.ColVector) -> None

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

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

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

getPositioningVelocity(self) float
getRobotState(self) visp._visp.robot.Robot.RobotStateType
getSamplingTime(self) float

Return the sampling time.

Returns:

Sampling time in second used to compute the robot displacement from the velocity applied to the robot during this time.

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

Get the current tool type.

getVelocity(*args, **kwargs)

Overloaded function.

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

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

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

  4. getVelocity(self: visp._visp.robot.SimulatorAfma6, 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.SimulatorAfma6, cMe: visp._visp.core.HomogeneousMatrix) -> None

Get the geometric transformation \(^c{\bf M}_e\) 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.

  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_cMo(self) visp._visp.core.HomogeneousMatrix

Get the pose between the object and the robot’s camera.

Returns:

The pose between the object and the fixed world frame.

get_cVe(*args, **kwargs)

Overloaded function.

  1. get_cVe(self: visp._visp.robot.SimulatorAfma6, cVe: visp._visp.core.VelocityTwistMatrix) -> None

Get the twist transformation \(^c{\bf V}_e\) 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.

  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.SimulatorAfma6, eJe: visp._visp.core.Matrix) -> None

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

To compute \(^e{\bf J}_e\) , we communicate with the low level controller to get the 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.SimulatorAfma6, fJe: visp._visp.core.Matrix) -> None

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

To compute \(^f{\bf J}_e\) , we communicate with the low level controller to get the joint position of the robot.

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

get_fMo(self) visp._visp.core.HomogeneousMatrix

Get the pose between the object and the fixed world frame.

Returns:

The pose between the object and the fixed world frame.

init(*args, **kwargs)

Overloaded function.

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

The eMc parameters depend on the camera.

Warning

Only perspective projection without distortion is available!

Note

See vpCameraParameters , init()

Parameters:
tool

Tool to use. Note that the generic camera is not handled.

  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.

initScene(*args, **kwargs)

Overloaded function.

  1. initScene(self: visp._visp.robot.RobotWireFrameSimulator, obj: visp._visp.robot.WireFrameSimulator.SceneObject, desiredObject: visp._visp.robot.WireFrameSimulator.SceneDesiredObject) -> None

  2. initScene(self: visp._visp.robot.RobotWireFrameSimulator, obj: str, desiredObject: str) -> None

Initialize the display. It enables to choose the type of scene which will be used to display the object at the current position and at the desired position.

Here you can use the scene you want. You have to set the path to the .bnd file which is a scene file. It is also possible to use a vrml (.wrl) file.

Parameters:
obj

Path to the scene file you want to use.

  1. initScene(self: visp._visp.robot.RobotWireFrameSimulator, obj: visp._visp.robot.WireFrameSimulator.SceneObject) -> None

  2. initScene(self: visp._visp.robot.RobotWireFrameSimulator, obj: str) -> None

Initialize the display. It enables to choose the type of scene which will be used to display the object at the current position. The object at the desired position is not displayed.

Here you can use the scene you want. You have to set the path to the .bnd file which is a scene file, or the vrml file.

Parameters:
obj

Path to the scene file you want to use.

initialiseCameraRelativeToObject(self, cMo: visp._visp.core.HomogeneousMatrix) bool

This method enables to initialise the joint coordinates of the robot in order to position the camera relative to the object.

Before using this method it is advised to set the position of the object thanks to the set_fMo() method.

In other terms, set the world to camera transformation \({^f}{\bf M}_c = {^f}{\bf M}_o \; ({^c}{\bf M}_o)^{-1}\) , and from the inverse kinematics set the joint positions \({\bf q}\) that corresponds to the \({^f}{\bf M}_c\) transformation.

Returns:

false if the robot kinematics is not able to reach the cMo position.

initialiseObjectRelativeToCamera(self, cMo: visp._visp.core.HomogeneousMatrix) None

This method enables to initialise the pose between the object and the reference frame, in order to position the object relative to the camera.

Before using this method it is advised to set the articular coordinates of the robot.

In other terms, set the world to object transformation \({^f}{\bf M}_o = {^f}{\bf M}_c \; {^c}{\bf M}_o\) where \({^f}{\bf M}_c = f({\bf q})\) with \({\bf q}\) the robot joint position

move(self, filename: str) None

Moves the robot to the joint position specified in the filename.

Note

See readPosFile

Parameters:
filename: str

File containing a joint position.

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.

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.

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

setCameraColor(self, col: visp._visp.core.Color) None

Set the color used to display the camera in the external view.

Parameters:
col: visp._visp.core.Color

The desired color.

setCameraParameters(self, cam: visp._visp.core.CameraParameters) None

Set the intrinsic camera parameters.

Parameters:
cam: visp._visp.core.CameraParameters

The desired camera parameters.

setConstantSamplingTimeMode(self, _constantSamplingTimeMode: bool) None

Set the flag used to force the sampling time in the thread computing the robot’s displacement to a constant value; see setSamplingTime() . It may be useful if the main thread (computing the features) is very time consuming. False by default.

Parameters:
_constantSamplingTimeMode: bool

The new value of the constantSamplingTimeMode flag.

setCurrentViewColor(self, col: visp._visp.core.Color) None

Set the color used to display the object at the current position in the robot’s camera view.

Parameters:
col: visp._visp.core.Color

The desired color.

setDesiredCameraPosition(self, cdMo_: visp._visp.core.HomogeneousMatrix) None

Set the desired position of the robot’s camera relative to the object.

Parameters:
cdMo_: visp._visp.core.HomogeneousMatrix

The desired pose of the camera.

setDesiredViewColor(self, col: visp._visp.core.Color) None

Set the color used to display the object at the desired position in the robot’s camera view.

Parameters:
col: visp._visp.core.Color

The desired color.

setDisplayRobotType(self, dispType: visp._visp.robot.RobotWireFrameSimulator.DisplayRobotType) None
setExternalCameraPosition(self, camMf_: visp._visp.core.HomogeneousMatrix) None

Set the external camera point of view.

Parameters:
camMf_: visp._visp.core.HomogeneousMatrix

The pose of the external camera relative to the world reference frame.

setGraphicsThickness(self, thickness: int) None

Specify the thickness of the graphics drawings.

setJointLimit(self, limitMin: visp._visp.core.ColVector, limitMax: visp._visp.core.ColVector) None

This method enables to set the minimum and maximum joint limits for all the six axis of the robot. The three first values have to be given in meter and the others in radian.

Parameters:
limitMin: visp._visp.core.ColVector

The minimum joint limits are given in a vector of size 6. The three first values have to be given in meter and the others in radian.

limitMax: visp._visp.core.ColVector

The maximum joint limits are given in a vector of size 6. The three first values have to be given in meter and the others in radian.

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.SimulatorAfma6, frame: visp._visp.robot.Robot.ControlFrameType, q: visp._visp.core.ColVector) -> None

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

  3. setPosition(self: visp._visp.robot.SimulatorAfma6, 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/vpSimulatorAfma6.h>

int main()
{
  vpColVector q;
  vpSimulatorAfma6 robot;

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

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, vel: float) None
setRobotState(self, newState: visp._visp.robot.Robot.RobotStateType) visp._visp.robot.Robot.RobotStateType
setSamplingTime(*args, **kwargs)

Overloaded function.

  1. setSamplingTime(self: visp._visp.robot.RobotWireFrameSimulator, delta_t: float) -> None

Set the sampling time.

Since the wireframe simulator is threaded, the sampling time is set to vpTime::getMinTimeForUsleepCall() / 1000 seconds.

Parameters:
delta_t

Sampling time in second used to compute the robot displacement from the velocity applied to the robot during this time.

  1. setSamplingTime(self: visp._visp.robot.RobotSimulator, delta_t: float) -> None

Set the sampling time.

Parameters:
delta_t

Sampling time in second used to compute the robot displacement from the velocity applied to the robot during this time.

setSingularityManagement(self, sm: bool) None

Set the parameter which enable or disable the singularity management.

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

Activates extra printings when the robot reaches joint limits…

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.

set_fMo(self, fMo_: visp._visp.core.HomogeneousMatrix) None

Set the pose between the object and the fixed world frame.

Parameters:
fMo_: visp._visp.core.HomogeneousMatrix

The pose between the object and the fixed world frame.

stopMotion(self) None

Stop the robot.