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

Namespaces

 franka
 

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

Detailed Description

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

Definition in file rate_limiting.h.



libfranka
Author(s): Franka Emika GmbH
autogenerated on Tue Jul 9 2019 03:32:01