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... | |
Robot & | operator= (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:
The following incomplete example shows the general structure of a callback function: double time = 0.0; franka::Duration time_step) -> franka::JointPositions { 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 from end effector frame to stiffness frame. More... | |
void | setEE (const std::array< double, 16 > &F_T_EE) |
Sets the transformation 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_ |
Maintains a network connection to the robot, provides the current robot state, gives access to the model library and allows to control the robot.
using franka::Robot::ServerVersion = uint16_t |
|
explicit |
Establishes a connection with the robot.
[in] | franka_address | IP/hostname of the robot. |
[in] | realtime_config | if 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_size | sets how many last states should be kept for logging purposes. The log is provided when a ControlException is thrown. |
NetworkException | if the connection is unsuccessful. |
IncompatibleVersionException | if this version of libfranka is not supported. |
|
noexcept |
|
noexcept |
Closes the connection.
void franka::Robot::automaticErrorRecovery | ( | ) |
Runs automatic error recovery on the robot.
Automatic error recovery e.g. resets the robot after a collision occurred.
CommandException | if the Control reports an error. |
NetworkException | if 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.
[in] | control_callback | Callback function providing joint-level torque commands. See here for more details. |
[in] | limit_rate | True if rate limiting should be activated. True by default. This could distort your motion! |
[in] | cutoff_frequency | Cutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to franka::kMaxCutoffFrequency to disable. |
ControlException | if an error related to torque control or motion generation occurred. |
InvalidOperationException | if a conflicting operation is already running. |
NetworkException | if the connection is lost, e.g. after a timeout. |
RealtimeException | if realtime priority cannot be set for the current thread. |
std::invalid_argument | if joint-level torque commands are NaN or infinity. |
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.
[in] | control_callback | Callback function providing joint-level torque commands. See here for more details. |
[in] | motion_generator_callback | Callback function for motion generation. See here for more details. |
[in] | limit_rate | True if rate limiting should be activated. True by default. This could distort your motion! |
[in] | cutoff_frequency | Cutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to franka::kMaxCutoffFrequency to disable. |
ControlException | if an error related to torque control or motion generation occurred. |
InvalidOperationException | if a conflicting operation is already running. |
NetworkException | if the connection is lost, e.g. after a timeout. |
RealtimeException | if realtime priority cannot be set for the current thread. |
std::invalid_argument | if joint-level torque or joint position commands are NaN or infinity. |
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.
[in] | control_callback | Callback function providing joint-level torque commands. See here for more details. |
[in] | motion_generator_callback | Callback function for motion generation. See here for more details. |
[in] | limit_rate | True if rate limiting should be activated. True by default. This could distort your motion! |
[in] | cutoff_frequency | Cutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to franka::kMaxCutoffFrequency to disable. |
ControlException | if an error related to torque control or motion generation occurred. |
InvalidOperationException | if a conflicting operation is already running. |
NetworkException | if the connection is lost, e.g. after a timeout. |
RealtimeException | if realtime priority cannot be set for the current thread. |
std::invalid_argument | if joint-level torque or joint velocitiy commands are NaN or infinity. |
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.
[in] | control_callback | Callback function providing joint-level torque commands. See here for more details. |
[in] | motion_generator_callback | Callback function for motion generation. See here for more details. |
[in] | limit_rate | True if rate limiting should be activated. True by default. This could distort your motion! |
[in] | cutoff_frequency | Cutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to franka::kMaxCutoffFrequency to disable. |
ControlException | if an error related to torque control or motion generation occurred. |
InvalidOperationException | if a conflicting operation is already running. |
NetworkException | if the connection is lost, e.g. after a timeout. |
RealtimeException | if realtime priority cannot be set for the current thread. |
std::invalid_argument | if joint-level torque or Cartesian pose command elements are NaN or infinity. |
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.
[in] | control_callback | Callback function providing joint-level torque commands. See here for more details. |
[in] | motion_generator_callback | Callback function for motion generation. See here for more details. |
[in] | limit_rate | True if rate limiting should be activated. True by default. This could distort your motion! |
[in] | cutoff_frequency | Cutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to franka::kMaxCutoffFrequency to disable. |
ControlException | if an error related to torque control or motion generation occurred. |
InvalidOperationException | if a conflicting operation is already running. |
NetworkException | if the connection is lost, e.g. after a timeout. |
RealtimeException | if realtime priority cannot be set for the current thread. |
std::invalid_argument | if joint-level torque or Cartesian velocity command elements are NaN or infinity. |
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.
[in] | motion_generator_callback | Callback function for motion generation. See here for more details. |
[in] | controller_mode | Controller to use to execute the motion. |
[in] | limit_rate | True if rate limiting should be activated. True by default. This could distort your motion! |
[in] | cutoff_frequency | Cutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to franka::kMaxCutoffFrequency to disable. |
ControlException | if an error related to motion generation occurred. |
InvalidOperationException | if a conflicting operation is already running. |
NetworkException | if the connection is lost, e.g. after a timeout. |
RealtimeException | if realtime priority cannot be set for the current thread. |
std::invalid_argument | if joint position commands are NaN or infinity. |
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.
[in] | motion_generator_callback | Callback function for motion generation. See here for more details. |
[in] | controller_mode | Controller to use to execute the motion. |
[in] | limit_rate | True if rate limiting should be activated. True by default. This could distort your motion! |
[in] | cutoff_frequency | Cutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to franka::kMaxCutoffFrequency to disable. |
ControlException | if an error related to motion generation occurred. |
InvalidOperationException | if a conflicting operation is already running. |
NetworkException | if the connection is lost, e.g. after a timeout. |
RealtimeException | if realtime priority cannot be set for the current thread. |
std::invalid_argument | if joint velocity commands are NaN or infinity. |
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.
[in] | motion_generator_callback | Callback function for motion generation. See here for more details. |
[in] | controller_mode | Controller to use to execute the motion. |
[in] | limit_rate | True if rate limiting should be activated. True by default. This could distort your motion! |
[in] | cutoff_frequency | Cutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to franka::kMaxCutoffFrequency to disable. |
ControlException | if an error related to motion generation occurred. |
InvalidOperationException | if a conflicting operation is already running. |
NetworkException | if the connection is lost, e.g. after a timeout. |
RealtimeException | if realtime priority cannot be set for the current thread. |
std::invalid_argument | if Cartesian pose command elements are NaN or infinity. |
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.
[in] | motion_generator_callback | Callback function for motion generation. See here for more details. |
[in] | controller_mode | Controller to use to execute the motion. |
[in] | limit_rate | True if rate limiting should be activated. True by default. This could distort your motion! |
[in] | cutoff_frequency | Cutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to franka::kMaxCutoffFrequency to disable. |
ControlException | if an error related to motion generation occurred. |
InvalidOperationException | if a conflicting operation is already running. |
NetworkException | if the connection is lost, e.g. after a timeout. |
RealtimeException | if realtime priority cannot be set for the current thread. |
std::invalid_argument | if Cartesian velocity command elements are NaN or infinity. |
VirtualWallCuboid franka::Robot::getVirtualWall | ( | int32_t | id | ) |
Returns the parameters of a virtual wall.
[in] | id | ID of the virtual wall. |
CommandException | if the Control reports an error. |
NetworkException | if the connection is lost, e.g. after a timeout. |
Model franka::Robot::loadModel | ( | ) |
Loads the model library from the robot.
ModelException | if the model library cannot be loaded. |
NetworkException | if the connection is lost, e.g. after a timeout. |
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:
[in] | read_callback | Callback function for robot state reading. |
InvalidOperationException | if a conflicting operation is already running. |
NetworkException | if 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.
InvalidOperationException | if a conflicting operation is already running. |
NetworkException | if the connection is lost, e.g. after a timeout. |
|
noexcept |
Returns the software version reported by 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.
[in] | K_x | Cartesian impedance values . |
CommandException | if the Control reports an error. |
NetworkException | if 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.
[in] | lower_torque_thresholds_acceleration | Contact torque thresholds during acceleration/deceleration for each joint in . |
[in] | upper_torque_thresholds_acceleration | Collision torque thresholds during acceleration/deceleration for each joint in . |
[in] | lower_torque_thresholds_nominal | Contact torque thresholds for each joint in . |
[in] | upper_torque_thresholds_nominal | Collision torque thresholds for each joint in . |
[in] | lower_force_thresholds_acceleration | Contact force thresholds during acceleration/deceleration for in . |
[in] | upper_force_thresholds_acceleration | Collision force thresholds during acceleration/deceleration for in . |
[in] | lower_force_thresholds_nominal | Contact force thresholds for in . |
[in] | upper_force_thresholds_nominal | Collision force thresholds for in . |
CommandException | if the Control reports an error. |
NetworkException | if the connection is lost, e.g. after a timeout. |
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.
[in] | lower_torque_thresholds | Contact torque thresholds for each joint in . |
[in] | upper_torque_thresholds | Collision torque thresholds for each joint in . |
[in] | lower_force_thresholds | Contact force thresholds for in . |
[in] | upper_force_thresholds | Collision force thresholds for in . |
CommandException | if the Control reports an error. |
NetworkException | if the connection is lost, e.g. after a timeout. |
void franka::Robot::setEE | ( | const std::array< double, 16 > & | F_T_EE | ) |
Sets the transformation from flange to end effector frame.
The transformation matrix is represented as a vectorized 4x4 matrix in column-major format.
[in] | F_T_EE | Vectorized flange-to-EE transformation matrix , column-major. |
CommandException | if the Control reports an error. |
NetworkException | if the connection is lost, e.g. after a timeout. |
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.
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.
[in] | joint_position_filter_frequency | Frequency at which the commanded joint position is cut off. |
[in] | joint_velocity_filter_frequency | Frequency at which the commanded joint velocity is cut off. |
[in] | cartesian_position_filter_frequency | Frequency at which the commanded Cartesian position is cut off. |
[in] | cartesian_velocity_filter_frequency | Frequency at which the commanded Cartesian velocity is cut off. |
[in] | controller_filter_frequency | Frequency at which the commanded torque is cut off. |
CommandException | if the Control reports an error. |
NetworkException | if 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.
[in] | guiding_mode | Unlocked movement in (x, y, z, R, P, Y) in guiding mode. |
[in] | elbow | True if the elbow is free in guiding mode, false otherwise. |
CommandException | if the Control reports an error. |
NetworkException | if 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.
[in] | K_theta | Joint impedance values . |
CommandException | if the Control reports an error. |
NetworkException | if the connection is lost, e.g. after a timeout. |
void franka::Robot::setK | ( | const std::array< double, 16 > & | EE_T_K | ) |
Sets the transformation from end effector frame to stiffness frame.
The transformation matrix is represented as a vectorized 4x4 matrix in column-major format.
[in] | EE_T_K | Vectorized EE-to-K transformation matrix , column-major. |
CommandException | if the Control reports an error. |
NetworkException | if the connection is lost, e.g. after a timeout. |
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.
[in] | load_mass | Mass of the load in . |
[in] | F_x_Cload | Translation from flange to center of mass of load in . |
[in] | load_inertia | Inertia matrix in , column-major. |
CommandException | if the Control reports an error. |
NetworkException | if 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.
CommandException | if the Control reports an error. |
NetworkException | if the connection is lost, e.g. after a timeout. |