Visual Servoing Platform  version 3.6.1 under development (2024-07-27)
vpRobotFranka Class Reference

#include <visp3/robot/vpRobotFranka.h>

+ Inheritance diagram for vpRobotFranka:

Public Types

enum  vpRobotStateType {
  STATE_STOP , STATE_VELOCITY_CONTROL , STATE_POSITION_CONTROL , STATE_ACCELERATION_CONTROL ,
  STATE_FORCE_TORQUE_CONTROL
}
 
enum  vpControlFrameType {
  REFERENCE_FRAME , ARTICULAR_FRAME , JOINT_STATE = ARTICULAR_FRAME , END_EFFECTOR_FRAME ,
  CAMERA_FRAME , TOOL_FRAME = CAMERA_FRAME , MIXT_FRAME
}
 

Public Member Functions

 vpRobotFranka ()
 
 vpRobotFranka (const std::string &franka_address, franka::RealtimeConfig realtime_config=franka::RealtimeConfig::kEnforce)
 
virtual ~vpRobotFranka ()
 
void connect (const std::string &franka_address, franka::RealtimeConfig realtime_config=franka::RealtimeConfig::kEnforce)
 
vpHomogeneousMatrix get_fMe (const vpColVector &q)
 
vpHomogeneousMatrix get_fMc (const vpColVector &q)
 
vpHomogeneousMatrix get_eMc () const
 
void get_eJe (vpMatrix &eJe) VP_OVERRIDE
 
void get_eJe (const vpColVector &q, vpMatrix &eJe)
 
void get_fJe (vpMatrix &fJe) VP_OVERRIDE
 
void get_fJe (const vpColVector &q, vpMatrix &fJe)
 
void getCoriolis (vpColVector &coriolis)
 
void getForceTorque (const vpRobot::vpControlFrameType frame, vpColVector &force)
 
void getGravity (vpColVector &gravity)
 
franka::RobotState getRobotInternalState ()
 
franka::Gripper * getGripperHandler ()
 
franka::Robot * getHandler ()
 
vpColVector getJointMin () const
 
vpColVector getJointMax () const
 
void getMass (vpMatrix &mass)
 
void getPosition (const vpRobot::vpControlFrameType frame, vpColVector &position) VP_OVERRIDE
 
void getPosition (const vpRobot::vpControlFrameType frame, vpPoseVector &pose)
 
void getVelocity (const vpRobot::vpControlFrameType frame, vpColVector &d_position)
 
int gripperClose ()
 
int gripperGrasp (double grasping_width, double force=60.)
 
int gripperGrasp (double grasping_width, double speed, double force)
 
void gripperHoming ()
 
int gripperMove (double width)
 
int gripperOpen ()
 
void gripperRelease ()
 
void move (const std::string &filename, double velocity_percentage=10.)
 
bool readPosFile (const std::string &filename, vpColVector &q)
 
bool savePosFile (const std::string &filename, const vpColVector &q)
 
void set_eMc (const vpHomogeneousMatrix &eMc)
 
void setForceTorque (const vpRobot::vpControlFrameType frame, const vpColVector &ft, const double &filter_gain=0.1, const bool &activate_pi_controller=false)
 
void setLogFolder (const std::string &folder)
 
void setPosition (const vpRobot::vpControlFrameType frame, const vpColVector &position) VP_OVERRIDE
 
void setPositioningVelocity (double velocity)
 
vpRobot::vpRobotStateType setRobotState (vpRobot::vpRobotStateType newState)
 
void setVelocity (const vpRobot::vpControlFrameType frame, const vpColVector &vel) VP_OVERRIDE
 
void stopMotion ()
 
Inherited functionalities from vpRobot
double getMaxTranslationVelocity (void) const
 
double getMaxRotationVelocity (void) const
 
int getNDof () const
 
vpColVector getPosition (const vpRobot::vpControlFrameType frame)
 
virtual vpRobotStateType getRobotState (void) const
 
void setMaxRotationVelocity (double maxVr)
 
void setMaxTranslationVelocity (double maxVt)
 
void setVerbose (bool verbose)
 

Static Public Member Functions

Static Public Member Functions inherited from vpRobot
static vpColVector saturateVelocities (const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
 

Protected Member Functions

Protected Member Functions Inherited from vpRobot
vpControlFrameType setRobotFrame (vpRobot::vpControlFrameType newFrame)
 
vpControlFrameType getRobotFrame (void) const
 

Protected Attributes

double maxTranslationVelocity
 
double maxRotationVelocity
 
int nDof
 
vpMatrix eJe
 
int eJeAvailable
 
vpMatrix fJe
 
int fJeAvailable
 
int areJointLimitsAvailable
 
double * qmin
 
double * qmax
 
bool verbose_
 

Static Protected Attributes

static const double maxTranslationVelocityDefault = 0.2
 
static const double maxRotationVelocityDefault = 0.7
 

Detailed Description

This class is a wrapper over the libfranka component part of the Franka Control Interface (FCI).

Before using vpRobotFranka follow the installation instructions to install libfranka. We suggest to build libfranka from source if you are not using ROS.

Moreover, you need also to setup a real-time kernel following these instructions.

Up to now, this class provides the following capabilities to:

What is not implemented is:

  • move to a given cartesian end-effector position
  • gripper controller
  • force/torque feedback and control

Known issues:

  • sometimes the joint to joint trajectory generator provided by Franka complains about discontinuities.

We provide also the getHandler() function that allows to access to the robot handler and call the native libfranka API functionalities:

vpRobotFranka robot("192.168.1.1");
franka::Robot *handler = robot.getHandler();
// Get end-effector cartesian position
std::array<double, 16> pose = handler->readOnce().O_T_EE;
See also
Tutorial: PBVS with Panda 7-dof robot from Franka Emika
Tutorial: IBVS with Panda 7-dof robot from Franka Emika
Examples
frankaGripper.cpp, frankaMoveToPosition.cpp, frankaSavePosition.cpp, servoFrankaIBVS.cpp, servoFrankaPBVS.cpp, testFrankaCartForceTorque-2.cpp, testFrankaCartForceTorque.cpp, testFrankaCartVelocity-2.cpp, testFrankaCartVelocity-3.cpp, testFrankaCartVelocity.cpp, testFrankaGetPose.cpp, testFrankaJointPosition.cpp, testFrankaJointTorque.cpp, testFrankaJointVelocity-2.cpp, testFrankaJointVelocity-3.cpp, testFrankaJointVelocity.cpp, and testFrankaJointVelocityLimits.cpp.

Definition at line 222 of file vpRobotFranka.h.

Member Enumeration Documentation

◆ vpControlFrameType

Robot control frames.

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

Definition at line 76 of file vpRobot.h.

◆ vpRobotStateType

enum vpRobot::vpRobotStateType
inherited

Robot control states.

Enumerator
STATE_STOP 

Stops robot motion especially in velocity and acceleration control.

STATE_VELOCITY_CONTROL 

Initialize the velocity controller.

STATE_POSITION_CONTROL 

Initialize the position controller.

STATE_ACCELERATION_CONTROL 

Initialize the acceleration controller.

STATE_FORCE_TORQUE_CONTROL 

Initialize the force/torque controller.

Definition at line 64 of file vpRobot.h.

Constructor & Destructor Documentation

◆ vpRobotFranka() [1/2]

BEGIN_VISP_NAMESPACE vpRobotFranka::vpRobotFranka ( )

Default constructor.

Definition at line 54 of file vpRobotFranka.cpp.

◆ vpRobotFranka() [2/2]

vpRobotFranka::vpRobotFranka ( const std::string &  franka_address,
franka::RealtimeConfig  realtime_config = franka::RealtimeConfig::kEnforce 
)

Establishes a connection with the robot.

Parameters
[in]franka_addressIP/hostname of the robot.
[in]realtime_configIf set to kEnforce, an exception will be thrown if realtime priority cannot be set when required. Setting realtime_config to kIgnore disables this behavior.

Definition at line 70 of file vpRobotFranka.cpp.

References connect().

◆ ~vpRobotFranka()

vpRobotFranka::~vpRobotFranka ( )
virtual

Destructor.

Definition at line 99 of file vpRobotFranka.cpp.

References setRobotState(), and vpRobot::STATE_STOP.

Member Function Documentation

◆ connect()

void vpRobotFranka::connect ( const std::string &  franka_address,
franka::RealtimeConfig  realtime_config = franka::RealtimeConfig::kEnforce 
)

Establishes a connection with the robot and set default behavior.

Parameters
[in]franka_addressIP/hostname of the robot.
[in]realtime_configIf set to kEnforce, an exception will be thrown if realtime priority cannot be set when required. Setting realtime_config to kIgnore disables this behavior.

Definition at line 123 of file vpRobotFranka.cpp.

References vpException::fatalError.

Referenced by vpRobotFranka().

◆ get_eJe() [1/2]

void vpRobotFranka::get_eJe ( const vpColVector q,
vpMatrix eJe_ 
)

Gets the robot Jacobian in the end-effector frame relative to the end-effector frame represented as a 6x7 matrix in row-major format and computed from the robot current joint position.

Parameters
[in]q: 7-dim vector corresponding to the robot joint position [rad].
[out]eJe_: Body Jacobian expressed in the end-effector frame.

Definition at line 499 of file vpRobotFranka.cpp.

References vpException::fatalError, getRobotInternalState(), and vpArray2D< Type >::resize().

◆ get_eJe() [2/2]

void vpRobotFranka::get_eJe ( vpMatrix eJe_)
virtual

Gets the robot Jacobian in the end-effector frame relative to the end-effector frame represented as a 6x7 matrix in row-major format and computed from the robot current joint position.

Parameters
[out]eJe_: Body Jacobian expressed in the end-effector frame.

Implements vpRobot.

Definition at line 476 of file vpRobotFranka.cpp.

References vpException::fatalError, getRobotInternalState(), and vpArray2D< Type >::resize().

◆ get_eMc()

vpHomogeneousMatrix vpRobotFranka::get_eMc ( ) const

Return the $ ^{e}{\bf M}_c$ homogeneous transformation that gives the position of the camera frame (or in general of any tool frame) in the robot end-effector frame.

By default, this transformation is set to identity, meaning that the camera (or tool) frame is located on the end-effector.

To change the position of the camera (or tool) frame on the end-effector frame, use set_eMc().

Definition at line 999 of file vpRobotFranka.cpp.

Referenced by getForceTorque().

◆ get_fJe() [1/2]

void vpRobotFranka::get_fJe ( const vpColVector q,
vpMatrix fJe_ 
)

Gets the robot Jacobian in the end-effector frame relative to the base frame represented as a 6x7 matrix in row-major format and computed from the robot joint position given as input.

Parameters
[in]q: 7-dim vector corresponding to the robot joint position [rad].
[out]fJe_: Zero Jacobian expressed in the base frame.

Definition at line 550 of file vpRobotFranka.cpp.

References vpException::fatalError, getRobotInternalState(), vpArray2D< Type >::resize(), and vpArray2D< Type >::size().

◆ get_fJe() [2/2]

void vpRobotFranka::get_fJe ( vpMatrix fJe_)
virtual

Gets the robot Jacobian in the end-effector frame relative to the base frame represented as a 6x7 matrix in row-major format and computed from the robot current joint position.

Parameters
[out]fJe_: Zero Jacobian expressed in the base frame.

Implements vpRobot.

Definition at line 527 of file vpRobotFranka.cpp.

References vpException::fatalError, getRobotInternalState(), and vpArray2D< Type >::resize().

◆ get_fMc()

vpHomogeneousMatrix vpRobotFranka::get_fMc ( const vpColVector q)

Given the joint position of the robot, computes the forward kinematics (direct geometric model) as an homogeneous matrix ${^f}{\bf M}_c$ that gives the position of the camera frame (or in general of any tool attached to the robot) in the robot base frame.

By default, the transformation $^{e}{\bf M}_c$ that corresponds to the transformation between the end-effector and the camera (or tool) frame is set to identity, meaning that the camera (or tool) frame is located on the end-effector.

To change the position of the camera (or tool) frame, use set_eMc().

Parameters
[in]q: Joint position as a 7-dim vector.
Returns
Position of the camera frame (or tool frame) in the robot base frame.

Definition at line 422 of file vpRobotFranka.cpp.

References get_fMe().

Referenced by getPosition().

◆ get_fMe()

vpHomogeneousMatrix vpRobotFranka::get_fMe ( const vpColVector q)

Given the joint position of the robot, computes the forward kinematics (direct geometric model) as an homogeneous matrix ${^f}{\bf M}_e$ that gives the position of the end-effector in the robot base frame.

Parameters
[in]q: Joint position as a 7-dim vector.
Returns
Position of the end-effector in the robot base frame.

Definition at line 381 of file vpRobotFranka.cpp.

References vpException::fatalError, getRobotInternalState(), and vpArray2D< Type >::size().

Referenced by get_fMc(), and getPosition().

◆ getCoriolis()

void vpRobotFranka::getCoriolis ( vpColVector coriolis)

Get the Coriolis force vector (state-space equation) calculated from the current robot state: $ c= C \times dq$, in $[Nm]$.

Parameters
[out]coriolis: Coriolis force vector.

Definition at line 310 of file vpRobotFranka.cpp.

References vpException::fatalError, getRobotInternalState(), and vpColVector::resize().

◆ getForceTorque()

void vpRobotFranka::getForceTorque ( const vpRobot::vpControlFrameType  frame,
vpColVector force 
)

Get robot force torque.

Parameters
[in]frame: Type of forces and torques to retrieve. Admissible values are:
[out]force: Measured forced and torques.

Definition at line 227 of file vpRobotFranka.cpp.

References vpRobot::END_EFFECTOR_FRAME, vpException::fatalError, get_eMc(), getRobotInternalState(), vpHomogeneousMatrix::inverse(), vpRobot::JOINT_STATE, vpColVector::resize(), and vpRobot::TOOL_FRAME.

◆ getGravity()

void vpRobotFranka::getGravity ( vpColVector gravity)

Get the gravity vector calculated form the current robot state. Unit: $[Nm]$.

Parameters
[out]gravity: Gravity vector

Definition at line 332 of file vpRobotFranka.cpp.

References vpException::fatalError, getRobotInternalState(), and vpColVector::resize().

◆ getGripperHandler()

franka::Gripper* vpRobotFranka::getGripperHandler ( )
inline

Get gripper handler to access native libfranka functions.

Returns
Robot handler if it exists, an exception otherwise.

Definition at line 299 of file vpRobotFranka.h.

References vpException::fatalError.

◆ getHandler()

franka::Robot* vpRobotFranka::getHandler ( )
inline

Get robot handler to access native libfranka functions.

Returns
Robot handler if it exists, an exception otherwise.

Definition at line 313 of file vpRobotFranka.h.

References vpException::fatalError.

◆ getJointMax()

vpColVector vpRobotFranka::getJointMax ( ) const

Gets maximum joint values.

Returns
A 7-dimension vector that contains the maximum joint values for the 7 dof. All the values are expressed in radians.

Definition at line 980 of file vpRobotFranka.cpp.

◆ getJointMin()

vpColVector vpRobotFranka::getJointMin ( ) const

Gets minimal joint values.

Returns
A 7-dimension vector that contains the minimal joint values for the 7 dof. All the values are expressed in radians.

Definition at line 967 of file vpRobotFranka.cpp.

◆ getMass()

void vpRobotFranka::getMass ( vpMatrix mass)

Get the 7x7 mass matrix. Unit: $[kg \times m^2]$.

Parameters
[out]mass: 7x7 mass matrix, row-major.

Definition at line 354 of file vpRobotFranka.cpp.

References vpException::fatalError, getRobotInternalState(), and vpArray2D< Type >::resize().

◆ getMaxRotationVelocity()

◆ getMaxTranslationVelocity()

◆ getNDof()

int vpRobot::getNDof ( ) const
inlineinherited

Return robot degrees of freedom number.

Examples
servoPololuPtuPoint2DJointVelocity.cpp.

Definition at line 145 of file vpRobot.h.

◆ getPosition() [1/3]

vpColVector vpRobot::getPosition ( const vpRobot::vpControlFrameType  frame)
inherited

Return the current robot position in the specified frame.

Definition at line 217 of file vpRobot.cpp.

References vpRobot::getPosition().

◆ getPosition() [2/3]

void vpRobotFranka::getPosition ( const vpRobot::vpControlFrameType  frame,
vpColVector position 
)
virtual

Get robot position.

Parameters
[in]frame: Type of position to retrieve. Admissible values are:
[out]position: Robot position. When joint position is asked this vector is 7-dim. Otherwise for a cartesian position this vector is 6-dim. Its content is similar to a vpPoseVector, with first the 3 tranlations in meter and then the 3 orientations in radian as a $\theta {\bf u}$ vector (see vpThetaUVector).

If you want to get a cartesian position, use rather getPosition(const vpRobot::vpControlFrameType, vpPoseVector &)

Implements vpRobot.

Definition at line 176 of file vpRobotFranka.cpp.

References vpRobot::END_EFFECTOR_FRAME, vpException::fatalError, get_fMc(), get_fMe(), getRobotInternalState(), vpRobot::JOINT_STATE, vpColVector::resize(), and vpRobot::TOOL_FRAME.

◆ getPosition() [3/3]

void vpRobotFranka::getPosition ( const vpRobot::vpControlFrameType  frame,
vpPoseVector pose 
)

Get robot cartesian position.

Parameters
[in]frame: Type of cartesian position to retrieve. Admissible values are:
[out]pose: Robot cartesian position. This vector is 6-dim with first the 3 tranlations in meter and then the 3 orientations in radian as a $\theta {\bf u}$ vector (see vpThetaUVector).

Definition at line 437 of file vpRobotFranka.cpp.

References vpPoseVector::build(), vpRobot::END_EFFECTOR_FRAME, vpException::fatalError, getRobotInternalState(), vpRobot::JOINT_STATE, and vpRobot::TOOL_FRAME.

◆ getRobotFrame()

vpControlFrameType vpRobot::getRobotFrame ( void  ) const
inlineprotectedinherited

◆ getRobotInternalState()

franka::RobotState vpRobotFranka::getRobotInternalState ( )

◆ getRobotState()

virtual vpRobotStateType vpRobot::getRobotState ( void  ) const
inlinevirtualinherited

Definition at line 155 of file vpRobot.h.

Referenced by vpRobotBiclops::getPosition(), vpRobotBiclops::getVelocity(), vpRobotCamera::setPosition(), vpSimulatorCamera::setPosition(), vpRobotAfma4::setPosition(), vpRobotAfma6::setPosition(), setPosition(), vpRobotUniversalRobots::setPosition(), vpRobotViper650::setPosition(), vpRobotViper850::setPosition(), vpRobotBiclops::setPosition(), vpRobotPololuPtu::setPosition(), vpRobotPtu46::setPosition(), vpSimulatorAfma6::setPosition(), vpSimulatorViper850::setPosition(), vpRobotBiclops::setRobotState(), vpRobotPololuPtu::setRobotState(), vpSimulatorAfma6::setRobotState(), vpSimulatorViper850::setRobotState(), vpRobotAfma4::setRobotState(), vpRobotAfma6::setRobotState(), vpRobotFlirPtu::setRobotState(), setRobotState(), vpRobotPtu46::setRobotState(), vpRobotUniversalRobots::setRobotState(), vpRobotViper650::setRobotState(), vpRobotViper850::setRobotState(), vpRobotBiclops::setVelocity(), vpRobotPololuPtu::setVelocity(), vpRobotPtu46::setVelocity(), vpRobotCamera::setVelocity(), vpRobotFlirPtu::setVelocity(), setVelocity(), vpRobotKinova::setVelocity(), vpRobotTemplate::setVelocity(), vpRobotUniversalRobots::setVelocity(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotViper650::setVelocity(), vpRobotViper850::setVelocity(), vpSimulatorAfma6::setVelocity(), vpSimulatorViper850::setVelocity(), vpRobotFlirPtu::stopMotion(), stopMotion(), vpRobotViper650::stopMotion(), vpRobotViper850::stopMotion(), vpSimulatorAfma6::stopMotion(), and vpSimulatorViper850::stopMotion().

◆ getVelocity()

void vpRobotFranka::getVelocity ( const vpRobot::vpControlFrameType  frame,
vpColVector d_position 
)

Get robot velocity.

Parameters
[in]frame: Type of velocity to retrieve. Admissible values are:
[out]d_position: Robot velocity. When joints velocity is asked this vector is 7-dim. Otherwise for a cartesian velocity this vector is 6-dim. Its content is similar to a vpPoseVector, with first the 3 tranlations in meter and then the 3 orientations in radian as a $\theta {\bf u}$ vector (see vpThetaUVector).
Warning
For the moment, cartesian velocities measurement in vpRobot::END_EFFECTOR_FRAME, vpRobot::CAMERA_FRAME, vpRobot::TOOL_FRAME are not implemented.

Definition at line 281 of file vpRobotFranka.cpp.

References vpException::fatalError, getRobotInternalState(), vpRobot::JOINT_STATE, and vpColVector::resize().

◆ gripperClose()

int vpRobotFranka::gripperClose ( )

Closes the gripper.

Returns
EXIT_SUCCESS if the success, EXIT_FAILURE otherwise.
See also
gripperHoming(), gripperGrasp(), gripperRelease(), gripperOpen()

Definition at line 1254 of file vpRobotFranka.cpp.

References gripperMove().

◆ gripperGrasp() [1/2]

int vpRobotFranka::gripperGrasp ( double  grasping_width,
double  force = 60. 
)

Grasp an object that has a given width.

An object is considered grasped if the distance d between the gripper fingers satisfies grasping_width - 0.005 < d < grasping_width + 0.005.

Parameters
[in]grasping_width: Size of the object to grasp. [m]
[in]force: Grasping force. [N]
Returns
EXIT_SUCCESS if grasping succeed, EXIT_FAILURE otherwise.
See also
gripperHoming(), gripperOpen(), gripperRelease()

Definition at line 1310 of file vpRobotFranka.cpp.

◆ gripperGrasp() [2/2]

int vpRobotFranka::gripperGrasp ( double  grasping_width,
double  speed,
double  force 
)

Grasp an object that has a given width.

An object is considered grasped if the distance d between the gripper fingers satisfies grasping_width - 0.005 < d < grasping_width + 0.005.

Parameters
[in]grasping_width: Size of the object to grasp. [m]
[in]speed: Closing speed. [m/s]
[in]force: Grasping force. [N]
Returns
EXIT_SUCCESS if grasping succeed, EXIT_FAILURE otherwise.
See also
gripperHoming(), gripperOpen(), gripperRelease()

Definition at line 1330 of file vpRobotFranka.cpp.

◆ gripperHoming()

void vpRobotFranka::gripperHoming ( )

Performing a gripper homing.

See also
gripperGrasp(), gripperMove(), gripperRelease()

Definition at line 1205 of file vpRobotFranka.cpp.

References vpException::fatalError.

◆ gripperMove()

int vpRobotFranka::gripperMove ( double  width)

Moves the gripper fingers to a specified width.

Parameters
[in]width: Intended opening width. [m]
Returns
EXIT_SUCCESS if the success, EXIT_FAILURE otherwise.
See also
gripperHoming(), gripperGrasp(), gripperRelease()

Definition at line 1225 of file vpRobotFranka.cpp.

References vpException::fatalError.

Referenced by gripperClose().

◆ gripperOpen()

int vpRobotFranka::gripperOpen ( )

Closes the gripper.

Returns
EXIT_SUCCESS if the success, EXIT_FAILURE otherwise.
See also
gripperHoming(), gripperGrasp(), gripperRelease(), gripperOpen()

Definition at line 1264 of file vpRobotFranka.cpp.

References vpException::fatalError.

◆ gripperRelease()

void vpRobotFranka::gripperRelease ( )

Release an object that is grasped.

See also
gripperHoming(), gripperMove(), gripperRelease()

Definition at line 1285 of file vpRobotFranka.cpp.

References vpException::fatalError.

◆ move()

void vpRobotFranka::move ( const std::string &  filename,
double  velocity_percentage = 10. 
)

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

Parameters
filename: File containing a joint position to reach.
velocity_percentage: Velocity percentage. Values in range [1, 100].

Definition at line 1024 of file vpRobotFranka.cpp.

References vpRobot::JOINT_STATE, readPosFile(), setPosition(), setPositioningVelocity(), setRobotState(), and vpRobot::STATE_POSITION_CONTROL.

◆ readPosFile()

bool vpRobotFranka::readPosFile ( const std::string &  filename,
vpColVector q 
)

Read joint positions in a specific Franka position file.

This position file has to start with a header. The seven joint positions are given after the "R:" keyword and are 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:

#PANDA - Joint position file
#
# R: q1 q2 q3 q4 q5 q6 q7
# with joint positions q1 to q7 expressed in degrees
#
R: 0.1 0.3 -0.25 -80.5 80 0 0
Parameters
[in]filename: Name of the position file to read.
[out]q: 7-dim joint positions: q1 q2 q3 q4 q5 q6 q7 with values expressed in radians.
Returns
true if the positions were successfully readen in the file. false, if an error occurs.

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

vpColVector q; // Joint position
robot.readPosFile("myposition.pos", q); // Set the joint position from the file
robot.setPositioningVelocity(5); // Positioning velocity set to 5%
robot.setPosition(vpRobot::ARTICULAR_FRAME, q); // Move to the joint position
@ ARTICULAR_FRAME
Definition: vpRobot.h:80
@ STATE_POSITION_CONTROL
Initialize the position controller.
Definition: vpRobot.h:68
See also
savePosFile(), move()

Definition at line 1078 of file vpRobotFranka.cpp.

References vpMath::rad(), vpColVector::resize(), and vpIoTools::splitChain().

Referenced by move().

◆ saturateVelocities()

vpColVector vpRobot::saturateVelocities ( const vpColVector v_in,
const vpColVector v_max,
bool  verbose = false 
)
staticinherited

Saturate velocities.

Parameters
v_in: Vector of input velocities to saturate. Translation velocities should be expressed in m/s while rotation velocities in rad/s.
v_max: Vector of maximal allowed velocities. Maximal translation velocities should be expressed in m/s while maximal rotation velocities in rad/s.
verbose: Print a message indicating which axis causes the saturation.
Returns
Saturated velocities.
Exceptions
vpRobotException::dimensionError: If the input vectors have different dimensions.

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>
#ifdef ENABLE_VISP_NAMESPACE
using namespace VISP_NAMESPACE_NAME;
#endif
int main()
{
// Set a velocity skew vector
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;
}
vpRowVector t() const
static vpColVector saturateVelocities(const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
Definition: vpRobot.cpp:164

Definition at line 164 of file vpRobot.cpp.

References vpException::dimensionError, and vpArray2D< Type >::size().

Referenced by vpRobotCamera::setVelocity(), vpRobotFlirPtu::setVelocity(), setVelocity(), vpRobotKinova::setVelocity(), vpRobotPioneer::setVelocity(), vpRobotTemplate::setVelocity(), vpRobotUniversalRobots::setVelocity(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotViper650::setVelocity(), and vpRobotViper850::setVelocity().

◆ savePosFile()

bool vpRobotFranka::savePosFile ( const std::string &  filename,
const vpColVector q 
)

Save joint positions in a specific Panda 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.

Parameters
filename: Name of the position file to create.
q: Joint positions vector to save in the filename with values expressed in radians.
Warning
The joint rotations written in the file are converted in degrees to be more representative for the user.
Returns
true if the positions were successfully saved in the file. false, if an error occurs.
See also
readPosFile()

Definition at line 1161 of file vpRobotFranka.cpp.

References vpMath::deg().

◆ set_eMc()

void vpRobotFranka::set_eMc ( const vpHomogeneousMatrix eMc)

Set the $ ^{e}{\bf M}_c$ homogeneous transformation that gives the position of the camera frame (or in general of any tool frame) in the robot end-effector frame.

By default, this transformation is set to identity, meaning that the camera (or tool) frame is located on the end-effector.

This transformation has to be set before controlling the robot cartesian velocity in the camera frame or getting the position of the robot in the camera frame.

Parameters
[in]eMc: End-effector to camera frame transformation.

Definition at line 1013 of file vpRobotFranka.cpp.

◆ setForceTorque()

void vpRobotFranka::setForceTorque ( const vpRobot::vpControlFrameType  frame,
const vpColVector ft,
const double &  filter_gain = 0.1,
const bool &  activate_pi_controller = false 
)

◆ setLogFolder()

void vpRobotFranka::setLogFolder ( const std::string &  folder)

Set the folder or directory used to record logs at 1Kz when setVelocity() is used. By default the log folder is empty.

When the log folder is empty, logs are not created.

Parameters
[in]folder: A path to a folder that will contain a basket of log files. If the folder doesn't exist it will be created recursively.

Definition at line 588 of file vpRobotFranka.cpp.

References vpIoTools::checkDirectory(), vpException::fatalError, and vpIoTools::makeDirectory().

◆ setMaxRotationVelocity()

void vpRobot::setMaxRotationVelocity ( double  w_max)
inherited

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

Parameters
w_max: Maximum rotational velocity expressed in rad/s.
Examples
servoMomentPoints.cpp, servoSimu4Points.cpp, servoSimuSphere.cpp, testFeatureSegment.cpp, testFrankaJointVelocityLimits.cpp, and testRobotFlirPtu.cpp.

Definition at line 261 of file vpRobot.cpp.

References vpRobot::maxRotationVelocity.

Referenced by vpRobotViper650::setMaxRotationVelocity(), vpRobotViper850::setMaxRotationVelocity(), and vpSimulatorAfma6::setPosition().

◆ setMaxTranslationVelocity()

void vpRobot::setMaxTranslationVelocity ( double  v_max)
inherited

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

Parameters
v_max: Maximum translation velocity expressed in m/s.
Examples
servoMomentPoints.cpp, servoSimu4Points.cpp, servoSimuSphere.cpp, simulateCircle2DCamVelocity.cpp, simulateFourPoints2DCartesianCamVelocity.cpp, simulateFourPoints2DPolarCamVelocity.cpp, and testFeatureSegment.cpp.

Definition at line 240 of file vpRobot.cpp.

References vpRobot::maxTranslationVelocity.

Referenced by vpSimulatorAfma6::setPosition().

◆ setPosition()

void vpRobotFranka::setPosition ( const vpRobot::vpControlFrameType  frame,
const vpColVector position 
)
virtual

Set robot position. This function is blocking; it returns when the desired position is reached.

Parameters
[in]frame: The only possible value is vpRobot::JOINT_STATE. Other values are not implemented.
[in]position: This is a 7-dim vector that corresponds to the robot joint positions expressed in rad.

Implements vpRobot.

Definition at line 613 of file vpRobotFranka.cpp.

References vpException::fatalError, vpException::functionNotImplementedError, vpRobot::getRobotState(), vpRobot::JOINT_STATE, setRobotState(), and vpRobot::STATE_POSITION_CONTROL.

Referenced by move().

◆ setPositioningVelocity()

void vpRobotFranka::setPositioningVelocity ( double  velocity)

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

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

Definition at line 663 of file vpRobotFranka.cpp.

Referenced by move().

◆ setRobotFrame()

◆ setRobotState()

vpRobot::vpRobotStateType vpRobotFranka::setRobotState ( vpRobot::vpRobotStateType  newState)
virtual

Change the robot state.

Parameters
[in]newState: New requested robot state.

Reimplemented from vpRobot.

Definition at line 671 of file vpRobotFranka.cpp.

References vpRobot::getRobotState(), vpRobot::setRobotState(), vpRobot::STATE_FORCE_TORQUE_CONTROL, vpRobot::STATE_POSITION_CONTROL, vpRobot::STATE_STOP, and vpRobot::STATE_VELOCITY_CONTROL.

Referenced by move(), setPosition(), stopMotion(), and ~vpRobotFranka().

◆ setVelocity()

void vpRobotFranka::setVelocity ( const vpRobot::vpControlFrameType  frame,
const vpColVector vel 
)
virtual

Apply a velocity to the robot.

Parameters
[in]frame: Control frame in which the velocity is expressed. Velocities could be expressed as joint velocities, cartesian velocity twist expressed in the robot reference frame, in the end-effector frame or in the camera or tool frame.
[in]vel: Velocity vector. Translation velocities are expressed in m/s while rotation velocities in rad/s. The size of this vector is always 6 for a cartesian velocity skew, and 7 for joint velocities.
  • When joint velocities have to be applied, frame should be set to vpRobot::JOINT_STATE, and $ vel = [\dot{q}_1, \dot{q}_2, \dot{q}_3, \dot{q}_4, \dot{q}_5, \dot{q}_6]^t, \dot{q}_7]^T $ correspond to joint velocities in rad/s.
  • When cartesian velocities have to be applied in the reference frame (or in a frame also called fixed frame in ViSP), frame should be set to vpRobot::REFERENCE_FRAME, $ vel = [^{f} v_x, ^{f} v_y, ^{f} v_z, ^{f} \omega_x, ^{f} \omega_y, ^{f} \omega_z]^T $ is a velocity twist vector corresponding to the velocity of the origin of the camera frame (or tool frame) expressed in the reference frame, with translations velocities $ ^{f} v_x, ^{f} v_y, ^{f} v_z $ in m/s and rotation velocities $ ^{f}\omega_x, ^{f} \omega_y, ^{f} \omega_z $ in rad/s.
  • When cartesian velocities have to be applied in the end-effector frame, frame should be set to vpRobot::END_EFFECTOR_FRAME, $ vel = [^{e} v_x, ^{e} v_y, ^{e} v_z, ^{e} \omega_x, ^{e} \omega_y, ^{e} \omega_z]^T $ is a velocity twist vector corresponding to the velocity of the origin of the end-effector frame expressed in the end-effector frame, with translations velocities $ ^{e} v_x, ^{e} v_y, ^{e} v_z $ in m/s and rotation velocities $ ^{e}\omega_x, ^{e} \omega_y, ^{e} \omega_z $ in rad/s.
  • When cartesian velocities have to be applied in the camera frame or more generally in a tool frame, frame should be set to vpRobot::CAMERA_FRAME or vpRobot::TOOL_FRAME, $ vel = [^{c} v_x, ^{c} v_y, ^{c} v_z, ^{c} \omega_x, ^{c} \omega_y, ^{c} \omega_z]^T $ is a velocity twist vector corresponding to the velocity of the origin of the camera (or tool frame) frame expressed in the camera (or tool frame), with translations velocities $ ^{c} v_x, ^{c} v_y, ^{c} v_z $ in m/s and rotation velocities $ ^{c}\omega_x, ^{c} \omega_y, ^{c} \omega_z $ in rad/s.
Exceptions
vpRobotException::wrongStateError: If a the robot is not configured to handle a velocity. The robot can handle a velocity only if the velocity control mode is set. For that, call setRobotState( vpRobot::STATE_VELOCITY_CONTROL) before setVelocity().
Warning
Velocities could be saturated if one of them exceed the maximal authorized speed (see vpRobot::maxTranslationVelocity and vpRobot::maxRotationVelocity). To change these values use setMaxTranslationVelocity() and setMaxRotationVelocity().

Implements vpRobot.

Definition at line 818 of file vpRobotFranka.cpp.

References vpRobot::END_EFFECTOR_FRAME, vpRobot::getMaxRotationVelocity(), vpRobot::getMaxTranslationVelocity(), vpRobot::getRobotState(), vpRobot::JOINT_STATE, vpRobot::MIXT_FRAME, vpRobot::REFERENCE_FRAME, vpRobot::saturateVelocities(), vpArray2D< Type >::size(), vpRobot::STATE_VELOCITY_CONTROL, vpRobot::TOOL_FRAME, and vpRobotException::wrongStateError.

Referenced by stopMotion().

◆ setVerbose()

◆ stopMotion()

void vpRobotFranka::stopMotion ( void  )

Stop the robot when it is controlled in velocity and set the robot state to vpRobot::STATE_STOP.

Exceptions
vpRobotException::lowLevelError: If the low level controller returns an error during robot stopping.

Definition at line 1190 of file vpRobotFranka.cpp.

References vpRobot::getRobotState(), vpRobot::JOINT_STATE, setRobotState(), setVelocity(), vpRobot::STATE_STOP, and vpRobot::STATE_VELOCITY_CONTROL.

Member Data Documentation

◆ areJointLimitsAvailable

int vpRobot::areJointLimitsAvailable
protectedinherited

Definition at line 114 of file vpRobot.h.

Referenced by vpRobot::operator=().

◆ eJe

◆ eJeAvailable

int vpRobot::eJeAvailable
protectedinherited

is the robot Jacobian expressed in the end-effector frame available

Definition at line 108 of file vpRobot.h.

Referenced by vpRobot::operator=().

◆ fJe

◆ fJeAvailable

int vpRobot::fJeAvailable
protectedinherited

is the robot Jacobian expressed in the robot reference frame available

Definition at line 112 of file vpRobot.h.

Referenced by vpRobot::operator=().

◆ maxRotationVelocity

◆ maxRotationVelocityDefault

const double vpRobot::maxRotationVelocityDefault = 0.7
staticprotectedinherited

Definition at line 101 of file vpRobot.h.

Referenced by vpRobotFlirPtu::init(), vpRobotKinova::init(), and vpRobotTemplate::init().

◆ maxTranslationVelocity

double vpRobot::maxTranslationVelocity
protectedinherited

◆ maxTranslationVelocityDefault

BEGIN_VISP_NAMESPACE const double vpRobot::maxTranslationVelocityDefault = 0.2
staticprotectedinherited

Definition at line 99 of file vpRobot.h.

Referenced by vpRobotFlirPtu::init(), vpRobotKinova::init(), and vpRobotTemplate::init().

◆ nDof

◆ qmax

double* vpRobot::qmax
protectedinherited

Definition at line 116 of file vpRobot.h.

Referenced by vpRobot::operator=(), and vpRobot::~vpRobot().

◆ qmin

double* vpRobot::qmin
protectedinherited

Definition at line 115 of file vpRobot.h.

Referenced by vpRobot::operator=(), and vpRobot::~vpRobot().

◆ verbose_