Classes | |
class | CartesianPose |
Stores values for Cartesian pose motion generation. More... | |
class | CartesianVelocities |
Stores values for Cartesian velocity motion generation. More... | |
struct | CommandException |
CommandException is thrown if an error occurs during command execution. More... | |
struct | ControlException |
ControlException is thrown if an error occurs during motion generation or torque control. More... | |
class | Duration |
Represents a duration with millisecond resolution. More... | |
struct | Errors |
Enumerates errors that can occur while controlling a franka::Robot. More... | |
struct | Exception |
Base class for all exceptions used by libfranka . More... | |
struct | Finishable |
Helper type for control and motion generation loops. More... | |
class | Gripper |
Maintains a network connection to the gripper, provides the current gripper state, and allows the execution of commands. More... | |
struct | GripperState |
Describes the gripper state. More... | |
struct | IncompatibleVersionException |
IncompatibleVersionException is thrown if the robot does not support this version of libfranka. More... | |
struct | InvalidOperationException |
InvalidOperationException is thrown if an operation cannot be performed. More... | |
class | JointPositions |
Stores values for joint position motion generation. More... | |
class | JointVelocities |
Stores values for joint velocity motion generation. More... | |
class | Model |
Calculates poses of joints and dynamic properties of the robot. More... | |
struct | ModelException |
ModelException is thrown if an error occurs when loading the model library. More... | |
struct | NetworkException |
NetworkException is thrown if a connection to the robot cannot be established, or when a timeout occurs. More... | |
struct | ProtocolException |
ProtocolException is thrown if the robot returns an incorrect message. More... | |
struct | RealtimeException |
RealtimeException is thrown if realtime priority cannot be set. More... | |
struct | Record |
One row of the log contains a robot command of timestamp n and a corresponding robot state of timestamp n+1. More... | |
class | Robot |
Maintains a network connection to the robot, provides the current robot state, gives access to the model library and allows to control the robot. More... | |
struct | RobotCommand |
Command sent to the robot. More... | |
struct | RobotState |
Describes the robot state. More... | |
class | Torques |
Stores joint-level torque commands without gravity and friction. More... | |
struct | VirtualWallCuboid |
Parameters of a cuboid used as virtual wall. More... | |
Enumerations | |
enum | ControllerMode { ControllerMode::kJointImpedance, ControllerMode::kCartesianImpedance } |
Available controller modes for a franka::Robot. More... | |
enum | Frame { Frame::kJoint1, Frame::kJoint2, Frame::kJoint3, Frame::kJoint4, Frame::kJoint5, Frame::kJoint6, Frame::kJoint7, Frame::kFlange, Frame::kEndEffector, Frame::kStiffness } |
Enumerates the seven joints, the flange, and the end effector of a robot. More... | |
enum | RealtimeConfig { RealtimeConfig::kEnforce, RealtimeConfig::kIgnore } |
Used to decide whether to enforce realtime mode for a control loop thread. More... | |
enum | RobotMode { RobotMode::kOther, RobotMode::kIdle, RobotMode::kMove, RobotMode::kGuiding, RobotMode::kReflex, RobotMode::kUserStopped, RobotMode::kAutomaticErrorRecovery } |
Describes the robot's current mode. More... | |
Functions | |
std::array< double, 16 > | cartesianLowpassFilter (double sample_time, std::array< double, 16 > y, std::array< double, 16 > y_last, double cutoff_frequency) |
Applies a first-order low-pass filter to the translation and spherical linear interpolation to the rotation of a transformation matrix which represents a Cartesian Motion. More... | |
bool | hasRealtimeKernel () |
Determines whether the current OS kernel is a realtime kernel. More... | |
bool | isHomogeneousTransformation (const std::array< double, 16 > &transform) noexcept |
Determines whether the given array represents a valid homogeneous transformation matrix. More... | |
bool | isValidElbow (const std::array< double, 2 > &elbow) noexcept |
Determines whether the given elbow configuration is valid or not. More... | |
std::array< double, 7 > | 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 | 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 | 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 > | 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 > | 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 > | 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 > | 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... | |
std::string | logToCSV (const std::vector< Record > &log) |
Writes the log to a string in CSV format. More... | |
double | lowpassFilter (double sample_time, double y, double y_last, double cutoff_frequency) |
Applies a first-order low-pass filter. More... | |
Torques | MotionFinished (Torques command) noexcept |
Helper method to indicate that a motion should stop after processing the given command. More... | |
JointPositions | MotionFinished (JointPositions command) noexcept |
Helper method to indicate that a motion should stop after processing the given command. More... | |
JointVelocities | MotionFinished (JointVelocities command) noexcept |
Helper method to indicate that a motion should stop after processing the given command. More... | |
CartesianPose | MotionFinished (CartesianPose command) noexcept |
Helper method to indicate that a motion should stop after processing the given command. More... | |
CartesianVelocities | MotionFinished (CartesianVelocities command) noexcept |
Helper method to indicate that a motion should stop after processing the given command. More... | |
Duration | operator* (uint64_t lhs, const Duration &rhs) noexcept |
Performs multiplication. More... | |
Frame | operator++ (Frame &frame, int) noexcept |
Post-increments the given Frame by one. More... | |
std::ostream & | operator<< (std::ostream &ostream, const franka::GripperState &gripper_state) |
Streams the gripper state as JSON object: {"field_name_1": value, "field_name_2": value, ...}. More... | |
std::ostream & | operator<< (std::ostream &ostream, const Errors &errors) |
Streams the errors as JSON array. More... | |
std::ostream & | operator<< (std::ostream &ostream, const franka::RobotState &robot_state) |
Streams the robot state as JSON object: {"field_name_1": [0,0,0,0,0,0,0], "field_name_2": [0,0,0,0,0,0], ...}. More... | |
bool | setCurrentThreadToHighestSchedulerPriority (std::string *error_message) |
Sets the current thread to the highest possible scheduler priority. More... | |
Variables | |
constexpr double | kDefaultCutoffFrequency = 100.0 |
Default cutoff frequency. More... | |
constexpr double | kDeltaT = 1e-3 |
Sample time constant. More... | |
constexpr double | kFactorCartesianRotationPoseInterface = 0.99 |
Factor for the definition of rotational limits using the Cartesian Pose interface. More... | |
constexpr double | kLimitEps = 1e-3 |
Epsilon value for checking limits. More... | |
constexpr double | kMaxCutoffFrequency = 1000.0 |
Maximum cutoff frequency. More... | |
constexpr double | kMaxElbowAcceleration = 10.0000 - kLimitEps |
Maximum elbow acceleration. More... | |
constexpr double | kMaxElbowJerk = 5000 - kLimitEps |
Maximum elbow jerk. More... | |
constexpr double | kMaxElbowVelocity |
Maximum elbow velocity. More... | |
constexpr std::array< double, 7 > | kMaxJointAcceleration |
Maximum joint acceleration. More... | |
constexpr std::array< double, 7 > | kMaxJointJerk |
Maximum joint jerk. More... | |
constexpr std::array< double, 7 > | kMaxJointVelocity |
Maximum joint velocity. More... | |
constexpr double | kMaxRotationalAcceleration = 25.0000 - kLimitEps |
Maximum rotational acceleration. More... | |
constexpr double | kMaxRotationalJerk = 12500.0 - kLimitEps |
Maximum rotational jerk. More... | |
constexpr double | kMaxRotationalVelocity |
Maximum rotational velocity. More... | |
constexpr std::array< double, 7 > | kMaxTorqueRate |
Maximum torque rate. More... | |
constexpr double | kMaxTranslationalAcceleration = 13.0000 - kLimitEps |
Maximum translational acceleration. More... | |
constexpr double | kMaxTranslationalJerk = 6500.0 - kLimitEps |
Maximum translational jerk. More... | |
constexpr double | kMaxTranslationalVelocity |
Maximum translational velocity. More... | |
constexpr double | kNormEps = std::numeric_limits<double>::epsilon() |
Epsilon value for limiting Cartesian accelerations/jerks or not. More... | |
constexpr double | kTolNumberPacketsLost = 3.0 |
Number of packets losts considered for the definition of velocity limits. More... | |
|
strong |
Available controller modes for a franka::Robot.
Enumerator | |
---|---|
kJointImpedance | |
kCartesianImpedance |
Definition at line 19 of file control_types.h.
|
strong |
|
strong |
Used to decide whether to enforce realtime mode for a control loop thread.
Enumerator | |
---|---|
kEnforce | |
kIgnore |
Definition at line 26 of file control_types.h.
|
strong |
Describes the robot's current mode.
Enumerator | |
---|---|
kOther | |
kIdle | |
kMove | |
kGuiding | |
kReflex | |
kUserStopped | |
kAutomaticErrorRecovery |
Definition at line 22 of file robot_state.h.
std::array<double, 16> franka::cartesianLowpassFilter | ( | double | sample_time, |
std::array< double, 16 > | y, | ||
std::array< double, 16 > | y_last, | ||
double | cutoff_frequency | ||
) |
Applies a first-order low-pass filter to the translation and spherical linear interpolation to the rotation of a transformation matrix which represents a Cartesian Motion.
[in] | sample_time | Sample time constant |
[in] | y | Current Cartesian transformation matrix to be filtered |
[in] | y_last | Cartesian transformation matrix from the previous time step |
[in] | cutoff_frequency | Cutoff frequency of the low-pass filter |
std::invalid_argument | if elements of y is infinite or NaN. |
std::invalid_argument | if elements of y_last is infinite or NaN. |
std::invalid_argument | if cutoff_frequency is zero, negative, infinite or NaN. |
std::invalid_argument | if sample_time is negative, infinite or NaN. |
bool franka::hasRealtimeKernel | ( | ) |
Determines whether the current OS kernel is a realtime kernel.
On Linux, this checks for the existence of /sys/kernel/realtime
. On Windows, this always returns true.
|
inlinenoexcept |
Determines whether the given array represents a valid homogeneous transformation matrix.
[in] | transform | 4x4 matrix in column-major format. |
Definition at line 33 of file control_tools.h.
|
inlinenoexcept |
Determines whether the given elbow configuration is valid or not.
[in] | elbow | Elbow configuration. |
Definition at line 22 of file control_tools.h.
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. |
std::string franka::logToCSV | ( | const std::vector< Record > & | log | ) |
Writes the log to a string in CSV format.
If the string is not empty, the first row contains the header with names of columns. The following lines contain rows of values separated by commas.
If the log is empty, the function returns an empty string.
[in] | log | Log provided by the ControlException. |
double franka::lowpassFilter | ( | double | sample_time, |
double | y, | ||
double | y_last, | ||
double | cutoff_frequency | ||
) |
Applies a first-order low-pass filter.
[in] | sample_time | Sample time constant |
[in] | y | Current value of the signal to be filtered |
[in] | y_last | Value of the signal to be filtered in the previous time step |
[in] | cutoff_frequency | Cutoff frequency of the low-pass filter |
std::invalid_argument | if y is infinite or NaN. |
std::invalid_argument | if y_last is infinite or NaN. |
std::invalid_argument | if cutoff_frequency is zero, negative, infinite or NaN. |
std::invalid_argument | if sample_time is negative, infinite or NaN. |
Helper method to indicate that a motion should stop after processing the given command.
[in] | command | Last command to be executed before the motion terminates. |
Definition at line 275 of file control_types.h.
|
inlinenoexcept |
Helper method to indicate that a motion should stop after processing the given command.
[in] | command | Last command to be executed before the motion terminates. |
Definition at line 289 of file control_types.h.
|
inlinenoexcept |
Helper method to indicate that a motion should stop after processing the given command.
[in] | command | Last command to be executed before the motion terminates. |
Definition at line 304 of file control_types.h.
|
inlinenoexcept |
Helper method to indicate that a motion should stop after processing the given command.
[in] | command | Last command to be executed before the motion terminates. |
Definition at line 319 of file control_types.h.
|
inlinenoexcept |
Helper method to indicate that a motion should stop after processing the given command.
[in] | command | Last command to be executed before the motion terminates. |
Definition at line 334 of file control_types.h.
Performs multiplication.
[in] | lhs | Left-hand side of the multiplication. |
[in] | rhs | Right-hand side of the multiplication. |
Post-increments the given Frame by one.
For example, Frame::kJoint2++ results in Frame::kJoint3.
[in] | frame | Frame to increment. |
std::ostream& franka::operator<< | ( | std::ostream & | ostream, |
const franka::GripperState & | gripper_state | ||
) |
Streams the gripper state as JSON object: {"field_name_1": value, "field_name_2": value, ...}.
[in] | ostream | Ostream instance |
[in] | gripper_state | GripperState struct instance to stream |
std::ostream& franka::operator<< | ( | std::ostream & | ostream, |
const Errors & | errors | ||
) |
Streams the errors as JSON array.
[in] | ostream | Ostream instance |
[in] | errors | Errors struct instance to stream |
std::ostream& franka::operator<< | ( | std::ostream & | ostream, |
const franka::RobotState & | robot_state | ||
) |
Streams the robot state as JSON object: {"field_name_1": [0,0,0,0,0,0,0], "field_name_2": [0,0,0,0,0,0], ...}.
[in] | ostream | Ostream instance |
[in] | robot_state | RobotState instance to stream |
bool franka::setCurrentThreadToHighestSchedulerPriority | ( | std::string * | error_message | ) |
Sets the current thread to the highest possible scheduler priority.
[out] | error_message | Contains an error message if the scheduler priority cannot be set successfully. |
constexpr double franka::kDefaultCutoffFrequency = 100.0 |
Default cutoff frequency.
Definition at line 21 of file lowpass_filter.h.
constexpr double franka::kDeltaT = 1e-3 |
Sample time constant.
Definition at line 18 of file rate_limiting.h.
constexpr double franka::kFactorCartesianRotationPoseInterface = 0.99 |
Factor for the definition of rotational limits using the Cartesian Pose interface.
Definition at line 35 of file rate_limiting.h.
constexpr double franka::kLimitEps = 1e-3 |
Epsilon value for checking limits.
Definition at line 22 of file rate_limiting.h.
constexpr double franka::kMaxCutoffFrequency = 1000.0 |
Maximum cutoff frequency.
Definition at line 17 of file lowpass_filter.h.
constexpr double franka::kMaxElbowAcceleration = 10.0000 - kLimitEps |
Maximum elbow acceleration.
Definition at line 98 of file rate_limiting.h.
constexpr double franka::kMaxElbowJerk = 5000 - kLimitEps |
Maximum elbow jerk.
Definition at line 94 of file rate_limiting.h.
constexpr double franka::kMaxElbowVelocity |
Maximum elbow velocity.
Definition at line 102 of file rate_limiting.h.
constexpr std::array<double, 7> franka::kMaxJointAcceleration |
Maximum joint acceleration.
Definition at line 51 of file rate_limiting.h.
constexpr std::array<double, 7> franka::kMaxJointJerk |
Maximum joint jerk.
Definition at line 45 of file rate_limiting.h.
constexpr std::array<double, 7> franka::kMaxJointVelocity |
Maximum joint velocity.
Definition at line 57 of file rate_limiting.h.
constexpr double franka::kMaxRotationalAcceleration = 25.0000 - kLimitEps |
Maximum rotational acceleration.
Definition at line 85 of file rate_limiting.h.
constexpr double franka::kMaxRotationalJerk = 12500.0 - kLimitEps |
Maximum rotational jerk.
Definition at line 81 of file rate_limiting.h.
constexpr double franka::kMaxRotationalVelocity |
Maximum rotational velocity.
Definition at line 89 of file rate_limiting.h.
constexpr std::array<double, 7> franka::kMaxTorqueRate |
Maximum torque rate.
Definition at line 39 of file rate_limiting.h.
constexpr double franka::kMaxTranslationalAcceleration = 13.0000 - kLimitEps |
Maximum translational acceleration.
Definition at line 72 of file rate_limiting.h.
constexpr double franka::kMaxTranslationalJerk = 6500.0 - kLimitEps |
Maximum translational jerk.
Definition at line 68 of file rate_limiting.h.
constexpr double franka::kMaxTranslationalVelocity |
Maximum translational velocity.
Definition at line 76 of file rate_limiting.h.
constexpr double franka::kNormEps = std::numeric_limits<double>::epsilon() |
Epsilon value for limiting Cartesian accelerations/jerks or not.
Definition at line 26 of file rate_limiting.h.
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
Definition at line 31 of file rate_limiting.h.