Franky 0.12.0
A High-Level Motion API for Franka
Loading...
Searching...
No Matches
Classes | Public Member Functions | Public Attributes | Static Public Attributes | List of all members
franky::Robot Class Reference

A class representing a Franka robot. More...

#include <robot.hpp>

Inheritance diagram for franky::Robot:

Classes

struct  Params
 Global parameters for the robot. More...
 

Public Member Functions

 Robot (const std::string &fci_hostname)
 Connects to a robot at the given FCI IP address.
 
 Robot (const std::string &fci_hostname, const Params &params)
 
void setCollisionBehavior (const ScalarOrArray< 7 > &torque_threshold, const ScalarOrArray< 6 > &force_threshold)
 Set the collision behavior of the robot.
 
void setCollisionBehavior (const ScalarOrArray< 7 > &lower_torque_threshold, const ScalarOrArray< 7 > &upper_torque_threshold, const ScalarOrArray< 6 > &lower_force_threshold, const ScalarOrArray< 6 > &upper_force_threshold)
 Set the collision behavior of the robot.
 
void setCollisionBehavior (const ScalarOrArray< 7 > &lower_torque_threshold_acceleration, const ScalarOrArray< 7 > &upper_torque_threshold_acceleration, const ScalarOrArray< 7 > &lower_torque_threshold_nominal, const ScalarOrArray< 7 > &upper_torque_threshold_nominal, const ScalarOrArray< 6 > &lower_force_threshold_acceleration, const ScalarOrArray< 6 > &upper_force_threshold_acceleration, const ScalarOrArray< 6 > &lower_force_threshold_nominal, const ScalarOrArray< 6 > &upper_force_threshold_nominal)
 Set the collision behavior of the robot.
 
bool recoverFromErrors ()
 Calls the automatic error recovery of the robot and returns whether the recovery was successful.
 
bool hasErrors ()
 Returns whether the robot has errors.
 
RobotPose currentPose ()
 Returns the current pose of the robot.
 
RobotVelocity currentCartesianVelocity ()
 Returns the current cartesian velocity of the robot.
 
CartesianState currentCartesianState ()
 Returns the current cartesian state of the robot.
 
JointState currentJointState ()
 Returns the current joint state of the robot.
 
Vector7d currentJointPositions ()
 Returns the current joint positions of the robot.
 
Vector7d currentJointVelocities ()
 Returns the current joint velocities of the robot.
 
RobotState state ()
 Returns the current state of the robot.
 
RelativeDynamicsFactor relative_dynamics_factor ()
 Returns the current global relative dynamics factor of the robot.
 
void setRelativeDynamicsFactor (const RelativeDynamicsFactor &relative_dynamics_factor)
 Sets the global relative dynamics factor of the robot.
 
bool is_in_control ()
 Whether the robot is currently in control, i.e. a motion is being executed.
 
std::string fci_hostname () const
 The hostname of the robot.
 
std::optional< ControlSignalTypecurrent_control_signal_type ()
 The type of the current control signal.
 
std::shared_ptr< const Modelmodel () const
 The model of the robot.
 
bool joinMotion ()
 Wait for the current motion to finish. Throw any exceptions that occurred during the motion.
 
template<class Rep , class Period >
bool joinMotion (const std::chrono::duration< Rep, Period > &timeout)
 Wait for the current motion to finish with a timeout. Throw any exceptions that occurred during the motion.
 
bool pollMotion ()
 Check whether the robot is still in motion. This function is non-blocking and returns immediately. Throw any exceptions that occurred during the motion.
 
void move (const std::shared_ptr< Motion< franka::CartesianPose > > &motion, bool async=false)
 Execute the given motion.
 
void move (const std::shared_ptr< Motion< franka::CartesianVelocities > > &motion, bool async=false)
 Execute the given motion.
 
void move (const std::shared_ptr< Motion< franka::JointPositions > > &motion, bool async=false)
 Execute the given motion.
 
void move (const std::shared_ptr< Motion< franka::JointVelocities > > &motion, bool async=false)
 Execute the given motion.
 
void move (const std::shared_ptr< Motion< franka::Torques > > &motion, bool async=false)
 Execute the given motion.
 

Public Attributes

DynamicsLimit< doubletranslation_velocity_limit
 Translational velocity limit [m/s].
 
DynamicsLimit< doublerotation_velocity_limit
 Rotational velocity limit [rad/s].
 
DynamicsLimit< doubleelbow_velocity_limit
 Elbow velocity limit [rad/s].
 
DynamicsLimit< doubletranslation_acceleration_limit
 Translational acceleration limit [m/s²].
 
DynamicsLimit< doublerotation_acceleration_limit
 Rotational acceleration limit [rad/s²].
 
DynamicsLimit< doubleelbow_acceleration_limit
 Elbow acceleration limit [rad/s²].
 
DynamicsLimit< doubletranslation_jerk_limit
 Translational jerk limit [m/s³].
 
DynamicsLimit< doublerotation_jerk_limit
 Rotational jerk limit [rad/s³].
 
DynamicsLimit< doubleelbow_jerk_limit
 Elbow jerk limit [rad/s³].
 
DynamicsLimit< Vector7djoint_velocity_limit
 
DynamicsLimit< Vector7djoint_acceleration_limit
 
DynamicsLimit< Vector7djoint_jerk_limit
 

Static Public Attributes

static constexpr size_t degrees_of_freedoms {7}
 
static constexpr double control_rate {0.001}
 

Detailed Description

A class representing a Franka robot.

This class extends the franka::Robot class and adds additional functionality to it.

Constructor & Destructor Documentation

◆ Robot() [1/2]

franky::Robot::Robot ( const std::string &  fci_hostname)
explicit

Connects to a robot at the given FCI IP address.

Parameters
fci_hostnameThe hostname or IP address of the robot.

◆ Robot() [2/2]

franky::Robot::Robot ( const std::string &  fci_hostname,
const Params params 
)
explicit
Parameters
fci_hostnameThe hostname or IP address of the robot.
paramsThe parameters for the robot.

Member Function Documentation

◆ current_control_signal_type()

std::optional< ControlSignalType > franky::Robot::current_control_signal_type ( )

The type of the current control signal.

◆ currentCartesianState()

CartesianState franky::Robot::currentCartesianState ( )
inline

Returns the current cartesian state of the robot.

Returns
The current cartesian state of the robot.

◆ currentCartesianVelocity()

RobotVelocity franky::Robot::currentCartesianVelocity ( )
inline

Returns the current cartesian velocity of the robot.

Returns
The current cartesian velocity of the robot.

◆ currentJointPositions()

Vector7d franky::Robot::currentJointPositions ( )
inline

Returns the current joint positions of the robot.

Returns
The current joint positions of the robot.

◆ currentJointState()

JointState franky::Robot::currentJointState ( )
inline

Returns the current joint state of the robot.

Returns
The current joint state of the robot.

◆ currentJointVelocities()

Vector7d franky::Robot::currentJointVelocities ( )
inline

Returns the current joint velocities of the robot.

Returns
The current joint velocities of the robot.

◆ currentPose()

RobotPose franky::Robot::currentPose ( )
inline

Returns the current pose of the robot.

Returns
The current pose of the robot.

◆ fci_hostname()

std::string franky::Robot::fci_hostname ( ) const

The hostname of the robot.

◆ hasErrors()

bool franky::Robot::hasErrors ( )

Returns whether the robot has errors.

Returns
Whether the robot has errors.

◆ is_in_control()

bool franky::Robot::is_in_control ( )

Whether the robot is currently in control, i.e. a motion is being executed.

◆ joinMotion() [1/2]

bool franky::Robot::joinMotion ( )
inline

Wait for the current motion to finish. Throw any exceptions that occurred during the motion.

◆ joinMotion() [2/2]

template<class Rep , class Period >
bool franky::Robot::joinMotion ( const std::chrono::duration< Rep, Period > &  timeout)
inline

Wait for the current motion to finish with a timeout. Throw any exceptions that occurred during the motion.

After the timeout has expired, the function will return false.

Parameters
timeoutThe timeout to wait for the motion to finish.
Returns
Whether the motion finished before the timeout expired.

◆ model()

std::shared_ptr< const Model > franky::Robot::model ( ) const
inline

The model of the robot.

The model is loaded in the constructor, so calling this function does not incur any overhead.

◆ move() [1/5]

void franky::Robot::move ( const std::shared_ptr< Motion< franka::CartesianPose > > &  motion,
bool  async = false 
)
inline

Execute the given motion.

Parameters
motionThe motion to execute.
asyncWhether to execute the motion asynchronously.

◆ move() [2/5]

void franky::Robot::move ( const std::shared_ptr< Motion< franka::CartesianVelocities > > &  motion,
bool  async = false 
)
inline

Execute the given motion.

Parameters
motionThe motion to execute.
asyncWhether to execute the motion asynchronously.

◆ move() [3/5]

void franky::Robot::move ( const std::shared_ptr< Motion< franka::JointPositions > > &  motion,
bool  async = false 
)
inline

Execute the given motion.

Parameters
motionThe motion to execute.
asyncWhether to execute the motion asynchronously.

◆ move() [4/5]

void franky::Robot::move ( const std::shared_ptr< Motion< franka::JointVelocities > > &  motion,
bool  async = false 
)
inline

Execute the given motion.

Parameters
motionThe motion to execute.
asyncWhether to execute the motion asynchronously.

◆ move() [5/5]

void franky::Robot::move ( const std::shared_ptr< Motion< franka::Torques > > &  motion,
bool  async = false 
)
inline

Execute the given motion.

Parameters
motionThe motion to execute.
asyncWhether to execute the motion asynchronously.

◆ pollMotion()

bool franky::Robot::pollMotion ( )
inline

Check whether the robot is still in motion. This function is non-blocking and returns immediately. Throw any exceptions that occurred during the motion.

Returns
Whether the robot is still in motion.

◆ recoverFromErrors()

bool franky::Robot::recoverFromErrors ( )

Calls the automatic error recovery of the robot and returns whether the recovery was successful.

Returns
Whether the recovery was successful.

◆ relative_dynamics_factor()

RelativeDynamicsFactor franky::Robot::relative_dynamics_factor ( )

Returns the current global relative dynamics factor of the robot.

Returns
The current relative dynamics factor of the robot.

◆ setCollisionBehavior() [1/3]

void franky::Robot::setCollisionBehavior ( const ScalarOrArray< 7 > &  lower_torque_threshold,
const ScalarOrArray< 7 > &  upper_torque_threshold,
const ScalarOrArray< 6 > &  lower_force_threshold,
const ScalarOrArray< 6 > &  upper_force_threshold 
)

Set the collision behavior of the robot.

Parameters
lower_torque_thresholdThe lower torque threshold for the collision behavior in Nm.
upper_torque_thresholdThe upper torque threshold for the collision behavior in Nm.
lower_force_thresholdThe lower force threshold for the collision behavior in N.
upper_force_thresholdThe upper force threshold for the collision behavior in N.

◆ setCollisionBehavior() [2/3]

void franky::Robot::setCollisionBehavior ( const ScalarOrArray< 7 > &  lower_torque_threshold_acceleration,
const ScalarOrArray< 7 > &  upper_torque_threshold_acceleration,
const ScalarOrArray< 7 > &  lower_torque_threshold_nominal,
const ScalarOrArray< 7 > &  upper_torque_threshold_nominal,
const ScalarOrArray< 6 > &  lower_force_threshold_acceleration,
const ScalarOrArray< 6 > &  upper_force_threshold_acceleration,
const ScalarOrArray< 6 > &  lower_force_threshold_nominal,
const ScalarOrArray< 6 > &  upper_force_threshold_nominal 
)

Set the collision behavior of the robot.

Parameters
lower_torque_threshold_accelerationThe lower torque threshold for the collision behavior in Nm during acceleration.
upper_torque_threshold_accelerationThe upper torque threshold for the collision behavior in Nm during acceleration.
lower_torque_threshold_nominalThe lower torque threshold for the collision behavior in Nm during nominal operation.
upper_torque_threshold_nominalThe upper torque threshold for the collision behavior in Nm during nominal operation.
lower_force_threshold_accelerationThe lower force threshold for the collision behavior in N during acceleration.
upper_force_threshold_accelerationThe upper force threshold for the collision behavior in N during acceleration.
lower_force_threshold_nominalThe lower force threshold for the collision behavior in N during nominal operation.
upper_force_threshold_nominalThe upper force threshold for the collision behavior in N during nominal operation.

◆ setCollisionBehavior() [3/3]

void franky::Robot::setCollisionBehavior ( const ScalarOrArray< 7 > &  torque_threshold,
const ScalarOrArray< 6 > &  force_threshold 
)

Set the collision behavior of the robot.

Parameters
torque_thresholdThe torque threshold for the collision behavior in Nm.
force_thresholdThe force threshold for the collision behavior in N.

◆ setRelativeDynamicsFactor()

void franky::Robot::setRelativeDynamicsFactor ( const RelativeDynamicsFactor relative_dynamics_factor)

Sets the global relative dynamics factor of the robot.

Parameters
relative_dynamics_factorThe relative dynamics factor to set.

◆ state()

RobotState franky::Robot::state ( )

Returns the current state of the robot.

Returns
The current state of the robot.

Member Data Documentation

◆ control_rate

constexpr double franky::Robot::control_rate {0.001}
staticconstexpr

Control rate of the robot [s]

◆ degrees_of_freedoms

constexpr size_t franky::Robot::degrees_of_freedoms {7}
staticconstexpr

Number of degrees of freedom of the robot

◆ elbow_acceleration_limit

DynamicsLimit<double> franky::Robot::elbow_acceleration_limit
Initial value:
{
"elbow acceleration", 10.0, 4.0, control_mutex_, [this] { return is_in_control_unsafe(); }}

Elbow acceleration limit [rad/s²].

◆ elbow_jerk_limit

DynamicsLimit<double> franky::Robot::elbow_jerk_limit
Initial value:
{
"elbow jerk", 5000.0, 800.0, control_mutex_, [this] { return is_in_control_unsafe(); }}

Elbow jerk limit [rad/s³].

◆ elbow_velocity_limit

DynamicsLimit<double> franky::Robot::elbow_velocity_limit
Initial value:
{
"elbow velocity", 2.175, 2.175, control_mutex_, [this] { return is_in_control_unsafe(); }}

Elbow velocity limit [rad/s].

◆ joint_acceleration_limit

DynamicsLimit<Vector7d> franky::Robot::joint_acceleration_limit
Initial value:
{
"joint_acceleration", MAX_JOINT_ACC, MAX_JOINT_ACC * 0.3, control_mutex_,
[this] { return is_in_control_unsafe(); }
}
#define MAX_JOINT_ACC
Joint acceleration limit [rad/s²].
Definition robot.hpp:161

◆ joint_jerk_limit

DynamicsLimit<Vector7d> franky::Robot::joint_jerk_limit
Initial value:
{
"joint_jerk", MAX_JOINT_JERK, MAX_JOINT_JERK * 0.3, control_mutex_,
[this] { return is_in_control_unsafe(); }
}
#define MAX_JOINT_JERK
Joint jerk limit [rad/s³].
Definition robot.hpp:170

◆ joint_velocity_limit

DynamicsLimit<Vector7d> franky::Robot::joint_velocity_limit
Initial value:
{
"joint_velocity", MAX_JOINT_VEL, MAX_JOINT_VEL, control_mutex_,
[this] { return is_in_control_unsafe(); }
}
#define MAX_JOINT_VEL
Joint velocity limit [rad/s].
Definition robot.hpp:152

◆ rotation_acceleration_limit

DynamicsLimit<double> franky::Robot::rotation_acceleration_limit
Initial value:
{
"rotational acceleration", 25.0, 10.0, control_mutex_, [this] { return is_in_control_unsafe(); }}

Rotational acceleration limit [rad/s²].

◆ rotation_jerk_limit

DynamicsLimit<double> franky::Robot::rotation_jerk_limit
Initial value:
{
"rotational jerk", 12500.0, 2000.0, control_mutex_, [this] { return is_in_control_unsafe(); }}

Rotational jerk limit [rad/s³].

◆ rotation_velocity_limit

DynamicsLimit<double> franky::Robot::rotation_velocity_limit
Initial value:
{
"rotational velocity", 2.5, 2.5, control_mutex_, [this] { return is_in_control_unsafe(); }}

Rotational velocity limit [rad/s].

◆ translation_acceleration_limit

DynamicsLimit<double> franky::Robot::translation_acceleration_limit
Initial value:
{
"translational acceleration", 13.0, 2.0, control_mutex_, [this] { return is_in_control_unsafe(); }}

Translational acceleration limit [m/s²].

◆ translation_jerk_limit

DynamicsLimit<double> franky::Robot::translation_jerk_limit
Initial value:
{
"translational jerk", 6500.0, 500.0, control_mutex_, [this] { return is_in_control_unsafe(); }}

Translational jerk limit [m/s³].

◆ translation_velocity_limit

DynamicsLimit<double> franky::Robot::translation_velocity_limit
Initial value:
{
"translational velocity", 1.7, 0.7, control_mutex_, [this] { return is_in_control_unsafe(); }}

Translational velocity limit [m/s].


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