Public Types | Public Member Functions | Private Attributes | List of all members
franka::Robot Class Reference

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

#include <robot.h>

Public Types

using ServerVersion = uint16_t
 Version of the robot server. More...
 

Public Member Functions

Model loadModel ()
 Loads the model library from the robot. More...
 
Robotoperator= (Robot &&other) noexcept
 Move-assigns this Robot from another Robot instance. More...
 
void read (std::function< bool(const RobotState &)> read_callback)
 Starts a loop for reading the current robot state. More...
 
RobotState readOnce ()
 Waits for a robot state update and returns it. More...
 
 Robot (const std::string &franka_address, RealtimeConfig realtime_config=RealtimeConfig::kEnforce, size_t log_size=50)
 Establishes a connection with the robot. More...
 
 Robot (Robot &&other) noexcept
 Move-constructs a new Robot instance. More...
 
ServerVersion serverVersion () const noexcept
 Returns the software version reported by the connected server. More...
 
 ~Robot () noexcept
 Closes the connection. More...
 
Motion generation and joint-level torque commands

The following methods allow to perform motion generation and/or send joint-level torque commands without gravity and friction by providing callback functions.

Only one of these methods can be active at the same time; a franka::ControlException is thrown otherwise.

When a robot state is received, the callback function is used to calculate the response: the desired values for that time step. After sending back the response, the callback function will be called again with the most recently received robot state. Since the robot is controlled with a 1 kHz frequency, the callback functions have to compute their result in a short time frame in order to be accepted. Callback functions take two parameters:

  • A franka::RobotState showing the current robot state.
  • A franka::Duration to indicate the time since the last callback invocation. Thus, the duration is zero on the first invocation of the callback function!

The following incomplete example shows the general structure of a callback function:

double time = 0.0;
auto control_callback = [&time](const franka::RobotState& robot_state,
time += time_step.toSec(); // Update time at the beginning of the callback.
franka::JointPositions output = getJointPositions(time);
if (time >= max_time) {
// Return MotionFinished at the end of the trajectory.
return franka::MotionFinished(output);
}
return output;
}
void control (std::function< Torques(const RobotState &, franka::Duration)> control_callback, bool limit_rate=true, double cutoff_frequency=kDefaultCutoffFrequency)
 Starts a control loop for sending joint-level torque commands. More...
 
void control (std::function< Torques(const RobotState &, franka::Duration)> control_callback, std::function< JointPositions(const RobotState &, franka::Duration)> motion_generator_callback, bool limit_rate=true, double cutoff_frequency=kDefaultCutoffFrequency)
 Starts a control loop for sending joint-level torque commands and joint positions. More...
 
void control (std::function< Torques(const RobotState &, franka::Duration)> control_callback, std::function< JointVelocities(const RobotState &, franka::Duration)> motion_generator_callback, bool limit_rate=true, double cutoff_frequency=kDefaultCutoffFrequency)
 Starts a control loop for sending joint-level torque commands and joint velocities. More...
 
void control (std::function< Torques(const RobotState &, franka::Duration)> control_callback, std::function< CartesianPose(const RobotState &, franka::Duration)> motion_generator_callback, bool limit_rate=true, double cutoff_frequency=kDefaultCutoffFrequency)
 Starts a control loop for sending joint-level torque commands and Cartesian poses. More...
 
void control (std::function< Torques(const RobotState &, franka::Duration)> control_callback, std::function< CartesianVelocities(const RobotState &, franka::Duration)> motion_generator_callback, bool limit_rate=true, double cutoff_frequency=kDefaultCutoffFrequency)
 Starts a control loop for sending joint-level torque commands and Cartesian velocities. More...
 
void control (std::function< JointPositions(const RobotState &, franka::Duration)> motion_generator_callback, ControllerMode controller_mode=ControllerMode::kJointImpedance, bool limit_rate=true, double cutoff_frequency=kDefaultCutoffFrequency)
 Starts a control loop for a joint position motion generator with a given controller mode. More...
 
void control (std::function< JointVelocities(const RobotState &, franka::Duration)> motion_generator_callback, ControllerMode controller_mode=ControllerMode::kJointImpedance, bool limit_rate=true, double cutoff_frequency=kDefaultCutoffFrequency)
 Starts a control loop for a joint velocity motion generator with a given controller mode. More...
 
void control (std::function< CartesianPose(const RobotState &, franka::Duration)> motion_generator_callback, ControllerMode controller_mode=ControllerMode::kJointImpedance, bool limit_rate=true, double cutoff_frequency=kDefaultCutoffFrequency)
 Starts a control loop for a Cartesian pose motion generator with a given controller mode. More...
 
void control (std::function< CartesianVelocities(const RobotState &, franka::Duration)> motion_generator_callback, ControllerMode controller_mode=ControllerMode::kJointImpedance, bool limit_rate=true, double cutoff_frequency=kDefaultCutoffFrequency)
 Starts a control loop for a Cartesian velocity motion generator with a given controller mode. More...
 
Commands

Commands are executed by communicating with the robot over the network.

These functions should therefore not be called from within control or motion generator loops.

VirtualWallCuboid getVirtualWall (int32_t id)
 Returns the parameters of a virtual wall. More...
 
void setCollisionBehavior (const std::array< double, 7 > &lower_torque_thresholds_acceleration, const std::array< double, 7 > &upper_torque_thresholds_acceleration, const std::array< double, 7 > &lower_torque_thresholds_nominal, const std::array< double, 7 > &upper_torque_thresholds_nominal, const std::array< double, 6 > &lower_force_thresholds_acceleration, const std::array< double, 6 > &upper_force_thresholds_acceleration, const std::array< double, 6 > &lower_force_thresholds_nominal, const std::array< double, 6 > &upper_force_thresholds_nominal)
 Changes the collision behavior. More...
 
void setCollisionBehavior (const std::array< double, 7 > &lower_torque_thresholds, const std::array< double, 7 > &upper_torque_thresholds, const std::array< double, 6 > &lower_force_thresholds, const std::array< double, 6 > &upper_force_thresholds)
 Changes the collision behavior. More...
 
void setJointImpedance (const std::array< double, 7 > &K_theta)
 Sets the impedance for each joint in the internal controller. More...
 
void setCartesianImpedance (const std::array< double, 6 > &K_x)
 Sets the Cartesian impedance for (x, y, z, roll, pitch, yaw) in the internal controller. More...
 
void setGuidingMode (const std::array< bool, 6 > &guiding_mode, bool elbow)
 Locks or unlocks guiding mode movement in (x, y, z, roll, pitch, yaw). More...
 
void setK (const std::array< double, 16 > &EE_T_K)
 Sets the transformation $^{EE}T_K$ from end effector frame to stiffness frame. More...
 
void setEE (const std::array< double, 16 > &F_T_EE)
 Sets the transformation $^FT_{EE}$ from flange to end effector frame. More...
 
void setLoad (double load_mass, const std::array< double, 3 > &F_x_Cload, const std::array< double, 9 > &load_inertia)
 Sets dynamic parameters of a payload. More...
 
void setFilters (double joint_position_filter_frequency, double joint_velocity_filter_frequency, double cartesian_position_filter_frequency, double cartesian_velocity_filter_frequency, double controller_filter_frequency)
 Sets the cut off frequency for the given motion generator or controller. More...
 
void automaticErrorRecovery ()
 Runs automatic error recovery on the robot. More...
 
void stop ()
 Stops all currently running motions. More...
 

Private Attributes

std::mutex control_mutex_
 
std::unique_ptr< Impl > impl_
 

Detailed Description

Maintains a network connection to the robot, provides the current robot state, gives access to the model library and allows to control the robot.

Note
The members of this class are threadsafe.
End effector frame EE
While the end effector parameters are set in a configuration file, it is possible to change the end effector frame with Robot::setEE.

Stiffness frame K
The stiffness frame is used for Cartesian impedance control, and for measuring and applying forces. It can be set with Robot::setK.

Definition at line 42 of file robot.h.

Member Typedef Documentation

using franka::Robot::ServerVersion = uint16_t

Version of the robot server.

Definition at line 47 of file robot.h.

Constructor & Destructor Documentation

franka::Robot::Robot ( const std::string &  franka_address,
RealtimeConfig  realtime_config = RealtimeConfig::kEnforce,
size_t  log_size = 50 
)
explicit

Establishes a connection with the robot.

Parameters
[in]franka_addressIP/hostname of the robot.
[in]realtime_configif set to Enforce, an exception will be thrown if realtime priority cannot be set when required. Setting realtime_config to Ignore disables this behavior.
[in]log_sizesets how many last states should be kept for logging purposes. The log is provided when a ControlException is thrown.
Exceptions
NetworkExceptionif the connection is unsuccessful.
IncompatibleVersionExceptionif this version of libfranka is not supported.
franka::Robot::Robot ( Robot &&  other)
noexcept

Move-constructs a new Robot instance.

Parameters
[in]otherOther Robot instance.
franka::Robot::~Robot ( )
noexcept

Closes the connection.

Member Function Documentation

void franka::Robot::automaticErrorRecovery ( )

Runs automatic error recovery on the robot.

Automatic error recovery e.g. resets the robot after a collision occurred.

Exceptions
CommandExceptionif the Control reports an error.
NetworkExceptionif the connection is lost, e.g. after a timeout.
void franka::Robot::control ( std::function< Torques(const RobotState &, franka::Duration)>  control_callback,
bool  limit_rate = true,
double  cutoff_frequency = kDefaultCutoffFrequency 
)

Starts a control loop for sending joint-level torque commands.

Sets realtime priority for the current thread. Cannot be executed while another control or motion generator loop is active.

Parameters
[in]control_callbackCallback function providing joint-level torque commands. See here for more details.
[in]limit_rateTrue if rate limiting should be activated. True by default. This could distort your motion!
[in]cutoff_frequencyCutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to franka::kMaxCutoffFrequency to disable.
Exceptions
ControlExceptionif an error related to torque control or motion generation occurred.
InvalidOperationExceptionif a conflicting operation is already running.
NetworkExceptionif the connection is lost, e.g. after a timeout.
RealtimeExceptionif realtime priority cannot be set for the current thread.
std::invalid_argumentif joint-level torque commands are NaN or infinity.
See also
Robot::Robot to change behavior if realtime priority cannot be set.
void franka::Robot::control ( std::function< Torques(const RobotState &, franka::Duration)>  control_callback,
std::function< JointPositions(const RobotState &, franka::Duration)>  motion_generator_callback,
bool  limit_rate = true,
double  cutoff_frequency = kDefaultCutoffFrequency 
)

Starts a control loop for sending joint-level torque commands and joint positions.

Sets realtime priority for the current thread. Cannot be executed while another control or motion generator loop is active.

Parameters
[in]control_callbackCallback function providing joint-level torque commands. See here for more details.
[in]motion_generator_callbackCallback function for motion generation. See here for more details.
[in]limit_rateTrue if rate limiting should be activated. True by default. This could distort your motion!
[in]cutoff_frequencyCutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to franka::kMaxCutoffFrequency to disable.
Exceptions
ControlExceptionif an error related to torque control or motion generation occurred.
InvalidOperationExceptionif a conflicting operation is already running.
NetworkExceptionif the connection is lost, e.g. after a timeout.
RealtimeExceptionif realtime priority cannot be set for the current thread.
std::invalid_argumentif joint-level torque or joint position commands are NaN or infinity.
See also
Robot::Robot to change behavior if realtime priority cannot be set.
void franka::Robot::control ( std::function< Torques(const RobotState &, franka::Duration)>  control_callback,
std::function< JointVelocities(const RobotState &, franka::Duration)>  motion_generator_callback,
bool  limit_rate = true,
double  cutoff_frequency = kDefaultCutoffFrequency 
)

Starts a control loop for sending joint-level torque commands and joint velocities.

Sets realtime priority for the current thread. Cannot be executed while another control or motion generator loop is active.

Parameters
[in]control_callbackCallback function providing joint-level torque commands. See here for more details.
[in]motion_generator_callbackCallback function for motion generation. See here for more details.
[in]limit_rateTrue if rate limiting should be activated. True by default. This could distort your motion!
[in]cutoff_frequencyCutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to franka::kMaxCutoffFrequency to disable.
Exceptions
ControlExceptionif an error related to torque control or motion generation occurred.
InvalidOperationExceptionif a conflicting operation is already running.
NetworkExceptionif the connection is lost, e.g. after a timeout.
RealtimeExceptionif realtime priority cannot be set for the current thread.
std::invalid_argumentif joint-level torque or joint velocitiy commands are NaN or infinity.
See also
Robot::Robot to change behavior if realtime priority cannot be set.
void franka::Robot::control ( std::function< Torques(const RobotState &, franka::Duration)>  control_callback,
std::function< CartesianPose(const RobotState &, franka::Duration)>  motion_generator_callback,
bool  limit_rate = true,
double  cutoff_frequency = kDefaultCutoffFrequency 
)

Starts a control loop for sending joint-level torque commands and Cartesian poses.

Sets realtime priority for the current thread. Cannot be executed while another control or motion generator loop is active.

Parameters
[in]control_callbackCallback function providing joint-level torque commands. See here for more details.
[in]motion_generator_callbackCallback function for motion generation. See here for more details.
[in]limit_rateTrue if rate limiting should be activated. True by default. This could distort your motion!
[in]cutoff_frequencyCutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to franka::kMaxCutoffFrequency to disable.
Exceptions
ControlExceptionif an error related to torque control or motion generation occurred.
InvalidOperationExceptionif a conflicting operation is already running.
NetworkExceptionif the connection is lost, e.g. after a timeout.
RealtimeExceptionif realtime priority cannot be set for the current thread.
std::invalid_argumentif joint-level torque or Cartesian pose command elements are NaN or infinity.
See also
Robot::Robot to change behavior if realtime priority cannot be set.
void franka::Robot::control ( std::function< Torques(const RobotState &, franka::Duration)>  control_callback,
std::function< CartesianVelocities(const RobotState &, franka::Duration)>  motion_generator_callback,
bool  limit_rate = true,
double  cutoff_frequency = kDefaultCutoffFrequency 
)

Starts a control loop for sending joint-level torque commands and Cartesian velocities.

Sets realtime priority for the current thread. Cannot be executed while another control or motion generator loop is active.

Parameters
[in]control_callbackCallback function providing joint-level torque commands. See here for more details.
[in]motion_generator_callbackCallback function for motion generation. See here for more details.
[in]limit_rateTrue if rate limiting should be activated. True by default. This could distort your motion!
[in]cutoff_frequencyCutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to franka::kMaxCutoffFrequency to disable.
Exceptions
ControlExceptionif an error related to torque control or motion generation occurred.
InvalidOperationExceptionif a conflicting operation is already running.
NetworkExceptionif the connection is lost, e.g. after a timeout.
RealtimeExceptionif realtime priority cannot be set for the current thread.
std::invalid_argumentif joint-level torque or Cartesian velocity command elements are NaN or infinity.
See also
Robot::Robot to change behavior if realtime priority cannot be set.
void franka::Robot::control ( std::function< JointPositions(const RobotState &, franka::Duration)>  motion_generator_callback,
ControllerMode  controller_mode = ControllerMode::kJointImpedance,
bool  limit_rate = true,
double  cutoff_frequency = kDefaultCutoffFrequency 
)

Starts a control loop for a joint position motion generator with a given controller mode.

Sets realtime priority for the current thread. Cannot be executed while another control or motion generator loop is active.

Parameters
[in]motion_generator_callbackCallback function for motion generation. See here for more details.
[in]controller_modeController to use to execute the motion.
[in]limit_rateTrue if rate limiting should be activated. True by default. This could distort your motion!
[in]cutoff_frequencyCutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to franka::kMaxCutoffFrequency to disable.
Exceptions
ControlExceptionif an error related to motion generation occurred.
InvalidOperationExceptionif a conflicting operation is already running.
NetworkExceptionif the connection is lost, e.g. after a timeout.
RealtimeExceptionif realtime priority cannot be set for the current thread.
std::invalid_argumentif joint position commands are NaN or infinity.
See also
Robot::Robot to change behavior if realtime priority cannot be set.
void franka::Robot::control ( std::function< JointVelocities(const RobotState &, franka::Duration)>  motion_generator_callback,
ControllerMode  controller_mode = ControllerMode::kJointImpedance,
bool  limit_rate = true,
double  cutoff_frequency = kDefaultCutoffFrequency 
)

Starts a control loop for a joint velocity motion generator with a given controller mode.

Sets realtime priority for the current thread. Cannot be executed while another control or motion generator loop is active.

Parameters
[in]motion_generator_callbackCallback function for motion generation. See here for more details.
[in]controller_modeController to use to execute the motion.
[in]limit_rateTrue if rate limiting should be activated. True by default. This could distort your motion!
[in]cutoff_frequencyCutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to franka::kMaxCutoffFrequency to disable.
Exceptions
ControlExceptionif an error related to motion generation occurred.
InvalidOperationExceptionif a conflicting operation is already running.
NetworkExceptionif the connection is lost, e.g. after a timeout.
RealtimeExceptionif realtime priority cannot be set for the current thread.
std::invalid_argumentif joint velocity commands are NaN or infinity.
See also
Robot::Robot to change behavior if realtime priority cannot be set.
void franka::Robot::control ( std::function< CartesianPose(const RobotState &, franka::Duration)>  motion_generator_callback,
ControllerMode  controller_mode = ControllerMode::kJointImpedance,
bool  limit_rate = true,
double  cutoff_frequency = kDefaultCutoffFrequency 
)

Starts a control loop for a Cartesian pose motion generator with a given controller mode.

Sets realtime priority for the current thread. Cannot be executed while another control or motion generator loop is active.

Parameters
[in]motion_generator_callbackCallback function for motion generation. See here for more details.
[in]controller_modeController to use to execute the motion.
[in]limit_rateTrue if rate limiting should be activated. True by default. This could distort your motion!
[in]cutoff_frequencyCutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to franka::kMaxCutoffFrequency to disable.
Exceptions
ControlExceptionif an error related to motion generation occurred.
InvalidOperationExceptionif a conflicting operation is already running.
NetworkExceptionif the connection is lost, e.g. after a timeout.
RealtimeExceptionif realtime priority cannot be set for the current thread.
std::invalid_argumentif Cartesian pose command elements are NaN or infinity.
See also
Robot::Robot to change behavior if realtime priority cannot be set.
void franka::Robot::control ( std::function< CartesianVelocities(const RobotState &, franka::Duration)>  motion_generator_callback,
ControllerMode  controller_mode = ControllerMode::kJointImpedance,
bool  limit_rate = true,
double  cutoff_frequency = kDefaultCutoffFrequency 
)

Starts a control loop for a Cartesian velocity motion generator with a given controller mode.

Sets realtime priority for the current thread. Cannot be executed while another control or motion generator loop is active.

Parameters
[in]motion_generator_callbackCallback function for motion generation. See here for more details.
[in]controller_modeController to use to execute the motion.
[in]limit_rateTrue if rate limiting should be activated. True by default. This could distort your motion!
[in]cutoff_frequencyCutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to franka::kMaxCutoffFrequency to disable.
Exceptions
ControlExceptionif an error related to motion generation occurred.
InvalidOperationExceptionif a conflicting operation is already running.
NetworkExceptionif the connection is lost, e.g. after a timeout.
RealtimeExceptionif realtime priority cannot be set for the current thread.
std::invalid_argumentif Cartesian velocity command elements are NaN or infinity.
See also
Robot::Robot to change behavior if realtime priority cannot be set.
VirtualWallCuboid franka::Robot::getVirtualWall ( int32_t  id)

Returns the parameters of a virtual wall.

Parameters
[in]idID of the virtual wall.
Returns
Parameters of virtual wall.
Exceptions
CommandExceptionif the Control reports an error.
NetworkExceptionif the connection is lost, e.g. after a timeout.
Model franka::Robot::loadModel ( )

Loads the model library from the robot.

Returns
Model instance.
Exceptions
ModelExceptionif the model library cannot be loaded.
NetworkExceptionif the connection is lost, e.g. after a timeout.
Robot& franka::Robot::operator= ( Robot &&  other)
noexcept

Move-assigns this Robot from another Robot instance.

Parameters
[in]otherOther Robot instance.
Returns
Robot instance.
void franka::Robot::read ( std::function< bool(const RobotState &)>  read_callback)

Starts a loop for reading the current robot state.

Cannot be executed while a control or motion generator loop is running.

This minimal example will print the robot state 100 times:

franka::Robot robot("robot.franka.de");
size_t count = 0;
robot.read([&count](const franka::RobotState& robot_state) {
std::cout << robot_state << std::endl;
return count++ < 100;
});
Parameters
[in]read_callbackCallback function for robot state reading.
Exceptions
InvalidOperationExceptionif a conflicting operation is already running.
NetworkExceptionif the connection is lost, e.g. after a timeout.
RobotState franka::Robot::readOnce ( )

Waits for a robot state update and returns it.

Cannot be executed while a control or motion generator loop is running.

Returns
Current robot state.
Exceptions
InvalidOperationExceptionif a conflicting operation is already running.
NetworkExceptionif the connection is lost, e.g. after a timeout.
See also
Robot::read for a way to repeatedly receive the robot state.
ServerVersion franka::Robot::serverVersion ( ) const
noexcept

Returns the software version reported by the connected server.

Returns
Software version of the connected server.
void franka::Robot::setCartesianImpedance ( const std::array< double, 6 > &  K_x)

Sets the Cartesian impedance for (x, y, z, roll, pitch, yaw) in the internal controller.

User-provided torques are not affected by this setting.

Parameters
[in]K_xCartesian impedance values $K_x=(x, y, z, R, P, Y)$.
Exceptions
CommandExceptionif the Control reports an error.
NetworkExceptionif the connection is lost, e.g. after a timeout.
void franka::Robot::setCollisionBehavior ( const std::array< double, 7 > &  lower_torque_thresholds_acceleration,
const std::array< double, 7 > &  upper_torque_thresholds_acceleration,
const std::array< double, 7 > &  lower_torque_thresholds_nominal,
const std::array< double, 7 > &  upper_torque_thresholds_nominal,
const std::array< double, 6 > &  lower_force_thresholds_acceleration,
const std::array< double, 6 > &  upper_force_thresholds_acceleration,
const std::array< double, 6 > &  lower_force_thresholds_nominal,
const std::array< double, 6 > &  upper_force_thresholds_nominal 
)

Changes the collision behavior.

Set separate torque and force boundaries for acceleration/deceleration and constant velocity movement phases.

Forces or torques between lower and upper threshold are shown as contacts in the RobotState. Forces or torques above the upper threshold are registered as collision and cause the robot to stop moving.

Parameters
[in]lower_torque_thresholds_accelerationContact torque thresholds during acceleration/deceleration for each joint in $[Nm]$.
[in]upper_torque_thresholds_accelerationCollision torque thresholds during acceleration/deceleration for each joint in $[Nm]$.
[in]lower_torque_thresholds_nominalContact torque thresholds for each joint in $[Nm]$.
[in]upper_torque_thresholds_nominalCollision torque thresholds for each joint in $[Nm]$.
[in]lower_force_thresholds_accelerationContact force thresholds during acceleration/deceleration for $(x,y,z,R,P,Y)$ in $[N]$.
[in]upper_force_thresholds_accelerationCollision force thresholds during acceleration/deceleration for $(x,y,z,R,P,Y)$ in $[N]$.
[in]lower_force_thresholds_nominalContact force thresholds for $(x,y,z,R,P,Y)$ in $[N]$.
[in]upper_force_thresholds_nominalCollision force thresholds for $(x,y,z,R,P,Y)$ in $[N]$.
Exceptions
CommandExceptionif the Control reports an error.
NetworkExceptionif the connection is lost, e.g. after a timeout.
See also
RobotState::cartesian_contact
RobotState::cartesian_collision
RobotState::joint_contact
RobotState::joint_collision
Robot::automaticErrorRecovery for performing a reset after a collision.
void franka::Robot::setCollisionBehavior ( const std::array< double, 7 > &  lower_torque_thresholds,
const std::array< double, 7 > &  upper_torque_thresholds,
const std::array< double, 6 > &  lower_force_thresholds,
const std::array< double, 6 > &  upper_force_thresholds 
)

Changes the collision behavior.

Set common torque and force boundaries for acceleration/deceleration and constant velocity movement phases.

Forces or torques between lower and upper threshold are shown as contacts in the RobotState. Forces or torques above the upper threshold are registered as collision and cause the robot to stop moving.

Parameters
[in]lower_torque_thresholdsContact torque thresholds for each joint in $[Nm]$.
[in]upper_torque_thresholdsCollision torque thresholds for each joint in $[Nm]$.
[in]lower_force_thresholdsContact force thresholds for $(x,y,z,R,P,Y)$ in $[N]$.
[in]upper_force_thresholdsCollision force thresholds for $(x,y,z,R,P,Y)$ in $[N]$.
Exceptions
CommandExceptionif the Control reports an error.
NetworkExceptionif the connection is lost, e.g. after a timeout.
See also
RobotState::cartesian_contact
RobotState::cartesian_collision
RobotState::joint_contact
RobotState::joint_collision
Robot::automaticErrorRecovery for performing a reset after a collision.
void franka::Robot::setEE ( const std::array< double, 16 > &  F_T_EE)

Sets the transformation $^FT_{EE}$ from flange to end effector frame.

The transformation matrix is represented as a vectorized 4x4 matrix in column-major format.

Parameters
[in]F_T_EEVectorized flange-to-EE transformation matrix $^FT_{EE}$, column-major.
Exceptions
CommandExceptionif the Control reports an error.
NetworkExceptionif the connection is lost, e.g. after a timeout.
See also
RobotState::O_T_EE for end effector pose in world base frame.
Robot for an explanation of the EE frame.
void franka::Robot::setFilters ( double  joint_position_filter_frequency,
double  joint_velocity_filter_frequency,
double  cartesian_position_filter_frequency,
double  cartesian_velocity_filter_frequency,
double  controller_filter_frequency 
)

Sets the cut off frequency for the given motion generator or controller.

Deprecated:
Use franka::lowpassFilter() instead.

Allowed input range for all the filters is between 1.0 Hz and 1000.0 Hz. If the value is set to maximum (1000Hz) then no filtering is done.

Parameters
[in]joint_position_filter_frequencyFrequency at which the commanded joint position is cut off.
[in]joint_velocity_filter_frequencyFrequency at which the commanded joint velocity is cut off.
[in]cartesian_position_filter_frequencyFrequency at which the commanded Cartesian position is cut off.
[in]cartesian_velocity_filter_frequencyFrequency at which the commanded Cartesian velocity is cut off.
[in]controller_filter_frequencyFrequency at which the commanded torque is cut off.
Exceptions
CommandExceptionif the Control reports an error.
NetworkExceptionif the connection is lost, e.g. after a timeout.
void franka::Robot::setGuidingMode ( const std::array< bool, 6 > &  guiding_mode,
bool  elbow 
)

Locks or unlocks guiding mode movement in (x, y, z, roll, pitch, yaw).

If a flag is set to true, movement is unlocked.

Note
Guiding mode can be enabled by pressing the two opposing buttons near the robot's flange.
Parameters
[in]guiding_modeUnlocked movement in (x, y, z, R, P, Y) in guiding mode.
[in]elbowTrue if the elbow is free in guiding mode, false otherwise.
Exceptions
CommandExceptionif the Control reports an error.
NetworkExceptionif the connection is lost, e.g. after a timeout.
void franka::Robot::setJointImpedance ( const std::array< double, 7 > &  K_theta)

Sets the impedance for each joint in the internal controller.

User-provided torques are not affected by this setting.

Parameters
[in]K_thetaJoint impedance values $K_{\theta}$.
Exceptions
CommandExceptionif the Control reports an error.
NetworkExceptionif the connection is lost, e.g. after a timeout.
void franka::Robot::setK ( const std::array< double, 16 > &  EE_T_K)

Sets the transformation $^{EE}T_K$ from end effector frame to stiffness frame.

The transformation matrix is represented as a vectorized 4x4 matrix in column-major format.

Parameters
[in]EE_T_KVectorized EE-to-K transformation matrix $^{EE}T_K$, column-major.
Exceptions
CommandExceptionif the Control reports an error.
NetworkExceptionif the connection is lost, e.g. after a timeout.
See also
Robot for an explanation of the stiffness frame.
void franka::Robot::setLoad ( double  load_mass,
const std::array< double, 3 > &  F_x_Cload,
const std::array< double, 9 > &  load_inertia 
)

Sets dynamic parameters of a payload.

Note
This is not for setting end effector parameters, which have to be set in the administrator's interface.
Parameters
[in]load_massMass of the load in $[kg]$.
[in]F_x_CloadTranslation from flange to center of mass of load $^Fx_{C_\text{load}}$ in $[m]$.
[in]load_inertiaInertia matrix $I_\text{load}$ in $[kg \times m^2]$, column-major.
Exceptions
CommandExceptionif the Control reports an error.
NetworkExceptionif the connection is lost, e.g. after a timeout.
void franka::Robot::stop ( )

Stops all currently running motions.

If a control or motion generator loop is running in another thread, it will be preempted with a franka::ControlException.

Exceptions
CommandExceptionif the Control reports an error.
NetworkExceptionif the connection is lost, e.g. after a timeout.

Member Data Documentation

std::mutex franka::Robot::control_mutex_
private

Definition at line 689 of file robot.h.

std::unique_ptr<Impl> franka::Robot::impl_
private

Definition at line 685 of file robot.h.


The documentation for this class was generated from the following file:


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