Visual Servoing Platform
version 3.6.1 under development (2024-11-21)
|
#include <visp3/robot/vpRobotFranka.h>
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 |
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:
Known issues:
We provide also the getHandler() function that allows to access to the robot handler and call the native libfranka API functionalities:
Definition at line 222 of file vpRobotFranka.h.
|
inherited |
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. |
|
inherited |
Robot control states.
BEGIN_VISP_NAMESPACE vpRobotFranka::vpRobotFranka | ( | ) |
Default constructor.
Definition at line 54 of file vpRobotFranka.cpp.
vpRobotFranka::vpRobotFranka | ( | const std::string & | franka_address, |
franka::RealtimeConfig | realtime_config = franka::RealtimeConfig::kEnforce |
||
) |
Establishes a connection with the robot.
[in] | franka_address | IP/hostname of the robot. |
[in] | realtime_config | If 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().
|
virtual |
Destructor.
Definition at line 99 of file vpRobotFranka.cpp.
References setRobotState(), and vpRobot::STATE_STOP.
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.
[in] | franka_address | IP/hostname of the robot. |
[in] | realtime_config | If 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().
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.
[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().
|
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.
[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().
vpHomogeneousMatrix vpRobotFranka::get_eMc | ( | ) | const |
Return the 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().
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.
[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().
|
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.
[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().
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 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 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().
[in] | q | : Joint position as a 7-dim vector. |
Definition at line 422 of file vpRobotFranka.cpp.
References get_fMe().
Referenced by getPosition().
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 that gives the position of the end-effector in the robot base frame.
[in] | q | : Joint position as a 7-dim vector. |
Definition at line 381 of file vpRobotFranka.cpp.
References vpException::fatalError, getRobotInternalState(), and vpArray2D< Type >::size().
Referenced by get_fMc(), and getPosition().
void vpRobotFranka::getCoriolis | ( | vpColVector & | coriolis | ) |
Get the Coriolis force vector (state-space equation) calculated from the current robot state: , in .
[out] | coriolis | : Coriolis force vector. |
Definition at line 310 of file vpRobotFranka.cpp.
References vpException::fatalError, getRobotInternalState(), and vpColVector::resize().
void vpRobotFranka::getForceTorque | ( | const vpRobot::vpControlFrameType | frame, |
vpColVector & | force | ||
) |
Get robot force torque.
[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.
void vpRobotFranka::getGravity | ( | vpColVector & | gravity | ) |
Get the gravity vector calculated form the current robot state. Unit: .
[out] | gravity | : Gravity vector |
Definition at line 332 of file vpRobotFranka.cpp.
References vpException::fatalError, getRobotInternalState(), and vpColVector::resize().
|
inline |
Get gripper handler to access native libfranka functions.
Definition at line 299 of file vpRobotFranka.h.
References vpException::fatalError.
|
inline |
Get robot handler to access native libfranka functions.
Definition at line 313 of file vpRobotFranka.h.
References vpException::fatalError.
vpColVector vpRobotFranka::getJointMax | ( | ) | const |
Gets maximum joint values.
Definition at line 980 of file vpRobotFranka.cpp.
vpColVector vpRobotFranka::getJointMin | ( | ) | const |
Gets minimal joint values.
Definition at line 967 of file vpRobotFranka.cpp.
void vpRobotFranka::getMass | ( | vpMatrix & | mass | ) |
Get the 7x7 mass matrix. Unit: .
[out] | mass | : 7x7 mass matrix, row-major. |
Definition at line 354 of file vpRobotFranka.cpp.
References vpException::fatalError, getRobotInternalState(), and vpArray2D< Type >::resize().
|
inherited |
Get the maximal rotation velocity that can be sent to the robot during a velocity control.
Definition at line 274 of file vpRobot.cpp.
References vpRobot::maxRotationVelocity.
Referenced by vpRobotPololuPtu::setPosition(), vpRobotPololuPtu::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().
|
inherited |
Get the maximal translation velocity that can be sent to the robot during a velocity control.
Definition at line 252 of file vpRobot.cpp.
References vpRobot::maxTranslationVelocity.
Referenced by 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().
|
inlineinherited |
Return robot degrees of freedom number.
|
inherited |
Return the current robot position in the specified frame.
Definition at line 217 of file vpRobot.cpp.
References vpRobot::getPosition().
|
virtual |
Get robot position.
[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 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.
void vpRobotFranka::getPosition | ( | const vpRobot::vpControlFrameType | frame, |
vpPoseVector & | pose | ||
) |
Get robot cartesian position.
[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 vector (see vpThetaUVector). |
Definition at line 437 of file vpRobotFranka.cpp.
References vpPoseVector::buildFrom(), vpRobot::END_EFFECTOR_FRAME, vpException::fatalError, getRobotInternalState(), vpRobot::JOINT_STATE, and vpRobot::TOOL_FRAME.
|
inlineprotectedinherited |
franka::RobotState vpRobotFranka::getRobotInternalState | ( | ) |
Definition at line 941 of file vpRobotFranka.cpp.
References vpException::fatalError.
Referenced by get_eJe(), get_fJe(), get_fMe(), getCoriolis(), getForceTorque(), getGravity(), getMass(), getPosition(), getVelocity(), and setForceTorque().
|
inlinevirtualinherited |
Definition at line 155 of file vpRobot.h.
Referenced by vpRobotBiclops::getPosition(), vpRobotBiclops::getVelocity(), vpSimulatorCamera::setPosition(), vpRobotAfma4::setPosition(), vpRobotAfma6::setPosition(), setPosition(), vpRobotUniversalRobots::setPosition(), vpRobotViper650::setPosition(), vpRobotViper850::setPosition(), vpRobotBiclops::setPosition(), vpRobotPololuPtu::setPosition(), vpRobotPtu46::setPosition(), vpRobotBiclops::setRobotState(), vpRobotPololuPtu::setRobotState(), vpRobotAfma4::setRobotState(), vpRobotAfma6::setRobotState(), vpRobotFlirPtu::setRobotState(), setRobotState(), vpRobotPtu46::setRobotState(), vpRobotUniversalRobots::setRobotState(), vpRobotViper650::setRobotState(), vpRobotViper850::setRobotState(), vpRobotBiclops::setVelocity(), vpRobotPololuPtu::setVelocity(), vpRobotPtu46::setVelocity(), vpRobotFlirPtu::setVelocity(), setVelocity(), vpRobotKinova::setVelocity(), vpRobotTemplate::setVelocity(), vpRobotUniversalRobots::setVelocity(), vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotViper650::setVelocity(), vpRobotViper850::setVelocity(), vpRobotFlirPtu::stopMotion(), stopMotion(), vpRobotViper650::stopMotion(), and vpRobotViper850::stopMotion().
void vpRobotFranka::getVelocity | ( | const vpRobot::vpControlFrameType | frame, |
vpColVector & | d_position | ||
) |
Get robot velocity.
[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 vector (see vpThetaUVector). |
Definition at line 281 of file vpRobotFranka.cpp.
References vpException::fatalError, getRobotInternalState(), vpRobot::JOINT_STATE, and vpColVector::resize().
int vpRobotFranka::gripperClose | ( | ) |
Closes the gripper.
Definition at line 1254 of file vpRobotFranka.cpp.
References gripperMove().
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.
[in] | grasping_width | : Size of the object to grasp. [m] |
[in] | force | : Grasping force. [N] |
Definition at line 1310 of file vpRobotFranka.cpp.
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.
[in] | grasping_width | : Size of the object to grasp. [m] |
[in] | speed | : Closing speed. [m/s] |
[in] | force | : Grasping force. [N] |
Definition at line 1330 of file vpRobotFranka.cpp.
void vpRobotFranka::gripperHoming | ( | ) |
Performing a gripper homing.
Definition at line 1205 of file vpRobotFranka.cpp.
References vpException::fatalError.
int vpRobotFranka::gripperMove | ( | double | width | ) |
Moves the gripper fingers to a specified width.
[in] | width | : Intended opening width. [m] |
Definition at line 1225 of file vpRobotFranka.cpp.
References vpException::fatalError.
Referenced by gripperClose().
int vpRobotFranka::gripperOpen | ( | ) |
Closes the gripper.
Definition at line 1264 of file vpRobotFranka.cpp.
References vpException::fatalError.
void vpRobotFranka::gripperRelease | ( | ) |
Release an object that is grasped.
Definition at line 1285 of file vpRobotFranka.cpp.
References vpException::fatalError.
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.
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.
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:
[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. |
The code below shows how to read a position from a file and move the robot to this position.
Definition at line 1078 of file vpRobotFranka.cpp.
References vpMath::rad(), vpColVector::resize(), and vpIoTools::splitChain().
Referenced by move().
|
staticinherited |
Saturate velocities.
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. |
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.
Definition at line 164 of file vpRobot.cpp.
References vpException::dimensionError, and vpArray2D< Type >::size().
Referenced by 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().
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.
filename | : Name of the position file to create. |
q | : Joint positions vector to save in the filename with values expressed in radians. |
Definition at line 1161 of file vpRobotFranka.cpp.
References vpMath::deg().
void vpRobotFranka::set_eMc | ( | const vpHomogeneousMatrix & | eMc | ) |
Set the 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.
[in] | eMc | : End-effector to camera frame transformation. |
Definition at line 1013 of file vpRobotFranka.cpp.
void vpRobotFranka::setForceTorque | ( | const vpRobot::vpControlFrameType | frame, |
const vpColVector & | ft, | ||
const double & | filter_gain = 0.1 , |
||
const bool & | activate_pi_controller = false |
||
) |
Definition at line 892 of file vpRobotFranka.cpp.
References vpRobot::END_EFFECTOR_FRAME, getRobotInternalState(), vpRobot::JOINT_STATE, vpRobot::MIXT_FRAME, vpRobot::REFERENCE_FRAME, vpArray2D< Type >::size(), vpRobot::TOOL_FRAME, and vpRobotException::wrongStateError.
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.
[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().
|
inherited |
Set the maximal rotation velocity that can be sent to the robot during a velocity control.
w_max | : Maximum rotational velocity expressed in rad/s. |
Definition at line 261 of file vpRobot.cpp.
References vpRobot::maxRotationVelocity.
Referenced by vpRobotViper650::setMaxRotationVelocity(), and vpRobotViper850::setMaxRotationVelocity().
|
inherited |
Set the maximal translation velocity that can be sent to the robot during a velocity control.
v_max | : Maximum translation velocity expressed in m/s. |
Definition at line 240 of file vpRobot.cpp.
References vpRobot::maxTranslationVelocity.
|
virtual |
Set robot position. This function is blocking; it returns when the desired position is reached.
[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().
void vpRobotFranka::setPositioningVelocity | ( | double | velocity | ) |
Set the maximal velocity percentage to use for a position control.
[in] | velocity | : Percentage of the maximal velocity. Values should be in ]0:100]. |
Definition at line 663 of file vpRobotFranka.cpp.
Referenced by move().
|
protectedinherited |
Definition at line 208 of file vpRobot.cpp.
Referenced by vpSimulatorCamera::setVelocity(), vpSimulatorPioneer::setVelocity(), and vpSimulatorPioneerPan::setVelocity().
|
virtual |
Change the robot state.
[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().
|
virtual |
Apply a velocity to the robot.
[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. |
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(). |
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().
|
inlineinherited |
Definition at line 170 of file vpRobot.h.
Referenced by vpRobotAfma4::vpRobotAfma4(), vpRobotAfma6::vpRobotAfma6(), vpRobotViper650::vpRobotViper650(), and vpRobotViper850::vpRobotViper850().
void vpRobotFranka::stopMotion | ( | void | ) |
Stop the robot when it is controlled in velocity and set the robot state to vpRobot::STATE_STOP.
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.
|
protectedinherited |
Definition at line 114 of file vpRobot.h.
Referenced by vpRobot::operator=().
|
protectedinherited |
robot Jacobian expressed in the end-effector frame
Definition at line 106 of file vpRobot.h.
Referenced by vpRobotFlirPtu::get_eJe(), vpRobotAfma6::get_eJe(), vpRobotPtu46::get_eJe(), vpRobotAfma4::get_eJe(), vpRobotBiclops::get_eJe(), vpRobotKinova::get_eJe(), vpRobotPololuPtu::get_eJe(), vpRobotViper650::get_eJe(), vpRobotViper850::get_eJe(), vpSimulatorCamera::get_eJe(), vpRobot::operator=(), and vpRobotAfma4::setVelocity().
|
protectedinherited |
is the robot Jacobian expressed in the end-effector frame available
Definition at line 108 of file vpRobot.h.
Referenced by vpRobot::operator=().
|
protectedinherited |
robot Jacobian expressed in the robot reference frame available
Definition at line 110 of file vpRobot.h.
Referenced by vpRobotFlirPtu::get_fJe(), vpRobotAfma6::get_fJe(), vpRobotPtu46::get_fJe(), vpRobotAfma4::get_fJe(), vpRobotBiclops::get_fJe(), vpRobotKinova::get_fJe(), vpRobotPololuPtu::get_fJe(), vpRobotViper650::get_fJe(), vpRobotViper850::get_fJe(), and vpRobot::operator=().
|
protectedinherited |
is the robot Jacobian expressed in the robot reference frame available
Definition at line 112 of file vpRobot.h.
Referenced by vpRobot::operator=().
|
protectedinherited |
Definition at line 100 of file vpRobot.h.
Referenced by vpRobot::getMaxRotationVelocity(), vpRobotFlirPtu::init(), vpRobotKinova::init(), vpRobotTemplate::init(), vpRobot::operator=(), vpRobot::setMaxRotationVelocity(), vpRobotPtu46::setVelocity(), vpRobotViper650::vpRobotViper650(), and vpRobotViper850::vpRobotViper850().
|
staticprotectedinherited |
Definition at line 101 of file vpRobot.h.
Referenced by vpRobotFlirPtu::init(), vpRobotKinova::init(), and vpRobotTemplate::init().
|
protectedinherited |
Definition at line 98 of file vpRobot.h.
Referenced by vpRobot::getMaxTranslationVelocity(), vpRobotFlirPtu::init(), vpRobotKinova::init(), vpRobotTemplate::init(), vpRobot::operator=(), and vpRobot::setMaxTranslationVelocity().
|
staticprotectedinherited |
Definition at line 99 of file vpRobot.h.
Referenced by vpRobotFlirPtu::init(), vpRobotKinova::init(), and vpRobotTemplate::init().
|
protectedinherited |
number of degrees of freedom
Definition at line 104 of file vpRobot.h.
Referenced by vpRobotPololuPtu::get_eJe(), vpRobotPololuPtu::get_fJe(), vpRobotKinova::getJointPosition(), vpRobotPololuPtu::getPosition(), vpRobotFlirPtu::init(), vpRobotKinova::init(), vpRobotUniversalRobots::init(), vpRobotTemplate::init(), vpRobot::operator=(), vpRobotUniversalRobots::readPosFile(), vpRobotKinova::setDoF(), vpRobotKinova::setJointVelocity(), vpRobotKinova::setPosition(), vpRobotPololuPtu::setPosition(), vpRobotPololuPtu::setVelocity(), vpRobotFlirPtu::setVelocity(), vpRobotKinova::setVelocity(), vpRobotTemplate::setVelocity(), and vpRobotPololuPtu::vpRobotPololuPtu().
|
protectedinherited |
Definition at line 116 of file vpRobot.h.
Referenced by vpRobot::operator=(), and vpRobot::~vpRobot().
|
protectedinherited |
Definition at line 115 of file vpRobot.h.
Referenced by vpRobot::operator=(), and vpRobot::~vpRobot().
|
protectedinherited |
Definition at line 118 of file vpRobot.h.
Referenced by vpRobotAfma4::init(), vpRobotAfma6::init(), vpRobotViper650::init(), vpRobotViper850::init(), vpRobot::operator=(), vpRobotAfma4::vpRobotAfma4(), vpRobotAfma6::vpRobotAfma6(), vpRobotViper650::vpRobotViper650(), and vpRobotViper850::vpRobotViper850().