libfranka 0.15.0
FCI C++ API
Loading...
Searching...
No Matches
Public Types | Public Member Functions | Protected Member Functions | 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.
 

Public Member Functions

 Robot (const std::string &franka_address, RealtimeConfig realtime_config=RealtimeConfig::kEnforce, size_t log_size=50)
 Establishes a connection with the robot.
 
 Robot (Robot &&other) noexcept
 Move-constructs a new Robot instance.
 
Robotoperator= (Robot &&other) noexcept
 Move-assigns this Robot from another Robot instance.
 
virtual ~Robot () noexcept
 Closes the connection.
 
void read (std::function< bool(const RobotState &)> read_callback)
 Starts a loop for reading the current robot state.
 
virtual RobotState readOnce ()
 Waits for a robot state update and returns it.
 
Model loadModel ()
 Loads the model library from the robot.
 
Model loadModel (std::unique_ptr< RobotModelBase > robot_model)
 
ServerVersion serverVersion () const noexcept
 Returns the software version reported by the connected server.
 
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;
}
Represents a duration with millisecond resolution.
Definition duration.h:19
Stores values for joint position motion generation.
Definition control_types.h:72
Torques MotionFinished(Torques command) noexcept
Helper method to indicate that a motion should stop after processing the given command.
Definition control_types.h:294
Describes the robot state.
Definition robot_state.h:34
void control (std::function< Torques(const RobotState &, franka::Duration)> control_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)
 Starts a control loop for sending joint-level torque commands.
 
void control (std::function< Torques(const RobotState &, franka::Duration)> control_callback, std::function< JointPositions(const RobotState &, franka::Duration)> motion_generator_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)
 Starts a control loop for sending joint-level torque commands and joint positions.
 
void control (std::function< Torques(const RobotState &, franka::Duration)> control_callback, std::function< JointVelocities(const RobotState &, franka::Duration)> motion_generator_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)
 Starts a control loop for sending joint-level torque commands and joint velocities.
 
void control (std::function< Torques(const RobotState &, franka::Duration)> control_callback, std::function< CartesianPose(const RobotState &, franka::Duration)> motion_generator_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)
 Starts a control loop for sending joint-level torque commands and Cartesian poses.
 
void control (std::function< Torques(const RobotState &, franka::Duration)> control_callback, std::function< CartesianVelocities(const RobotState &, franka::Duration)> motion_generator_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)
 Starts a control loop for sending joint-level torque commands and Cartesian velocities.
 
void control (std::function< JointPositions(const RobotState &, franka::Duration)> motion_generator_callback, ControllerMode controller_mode=ControllerMode::kJointImpedance, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)
 Starts a control loop for a joint position motion generator with a given controller mode.
 
void control (std::function< JointVelocities(const RobotState &, franka::Duration)> motion_generator_callback, ControllerMode controller_mode=ControllerMode::kJointImpedance, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)
 Starts a control loop for a joint velocity motion generator with a given controller mode.
 
void control (std::function< CartesianPose(const RobotState &, franka::Duration)> motion_generator_callback, ControllerMode controller_mode=ControllerMode::kJointImpedance, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)
 Starts a control loop for a Cartesian pose motion generator with a given controller mode.
 
void control (std::function< CartesianVelocities(const RobotState &, franka::Duration)> motion_generator_callback, ControllerMode controller_mode=ControllerMode::kJointImpedance, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency)
 Starts a control loop for a Cartesian velocity motion generator with a given controller mode.
 
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.

auto getRobotModel () -> std::string
 
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.
 
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.
 
void setJointImpedance (const std::array< double, 7 > &K_theta)
 Sets the impedance for each joint in the internal controller.
 
void setCartesianImpedance (const std::array< double, 6 > &K_x)
 Sets the Cartesian stiffness/compliance (for x, y, z, roll, pitch, yaw) in the internal controller.
 
void setGuidingMode (const std::array< bool, 6 > &guiding_mode, bool elbow)
 Locks or unlocks guiding mode movement in (x, y, z, roll, pitch, yaw).
 
void setK (const std::array< double, 16 > &EE_T_K)
 Sets the transformation \(^{EE}T_K\) from end effector frame to stiffness frame.
 
void setEE (const std::array< double, 16 > &NE_T_EE)
 Sets the transformation \(^{NE}T_{EE}\) from nominal end effector to end effector frame.
 
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.
 
void automaticErrorRecovery ()
 Runs automatic error recovery on the robot.
 
virtual std::unique_ptr< ActiveControlBasestartTorqueControl ()
 Starts a new torque controller.
 
virtual std::unique_ptr< ActiveControlBasestartJointPositionControl (const research_interface::robot::Move::ControllerMode &control_type)
 Starts a new joint position motion generator.
 
virtual std::unique_ptr< ActiveControlBasestartJointVelocityControl (const research_interface::robot::Move::ControllerMode &control_type)
 Starts a new joint velocity motion generator.
 
virtual std::unique_ptr< ActiveControlBasestartCartesianPoseControl (const research_interface::robot::Move::ControllerMode &control_type)
 Starts a new cartesian position motion generator.
 
virtual std::unique_ptr< ActiveControlBasestartCartesianVelocityControl (const research_interface::robot::Move::ControllerMode &control_type)
 Starts a new cartesian velocity motion generator.
 
void stop ()
 Stops all currently running motions.
 

Protected Member Functions

 Robot (std::shared_ptr< Impl > robot_impl)
 Constructs a new Robot given a Robot::Impl.
 
 Robot ()=default
 Default constructor to enable mocking and testing.
 

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.

Base frame O
The base frame is located at the center of the robot's base. Its z-axis is identical with the axis of rotation of the first joint.

Flange frame F
The flange frame is located at the center of the flange surface. Its z-axis is identical with the axis of rotation of the last joint. This frame is fixed and cannot be changed.

Nominal end effector frame NE
The nominal end effector frame is configured outside of libfranka (in DESK) and cannot be changed here. It may be used to set end effector frames which are rarely changed.

end effector frame EE
By default, the end effector frame EE is the same as the nominal end effector frame NE (i.e. the transformation between NE and EE is the identity transformation). It may be used to set end effector frames which are changed more frequently (such as a tool that is grasped with the end effector). With Robot::setEE, a custom transformation matrix can be set.

Stiffness frame K
This frame describes the transformation from the end effector frame EE to the stiffness frame K. The stiffness frame is used for Cartesian impedance control, and for measuring and applying forces. The values set using Robot::setCartesianImpedance are used in the direction of the stiffness frame. It can be set with Robot::setK. This frame allows to modify the compliance behavior of the robot (e.g. to have a low stiffness around a specific point which is not the end effector). The stiffness frame does not affect where the robot will move to. The user should always command the desired end effector frame (and not the desired stiffness frame).
Examples
cartesian_impedance_control.cpp, communication_test.cpp, echo_robot_state.cpp, force_control.cpp, generate_cartesian_pose_motion.cpp, generate_cartesian_pose_motion_external_control_loop.cpp, generate_cartesian_velocity_motion.cpp, generate_cartesian_velocity_motion_external_control_loop.cpp, generate_consecutive_motions.cpp, generate_elbow_motion.cpp, generate_joint_position_motion.cpp, generate_joint_position_motion_external_control_loop.cpp, generate_joint_velocity_motion.cpp, generate_joint_velocity_motion_external_control_loop.cpp, joint_impedance_control.cpp, joint_point_to_point_motion.cpp, motion_with_control.cpp, motion_with_control_external_control_loop.cpp, and print_joint_poses.cpp.

Constructor & Destructor Documentation

◆ Robot() [1/3]

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.

◆ Robot() [2/3]

franka::Robot::Robot ( Robot &&  other)
noexcept

Move-constructs a new Robot instance.

Parameters
[in]otherOther Robot instance.

◆ Robot() [3/3]

franka::Robot::Robot ( std::shared_ptr< Impl >  robot_impl)
protected

Constructs a new Robot given a Robot::Impl.

This enables unittests with Robot::Impl-Mocks.

Parameters
robot_implRobot::Impl to use

Member Function Documentation

◆ automaticErrorRecovery()

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.
Examples
generate_consecutive_motions.cpp.

◆ control() [1/9]

void franka::Robot::control ( std::function< CartesianPose(const RobotState &, franka::Duration)>  motion_generator_callback,
ControllerMode  controller_mode = ControllerMode::kJointImpedance,
bool  limit_rate = false,
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. False 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.

◆ control() [2/9]

void franka::Robot::control ( std::function< CartesianVelocities(const RobotState &, franka::Duration)>  motion_generator_callback,
ControllerMode  controller_mode = ControllerMode::kJointImpedance,
bool  limit_rate = false,
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. False 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.

◆ control() [3/9]

void franka::Robot::control ( std::function< JointPositions(const RobotState &, franka::Duration)>  motion_generator_callback,
ControllerMode  controller_mode = ControllerMode::kJointImpedance,
bool  limit_rate = false,
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. False 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.

◆ control() [4/9]

void franka::Robot::control ( std::function< JointVelocities(const RobotState &, franka::Duration)>  motion_generator_callback,
ControllerMode  controller_mode = ControllerMode::kJointImpedance,
bool  limit_rate = false,
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. False 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.

◆ control() [5/9]

void franka::Robot::control ( std::function< Torques(const RobotState &, franka::Duration)>  control_callback,
bool  limit_rate = false,
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. False 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.
Examples
cartesian_impedance_control.cpp, communication_test.cpp, force_control.cpp, generate_cartesian_pose_motion.cpp, generate_cartesian_pose_motion_external_control_loop.cpp, generate_cartesian_velocity_motion.cpp, generate_cartesian_velocity_motion_external_control_loop.cpp, generate_consecutive_motions.cpp, generate_elbow_motion.cpp, generate_joint_position_motion.cpp, generate_joint_position_motion_external_control_loop.cpp, generate_joint_velocity_motion.cpp, generate_joint_velocity_motion_external_control_loop.cpp, and joint_point_to_point_motion.cpp.

◆ control() [6/9]

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 = false,
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. False 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.

◆ control() [7/9]

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 = false,
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. False 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.

◆ control() [8/9]

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 = false,
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. False 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.

◆ control() [9/9]

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 = false,
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. False 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 velocity commands are NaN or infinity.
See also
Robot::Robot to change behavior if realtime priority cannot be set.

◆ getRobotModel()

auto franka::Robot::getRobotModel ( ) -> std::string
Exceptions
CommandExceptionif the Control reports an error.
NetworkExceptionif the connection is lost, e.g. after a timeout.
Returns
std::string Provides the URDF model of the attached robot arm as json string

◆ loadModel()

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.
Examples
cartesian_impedance_control.cpp, and force_control.cpp.

◆ operator=()

Robot & franka::Robot::operator= ( Robot &&  other)
noexcept

Move-assigns this Robot from another Robot instance.

Parameters
[in]otherOther Robot instance.
Returns
Robot instance.

◆ read()

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;
});
Maintains a network connection to the robot, provides the current robot state, gives access to the mo...
Definition robot.h:68
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.
Examples
echo_robot_state.cpp.

◆ readOnce()

virtual RobotState franka::Robot::readOnce ( )
virtual

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.
Examples
cartesian_impedance_control.cpp, and force_control.cpp.

◆ serverVersion()

ServerVersion franka::Robot::serverVersion ( ) const
noexcept

Returns the software version reported by the connected server.

Returns
Software version of the connected server.

◆ setCartesianImpedance()

void franka::Robot::setCartesianImpedance ( const std::array< double, 6 > &  K_x)

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

The values set using Robot::setCartesianImpedance are used in the direction of the stiffness frame, which can be set with Robot::setK.

Inputs received by the torque controller are not affected by this setting.

Parameters
[in]K_xCartesian impedance values \(K_x=(K_{x_{x,y,z}} \in [10,3000] \frac{N}{m}, K_{x_{R,P,Y}} \in [1,300] \frac{Nm}{rad})\)
Exceptions
CommandExceptionif the Control reports an error.
NetworkExceptionif the connection is lost, e.g. after a timeout.

◆ setCollisionBehavior() [1/2]

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.

◆ setCollisionBehavior() [2/2]

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.
Examples
cartesian_impedance_control.cpp, communication_test.cpp, force_control.cpp, generate_cartesian_pose_motion.cpp, generate_cartesian_pose_motion_external_control_loop.cpp, generate_cartesian_velocity_motion.cpp, generate_cartesian_velocity_motion_external_control_loop.cpp, generate_consecutive_motions.cpp, generate_elbow_motion.cpp, generate_joint_position_motion.cpp, generate_joint_position_motion_external_control_loop.cpp, generate_joint_velocity_motion.cpp, generate_joint_velocity_motion_external_control_loop.cpp, and joint_point_to_point_motion.cpp.

◆ setEE()

void franka::Robot::setEE ( const std::array< double, 16 > &  NE_T_EE)

Sets the transformation \(^{NE}T_{EE}\) from nominal end effector to end effector frame.

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

Parameters
[in]NE_T_EEVectorized NE-to-EE transformation matrix \(^{NE}T_{EE}\), column-major.
Exceptions
CommandExceptionif the Control reports an error.
NetworkExceptionif the connection is lost, e.g. after a timeout.
See also
RobotState::NE_T_EE for end effector pose in nominal end effector frameNE". @see RobotState::O_T_EE for end effector pose in @ref o-frame "world base frame O". @see RobotState::F_T_EE for end effector pose in @ref f-frame "flange frame F".

◆ setGuidingMode()

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.

◆ setJointImpedance()

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_{1-7}} = \in [0,14250] \frac{Nm}{rad}\)
Exceptions
CommandExceptionif the Control reports an error.
NetworkExceptionif the connection is lost, e.g. after a timeout.
Examples
generate_cartesian_velocity_motion.cpp, and generate_cartesian_velocity_motion_external_control_loop.cpp.

◆ setK()

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.

◆ setLoad()

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.

◆ startCartesianPoseControl()

virtual std::unique_ptr< ActiveControlBase > franka::Robot::startCartesianPoseControl ( const research_interface::robot::Move::ControllerMode &  control_type)
virtual

Starts a new cartesian position motion generator.

Parameters
control_typeresearch_interface::robot::Move::ControllerMode control type for the operation
Returns
unique_ptr of ActiveMotionGenerator for the started motion
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.
std::invalid_argumentif joint-level torque commands are NaN or infinity.
Examples
generate_cartesian_pose_motion_external_control_loop.cpp.

◆ startCartesianVelocityControl()

virtual std::unique_ptr< ActiveControlBase > franka::Robot::startCartesianVelocityControl ( const research_interface::robot::Move::ControllerMode &  control_type)
virtual

Starts a new cartesian velocity motion generator.

Parameters
control_typeresearch_interface::robot::Move::ControllerMode control type for the operation
Returns
unique_ptr of ActiveMotionGenerator for the started motion
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.
std::invalid_argumentif joint-level torque commands are NaN or infinity.
Examples
generate_cartesian_velocity_motion_external_control_loop.cpp.

◆ startJointPositionControl()

virtual std::unique_ptr< ActiveControlBase > franka::Robot::startJointPositionControl ( const research_interface::robot::Move::ControllerMode &  control_type)
virtual

Starts a new joint position motion generator.

Parameters
control_typeresearch_interface::robot::Move::ControllerMode control type for the operation
Returns
unique_ptr of ActiveMotionGenerator for the started motion
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.
std::invalid_argumentif joint-level torque commands are NaN or infinity.
Examples
generate_joint_position_motion_external_control_loop.cpp.

◆ startJointVelocityControl()

virtual std::unique_ptr< ActiveControlBase > franka::Robot::startJointVelocityControl ( const research_interface::robot::Move::ControllerMode &  control_type)
virtual

Starts a new joint velocity motion generator.

Parameters
control_typeresearch_interface::robot::Move::ControllerMode control type for the operation
Returns
unique_ptr of ActiveMotionGenerator for the started motion
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.
std::invalid_argumentif joint-level torque commands are NaN or infinity.
Examples
generate_joint_velocity_motion_external_control_loop.cpp.

◆ startTorqueControl()

virtual std::unique_ptr< ActiveControlBase > franka::Robot::startTorqueControl ( )
virtual

Starts a new torque controller.

Returns
unique_ptr of ActiveTorqueControl for the started motion
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.
std::invalid_argumentif joint-level torque commands are NaN or infinity.
Examples
communication_test.cpp.

◆ stop()

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.

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