Classes | Enumerations | Functions | Variables
franka Namespace Reference

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

Enumeration Type Documentation

Available controller modes for a franka::Robot.

Enumerator
kJointImpedance 
kCartesianImpedance 

Definition at line 19 of file control_types.h.

enum franka::Frame
strong

Enumerates the seven joints, the flange, and the end effector of a robot.

Enumerator
kJoint1 
kJoint2 
kJoint3 
kJoint4 
kJoint5 
kJoint6 
kJoint7 
kFlange 
kEndEffector 
kStiffness 

Definition at line 21 of file model.h.

Used to decide whether to enforce realtime mode for a control loop thread.

See also
Robot::Robot
Enumerator
kEnforce 
kIgnore 

Definition at line 26 of file control_types.h.

enum franka::RobotMode
strong

Describes the robot's current mode.

Enumerator
kOther 
kIdle 
kMove 
kGuiding 
kReflex 
kUserStopped 
kAutomaticErrorRecovery 

Definition at line 22 of file robot_state.h.

Function Documentation

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.

Parameters
[in]sample_timeSample time constant
[in]yCurrent Cartesian transformation matrix to be filtered
[in]y_lastCartesian transformation matrix from the previous time step
[in]cutoff_frequencyCutoff frequency of the low-pass filter
Exceptions
std::invalid_argumentif elements of y is infinite or NaN.
std::invalid_argumentif elements of y_last is infinite or NaN.
std::invalid_argumentif cutoff_frequency is zero, negative, infinite or NaN.
std::invalid_argumentif sample_time is negative, infinite or NaN.
Returns
Filtered Cartesian transformation matrix.
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.

Returns
True if running a realtime kernel, false otherwise.
bool franka::isHomogeneousTransformation ( const std::array< double, 16 > &  transform)
inlinenoexcept

Determines whether the given array represents a valid homogeneous transformation matrix.

Parameters
[in]transform4x4 matrix in column-major format.
Returns
True if the array represents a homogeneous transformation matrix, otherwise false.

Definition at line 33 of file control_tools.h.

bool franka::isValidElbow ( const std::array< double, 2 > &  elbow)
inlinenoexcept

Determines whether the given elbow configuration is valid or not.

Parameters
[in]elbowElbow configuration.
Returns
True if valid, otherwise false.

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.

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

Parameters
[in]logLog provided by the ControlException.
Returns
a string in CSV format, or empty string.
double franka::lowpassFilter ( double  sample_time,
double  y,
double  y_last,
double  cutoff_frequency 
)

Applies a first-order low-pass filter.

Parameters
[in]sample_timeSample time constant
[in]yCurrent value of the signal to be filtered
[in]y_lastValue of the signal to be filtered in the previous time step
[in]cutoff_frequencyCutoff frequency of the low-pass filter
Exceptions
std::invalid_argumentif y is infinite or NaN.
std::invalid_argumentif y_last is infinite or NaN.
std::invalid_argumentif cutoff_frequency is zero, negative, infinite or NaN.
std::invalid_argumentif sample_time is negative, infinite or NaN.
Returns
Filtered value.
Torques franka::MotionFinished ( Torques  command)
inlinenoexcept

Helper method to indicate that a motion should stop after processing the given command.

Parameters
[in]commandLast command to be executed before the motion terminates.
Returns
Command with motion_finished set to true.
See also
Documentation on callbacks

Definition at line 275 of file control_types.h.

JointPositions franka::MotionFinished ( JointPositions  command)
inlinenoexcept

Helper method to indicate that a motion should stop after processing the given command.

Parameters
[in]commandLast command to be executed before the motion terminates.
Returns
Command with motion_finished set to true.
See also
Documentation on callbacks

Definition at line 289 of file control_types.h.

JointVelocities franka::MotionFinished ( JointVelocities  command)
inlinenoexcept

Helper method to indicate that a motion should stop after processing the given command.

Parameters
[in]commandLast command to be executed before the motion terminates.
Returns
Command with motion_finished set to true.
See also
Documentation on callbacks

Definition at line 304 of file control_types.h.

CartesianPose franka::MotionFinished ( CartesianPose  command)
inlinenoexcept

Helper method to indicate that a motion should stop after processing the given command.

Parameters
[in]commandLast command to be executed before the motion terminates.
Returns
Command with motion_finished set to true.
See also
Documentation on callbacks

Definition at line 319 of file control_types.h.

CartesianVelocities franka::MotionFinished ( CartesianVelocities  command)
inlinenoexcept

Helper method to indicate that a motion should stop after processing the given command.

Parameters
[in]commandLast command to be executed before the motion terminates.
Returns
Command with motion_finished set to true.
See also
Documentation on callbacks

Definition at line 334 of file control_types.h.

Duration franka::operator* ( uint64_t  lhs,
const Duration rhs 
)
noexcept

Performs multiplication.

Parameters
[in]lhsLeft-hand side of the multiplication.
[in]rhsRight-hand side of the multiplication.
Returns
Result of the multiplication.
Frame franka::operator++ ( Frame frame,
int   
)
noexcept

Post-increments the given Frame by one.

For example, Frame::kJoint2++ results in Frame::kJoint3.

Parameters
[in]frameFrame to increment.
Returns
Original Frame.
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, ...}.

Parameters
[in]ostreamOstream instance
[in]gripper_stateGripperState struct instance to stream
Returns
Ostream instance
std::ostream& franka::operator<< ( std::ostream &  ostream,
const Errors errors 
)

Streams the errors as JSON array.

Parameters
[in]ostreamOstream instance
[in]errorsErrors struct instance to stream
Returns
Ostream instance
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], ...}.

Parameters
[in]ostreamOstream instance
[in]robot_stateRobotState instance to stream
Returns
Ostream instance
bool franka::setCurrentThreadToHighestSchedulerPriority ( std::string *  error_message)

Sets the current thread to the highest possible scheduler priority.

Parameters
[out]error_messageContains an error message if the scheduler priority cannot be set successfully.
Returns
True if successful, false otherwise.

Variable Documentation

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
Initial value:
=
constexpr double kMaxElbowAcceleration
Maximum elbow acceleration.
Definition: rate_limiting.h:98
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 elbow velocity.

Definition at line 102 of file rate_limiting.h.

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.

Definition at line 51 of file rate_limiting.h.

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.

Definition at line 45 of file rate_limiting.h.

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 std::array< double, 7 > kMaxJointAcceleration
Maximum joint acceleration.
Definition: rate_limiting.h:51
constexpr double kDeltaT
Sample time constant.
Definition: rate_limiting.h:18

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
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 kMaxRotationalAcceleration
Maximum rotational acceleration.
Definition: rate_limiting.h:85
constexpr double kDeltaT
Sample time constant.
Definition: rate_limiting.h:18

Maximum rotational velocity.

Definition at line 89 of file rate_limiting.h.

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.

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
Initial value:
=
constexpr double kMaxTranslationalAcceleration
Maximum translational acceleration.
Definition: rate_limiting.h:72
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 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.



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