libfranka
0.8.0
FCI C++ API
|
Contains functions for limiting the rate of torques, Cartesian pose, Cartesian velocity, joint position and joint velocity. More...
#include <array>
#include <limits>
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... | |
Contains functions for limiting the rate of torques, Cartesian pose, Cartesian velocity, joint position and joint velocity.
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.
[in] | max_derivatives | Per-joint maximum allowed time derivative. |
[in] | commanded_values | Commanded values of the current time step. |
[in] | last_commanded_values | Commanded values of the previous time step. |
std::invalid_argument | if commanded_values are infinite or NaN. |
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.
[in] | max_velocity | Maximum allowed velocity. |
[in] | max_acceleration | Maximum allowed acceleration. |
[in] | max_jerk | Maximum allowed jerk. |
[in] | commanded_velocity | Commanded joint velocity of the current time step. |
[in] | last_commanded_velocity | Commanded joint velocitiy of the previous time step. |
[in] | last_commanded_acceleration | Commanded joint acceleration of the previous time step. |
std::invalid_argument | if commanded_velocity is infinite or NaN. |
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.
[in] | max_velocity | Maximum allowed velocity. |
[in] | max_acceleration | Maximum allowed acceleration. |
[in] | max_jerk | Maximum allowed jerk. |
[in] | commanded_position | Commanded joint position of the current time step. |
[in] | last_commanded_position | Commanded joint position of the previous time step. |
[in] | last_commanded_velocity | Commanded joint velocity of the previous time step. |
[in] | last_commanded_acceleration | Commanded joint acceleration of the previous time step. |
std::invalid_argument | if commanded_position is infinite or NaN. |
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.
[in] | max_velocity | Per-joint maximum allowed velocity. |
[in] | max_acceleration | Per-joint maximum allowed acceleration. |
[in] | max_jerk | Per-joint maximum allowed jerk. |
[in] | commanded_velocities | Commanded joint velocity of the current time step. |
[in] | last_commanded_velocities | Commanded joint velocities of the previous time step. |
[in] | last_commanded_accelerations | Commanded joint accelerations of the previous time step. |
std::invalid_argument | if commanded_velocities are infinite or NaN. |
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.
[in] | max_velocity | Per-joint maximum allowed velocity. |
[in] | max_acceleration | Per-joint maximum allowed velocity. |
[in] | max_jerk | Per-joint maximum allowed velocity. |
[in] | commanded_positions | Per-joint maximum allowed acceleration. |
[in] | last_commanded_positions | Commanded joint positions of the current time step. |
[in] | last_commanded_velocities | Commanded joint positions of the previous time step. |
[in] | last_commanded_accelerations | Commanded joint velocities of the previous time step. |
std::invalid_argument | if commanded_positions are infinite or NaN. |
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.
[in] | max_translational_velocity | Maximum translational velocity. |
[in] | max_translational_acceleration | Maximum translational acceleration. |
[in] | max_translational_jerk | Maximum translational jerk. |
[in] | max_rotational_velocity | Maximum rotational velocity. |
[in] | max_rotational_acceleration | Maximum rotational acceleration. |
[in] | max_rotational_jerk | Maximum rotational jerk. |
[in] | O_dP_EE_c | Commanded end effector twist of the current time step. |
[in] | last_O_dP_EE_c | Commanded end effector twist of the previous time step. |
[in] | last_O_ddP_EE_c | Commanded end effector acceleration of the previous time step. |
std::invalid_argument | if an element of O_dP_EE_c is infinite or NaN. |
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.
[in] | max_translational_velocity | Maximum translational velocity. |
[in] | max_translational_acceleration | Maximum translational acceleration. |
[in] | max_translational_jerk | Maximum translational jerk. |
[in] | max_rotational_velocity | Maximum rotational velocity. |
[in] | max_rotational_acceleration | Maximum rotational acceleration. |
[in] | max_rotational_jerk | Maximum rotational jerk. |
[in] | O_T_EE_c | Commanded pose of the current time step. |
[in] | last_O_T_EE_c | Commanded pose of the previous time step. |
[in] | last_O_dP_EE_c | Commanded end effector twist of the previous time step. |
[in] | last_O_ddP_EE_c | Commanded end effector acceleration of the previous time step. |
std::invalid_argument | if an element of O_T_EE_c is infinite or NaN. |
constexpr double franka::kMaxElbowVelocity |
Maximum elbow velocity.
constexpr std::array<double, 7> franka::kMaxJointAcceleration |
constexpr std::array<double, 7> franka::kMaxJointJerk |
constexpr std::array<double, 7> franka::kMaxJointVelocity |
Maximum joint velocity.
constexpr double franka::kMaxRotationalVelocity |
Maximum rotational velocity.
constexpr std::array<double, 7> franka::kMaxTorqueRate |
Maximum torque rate.
constexpr double franka::kMaxTranslationalVelocity |
Maximum translational velocity.
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