libfranka  0.8.0
FCI C++ API
Functions | Variables
rate_limiting.h File Reference

Contains functions for limiting the rate of torques, Cartesian pose, Cartesian velocity, joint position and joint velocity. More...

#include <array>
#include <limits>
Include dependency graph for rate_limiting.h:

Go to the source code of this file.

Functions

std::array< double, 7 > franka::limitRate (const std::array< double, 7 > &max_derivatives, const std::array< double, 7 > &commanded_values, const std::array< double, 7 > &last_commanded_values)
 Limits the rate of an input vector of per-joint commands considering the maximum allowed time derivatives. More...
 
double franka::limitRate (double max_velocity, double max_acceleration, double max_jerk, double commanded_velocity, double last_commanded_velocity, double last_commanded_acceleration)
 Limits the rate of a desired joint velocity considering the limits provided. More...
 
double franka::limitRate (double max_velocity, double max_acceleration, double max_jerk, double commanded_position, double last_commanded_position, double last_commanded_velocity, double last_commanded_acceleration)
 Limits the rate of a desired joint position considering the limits provided. More...
 
std::array< double, 7 > franka::limitRate (const std::array< double, 7 > &max_velocity, const std::array< double, 7 > &max_acceleration, const std::array< double, 7 > &max_jerk, const std::array< double, 7 > &commanded_velocities, const std::array< double, 7 > &last_commanded_velocities, const std::array< double, 7 > &last_commanded_accelerations)
 Limits the rate of a desired joint velocity considering the limits provided. More...
 
std::array< double, 7 > franka::limitRate (const std::array< double, 7 > &max_velocity, const std::array< double, 7 > &max_acceleration, const std::array< double, 7 > &max_jerk, const std::array< double, 7 > &commanded_positions, const std::array< double, 7 > &last_commanded_positions, const std::array< double, 7 > &last_commanded_velocities, const std::array< double, 7 > &last_commanded_accelerations)
 Limits the rate of a desired joint position considering the limits provided. More...
 
std::array< double, 6 > franka::limitRate (double max_translational_velocity, double max_translational_acceleration, double max_translational_jerk, double max_rotational_velocity, double max_rotational_acceleration, double max_rotational_jerk, const std::array< double, 6 > &O_dP_EE_c, const std::array< double, 6 > &last_O_dP_EE_c, const std::array< double, 6 > &last_O_ddP_EE_c)
 Limits the rate of a desired Cartesian velocity considering the limits provided. More...
 
std::array< double, 16 > franka::limitRate (double max_translational_velocity, double max_translational_acceleration, double max_translational_jerk, double max_rotational_velocity, double max_rotational_acceleration, double max_rotational_jerk, const std::array< double, 16 > &O_T_EE_c, const std::array< double, 16 > &last_O_T_EE_c, const std::array< double, 6 > &last_O_dP_EE_c, const std::array< double, 6 > &last_O_ddP_EE_c)
 Limits the rate of a desired Cartesian pose considering the limits provided. More...
 

Variables

constexpr double franka::kDeltaT = 1e-3
 Sample time constant.
 
constexpr double franka::kLimitEps = 1e-3
 Epsilon value for checking limits.
 
constexpr double franka::kNormEps = std::numeric_limits<double>::epsilon()
 Epsilon value for limiting Cartesian accelerations/jerks or not.
 
constexpr double franka::kTolNumberPacketsLost = 3.0
 Number of packets losts considered for the definition of velocity limits. More...
 
constexpr double franka::kFactorCartesianRotationPoseInterface = 0.99
 Factor for the definition of rotational limits using the Cartesian Pose interface.
 
constexpr std::array< double, 7 > franka::kMaxTorqueRate
 Maximum torque rate. More...
 
constexpr std::array< double, 7 > franka::kMaxJointJerk
 Maximum joint jerk. More...
 
constexpr std::array< double, 7 > franka::kMaxJointAcceleration
 Maximum joint acceleration. More...
 
constexpr std::array< double, 7 > franka::kMaxJointVelocity
 Maximum joint velocity. More...
 
constexpr double franka::kMaxTranslationalJerk = 6500.0 - kLimitEps
 Maximum translational jerk.
 
constexpr double franka::kMaxTranslationalAcceleration = 13.0000 - kLimitEps
 Maximum translational acceleration.
 
constexpr double franka::kMaxTranslationalVelocity
 Maximum translational velocity. More...
 
constexpr double franka::kMaxRotationalJerk = 12500.0 - kLimitEps
 Maximum rotational jerk.
 
constexpr double franka::kMaxRotationalAcceleration = 25.0000 - kLimitEps
 Maximum rotational acceleration.
 
constexpr double franka::kMaxRotationalVelocity
 Maximum rotational velocity. More...
 
constexpr double franka::kMaxElbowJerk = 5000 - kLimitEps
 Maximum elbow jerk.
 
constexpr double franka::kMaxElbowAcceleration = 10.0000 - kLimitEps
 Maximum elbow acceleration.
 
constexpr double franka::kMaxElbowVelocity
 Maximum elbow velocity. More...
 

Detailed Description

Contains functions for limiting the rate of torques, Cartesian pose, Cartesian velocity, joint position and joint velocity.

Function Documentation

◆ limitRate() [1/7]

std::array<double, 7> franka::limitRate ( const std::array< double, 7 > &  max_derivatives,
const std::array< double, 7 > &  commanded_values,
const std::array< double, 7 > &  last_commanded_values 
)

Limits the rate of an input vector of per-joint commands considering the maximum allowed time derivatives.

Note
FCI filters must be deactivated to work properly.
Parameters
[in]max_derivativesPer-joint maximum allowed time derivative.
[in]commanded_valuesCommanded values of the current time step.
[in]last_commanded_valuesCommanded values of the previous time step.
Exceptions
std::invalid_argumentif commanded_values are infinite or NaN.
Returns
Rate-limited vector of desired values.
Examples:
joint_impedance_control.cpp.

◆ limitRate() [2/7]

double franka::limitRate ( double  max_velocity,
double  max_acceleration,
double  max_jerk,
double  commanded_velocity,
double  last_commanded_velocity,
double  last_commanded_acceleration 
)

Limits the rate of a desired joint velocity considering the limits provided.

Note
FCI filters must be deactivated to work properly.
Parameters
[in]max_velocityMaximum allowed velocity.
[in]max_accelerationMaximum allowed acceleration.
[in]max_jerkMaximum allowed jerk.
[in]commanded_velocityCommanded joint velocity of the current time step.
[in]last_commanded_velocityCommanded joint velocitiy of the previous time step.
[in]last_commanded_accelerationCommanded joint acceleration of the previous time step.
Exceptions
std::invalid_argumentif commanded_velocity is infinite or NaN.
Returns
Rate-limited desired joint velocity.

◆ limitRate() [3/7]

double franka::limitRate ( double  max_velocity,
double  max_acceleration,
double  max_jerk,
double  commanded_position,
double  last_commanded_position,
double  last_commanded_velocity,
double  last_commanded_acceleration 
)

Limits the rate of a desired joint position considering the limits provided.

Note
FCI filters must be deactivated to work properly.
Parameters
[in]max_velocityMaximum allowed velocity.
[in]max_accelerationMaximum allowed acceleration.
[in]max_jerkMaximum allowed jerk.
[in]commanded_positionCommanded joint position of the current time step.
[in]last_commanded_positionCommanded joint position of the previous time step.
[in]last_commanded_velocityCommanded joint velocity of the previous time step.
[in]last_commanded_accelerationCommanded joint acceleration of the previous time step.
Exceptions
std::invalid_argumentif commanded_position is infinite or NaN.
Returns
Rate-limited desired joint position.

◆ limitRate() [4/7]

std::array<double, 7> franka::limitRate ( const std::array< double, 7 > &  max_velocity,
const std::array< double, 7 > &  max_acceleration,
const std::array< double, 7 > &  max_jerk,
const std::array< double, 7 > &  commanded_velocities,
const std::array< double, 7 > &  last_commanded_velocities,
const std::array< double, 7 > &  last_commanded_accelerations 
)

Limits the rate of a desired joint velocity considering the limits provided.

Note
FCI filters must be deactivated to work properly.
Parameters
[in]max_velocityPer-joint maximum allowed velocity.
[in]max_accelerationPer-joint maximum allowed acceleration.
[in]max_jerkPer-joint maximum allowed jerk.
[in]commanded_velocitiesCommanded joint velocity of the current time step.
[in]last_commanded_velocitiesCommanded joint velocities of the previous time step.
[in]last_commanded_accelerationsCommanded joint accelerations of the previous time step.
Exceptions
std::invalid_argumentif commanded_velocities are infinite or NaN.
Returns
Rate-limited vector of desired joint velocities.

◆ limitRate() [5/7]

std::array<double, 7> franka::limitRate ( const std::array< double, 7 > &  max_velocity,
const std::array< double, 7 > &  max_acceleration,
const std::array< double, 7 > &  max_jerk,
const std::array< double, 7 > &  commanded_positions,
const std::array< double, 7 > &  last_commanded_positions,
const std::array< double, 7 > &  last_commanded_velocities,
const std::array< double, 7 > &  last_commanded_accelerations 
)

Limits the rate of a desired joint position considering the limits provided.

Note
FCI filters must be deactivated to work properly.
Parameters
[in]max_velocityPer-joint maximum allowed velocity.
[in]max_accelerationPer-joint maximum allowed velocity.
[in]max_jerkPer-joint maximum allowed velocity.
[in]commanded_positionsPer-joint maximum allowed acceleration.
[in]last_commanded_positionsCommanded joint positions of the current time step.
[in]last_commanded_velocitiesCommanded joint positions of the previous time step.
[in]last_commanded_accelerationsCommanded joint velocities of the previous time step.
Exceptions
std::invalid_argumentif commanded_positions are infinite or NaN.
Returns
Rate-limited vector of desired joint positions.

◆ limitRate() [6/7]

std::array<double, 6> franka::limitRate ( double  max_translational_velocity,
double  max_translational_acceleration,
double  max_translational_jerk,
double  max_rotational_velocity,
double  max_rotational_acceleration,
double  max_rotational_jerk,
const std::array< double, 6 > &  O_dP_EE_c,
const std::array< double, 6 > &  last_O_dP_EE_c,
const std::array< double, 6 > &  last_O_ddP_EE_c 
)

Limits the rate of a desired Cartesian velocity considering the limits provided.

Note
FCI filters must be deactivated to work properly.
Parameters
[in]max_translational_velocityMaximum translational velocity.
[in]max_translational_accelerationMaximum translational acceleration.
[in]max_translational_jerkMaximum translational jerk.
[in]max_rotational_velocityMaximum rotational velocity.
[in]max_rotational_accelerationMaximum rotational acceleration.
[in]max_rotational_jerkMaximum rotational jerk.
[in]O_dP_EE_cCommanded end effector twist of the current time step.
[in]last_O_dP_EE_cCommanded end effector twist of the previous time step.
[in]last_O_ddP_EE_cCommanded end effector acceleration of the previous time step.
Exceptions
std::invalid_argumentif an element of O_dP_EE_c is infinite or NaN.
Returns
Rate-limited desired end effector twist.

◆ limitRate() [7/7]

std::array<double, 16> franka::limitRate ( double  max_translational_velocity,
double  max_translational_acceleration,
double  max_translational_jerk,
double  max_rotational_velocity,
double  max_rotational_acceleration,
double  max_rotational_jerk,
const std::array< double, 16 > &  O_T_EE_c,
const std::array< double, 16 > &  last_O_T_EE_c,
const std::array< double, 6 > &  last_O_dP_EE_c,
const std::array< double, 6 > &  last_O_ddP_EE_c 
)

Limits the rate of a desired Cartesian pose considering the limits provided.

Note
FCI filters must be deactivated to work properly.
Parameters
[in]max_translational_velocityMaximum translational velocity.
[in]max_translational_accelerationMaximum translational acceleration.
[in]max_translational_jerkMaximum translational jerk.
[in]max_rotational_velocityMaximum rotational velocity.
[in]max_rotational_accelerationMaximum rotational acceleration.
[in]max_rotational_jerkMaximum rotational jerk.
[in]O_T_EE_cCommanded pose of the current time step.
[in]last_O_T_EE_cCommanded pose of the previous time step.
[in]last_O_dP_EE_cCommanded end effector twist of the previous time step.
[in]last_O_ddP_EE_cCommanded end effector acceleration of the previous time step.
Exceptions
std::invalid_argumentif an element of O_T_EE_c is infinite or NaN.
Returns
Rate-limited desired pose.

Variable Documentation

◆ kMaxElbowVelocity

constexpr double franka::kMaxElbowVelocity
Initial value:
=
constexpr double kTolNumberPacketsLost
Number of packets losts considered for the definition of velocity limits.
Definition: rate_limiting.h:31
constexpr double kLimitEps
Epsilon value for checking limits.
Definition: rate_limiting.h:22
constexpr double kMaxElbowAcceleration
Maximum elbow acceleration.
Definition: rate_limiting.h:98
constexpr double kDeltaT
Sample time constant.
Definition: rate_limiting.h:18

Maximum elbow velocity.

◆ kMaxJointAcceleration

constexpr std::array<double, 7> franka::kMaxJointAcceleration
Initial value:
{
{15.0000 - kLimitEps, 7.500 - kLimitEps, 10.0000 - kLimitEps, 12.5000 - kLimitEps,
15.0000 - kLimitEps, 20.0000 - kLimitEps, 20.0000 - kLimitEps}}
constexpr double kLimitEps
Epsilon value for checking limits.
Definition: rate_limiting.h:22

Maximum joint acceleration.

◆ kMaxJointJerk

constexpr std::array<double, 7> franka::kMaxJointJerk
Initial value:
{
{7500.0 - kLimitEps, 3750.0 - kLimitEps, 5000.0 - kLimitEps, 6250.0 - kLimitEps,
7500.0 - kLimitEps, 10000.0 - kLimitEps, 10000.0 - kLimitEps}}
constexpr double kLimitEps
Epsilon value for checking limits.
Definition: rate_limiting.h:22

Maximum joint jerk.

◆ kMaxJointVelocity

constexpr std::array<double, 7> franka::kMaxJointVelocity
Initial value:
{
2.1750 - kLimitEps - kTolNumberPacketsLost* kDeltaT* kMaxJointAcceleration[1],
2.1750 - kLimitEps - kTolNumberPacketsLost* kDeltaT* kMaxJointAcceleration[2],
2.1750 - kLimitEps - kTolNumberPacketsLost* kDeltaT* kMaxJointAcceleration[3],
2.6100 - kLimitEps - kTolNumberPacketsLost* kDeltaT* kMaxJointAcceleration[4],
2.6100 - kLimitEps - kTolNumberPacketsLost* kDeltaT* kMaxJointAcceleration[5],
2.6100 - kLimitEps - kTolNumberPacketsLost* kDeltaT* kMaxJointAcceleration[6]}}
constexpr double kTolNumberPacketsLost
Number of packets losts considered for the definition of velocity limits.
Definition: rate_limiting.h:31
constexpr double kLimitEps
Epsilon value for checking limits.
Definition: rate_limiting.h:22
constexpr double kDeltaT
Sample time constant.
Definition: rate_limiting.h:18
constexpr std::array< double, 7 > kMaxJointAcceleration
Maximum joint acceleration.
Definition: rate_limiting.h:51

Maximum joint velocity.

◆ kMaxRotationalVelocity

constexpr double franka::kMaxRotationalVelocity
Initial value:
=
constexpr double kMaxRotationalAcceleration
Maximum rotational acceleration.
Definition: rate_limiting.h:85
constexpr double kTolNumberPacketsLost
Number of packets losts considered for the definition of velocity limits.
Definition: rate_limiting.h:31
constexpr double kLimitEps
Epsilon value for checking limits.
Definition: rate_limiting.h:22
constexpr double kDeltaT
Sample time constant.
Definition: rate_limiting.h:18

Maximum rotational velocity.

◆ kMaxTorqueRate

constexpr std::array<double, 7> franka::kMaxTorqueRate
Initial value:
{
{1000 - kLimitEps, 1000 - kLimitEps, 1000 - kLimitEps, 1000 - kLimitEps, 1000 - kLimitEps,
1000 - kLimitEps, 1000 - kLimitEps}}
constexpr double kLimitEps
Epsilon value for checking limits.
Definition: rate_limiting.h:22

Maximum torque rate.

Examples:
joint_impedance_control.cpp.

◆ kMaxTranslationalVelocity

constexpr double franka::kMaxTranslationalVelocity
Initial value:
=
constexpr double kTolNumberPacketsLost
Number of packets losts considered for the definition of velocity limits.
Definition: rate_limiting.h:31
constexpr double kLimitEps
Epsilon value for checking limits.
Definition: rate_limiting.h:22
constexpr double kDeltaT
Sample time constant.
Definition: rate_limiting.h:18
constexpr double kMaxTranslationalAcceleration
Maximum translational acceleration.
Definition: rate_limiting.h:72

Maximum translational velocity.

◆ kTolNumberPacketsLost

constexpr double franka::kTolNumberPacketsLost = 3.0

Number of packets losts considered for the definition of velocity limits.

When a packet is lost, FCI assumes a constant acceleration model