Franky  0.9.1
A High-Level Motion API for Franka
Classes | Public Types | Public Member Functions | Static 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 Types

template<size_t dims>
using ScalarOrArray = std::variant< double, std::array< double, dims >, Eigen::Vector< double, dims > >
 

Public Member Functions

 Robot (const std::string &fci_hostname)
 Connects to a robot at the given FCI IP address. More...
 
 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. More...
 
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. More...
 
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. More...
 
bool recoverFromErrors ()
 Calls the automatic error recovery of the robot and returns whether the recovery was successful. More...
 
bool hasErrors ()
 Returns whether the robot has errors. More...
 
RobotPose currentPose ()
 Returns the current pose of the robot. More...
 
RobotVelocity currentCartesianVelocity ()
 Returns the current cartesian velocity of the robot. More...
 
CartesianState currentCartesianState ()
 Returns the current cartesian state of the robot. More...
 
JointState currentJointState ()
 Returns the current joint state of the robot. More...
 
Vector7d currentJointPositions ()
 Returns the current joint positions of the robot. More...
 
Vector7d currentJointVelocities ()
 Returns the current joint velocities of the robot. More...
 
franka::RobotState state ()
 Returns the current state of the robot. More...
 
RelativeDynamicsFactor relative_dynamics_factor ()
 Returns the current global relative dynamics factor of the robot. More...
 
void setRelativeDynamicsFactor (const RelativeDynamicsFactor &relative_dynamics_factor)
 Sets the global relative dynamics factor of the robot. More...
 
bool is_in_control ()
 Whether the robot is currently in control, i.e. a motion is being executed. More...
 
std::string fci_hostname () const
 The hostname of the robot. More...
 
std::optional< ControlSignalTypecurrent_control_signal_type ()
 The type of the current control signal. More...
 
bool joinMotion ()
 Wait for the current motion to finish. Throw any exceptions that occurred during the motion. More...
 
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. More...
 
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. More...
 
void move (const std::shared_ptr< Motion< franka::CartesianPose >> &motion, bool async=false)
 Execute the given motion. More...
 
void move (const std::shared_ptr< Motion< franka::CartesianVelocities >> &motion, bool async=false)
 Execute the given motion. More...
 
void move (const std::shared_ptr< Motion< franka::JointPositions >> &motion, bool async=false)
 Execute the given motion. More...
 
void move (const std::shared_ptr< Motion< franka::JointVelocities >> &motion, bool async=false)
 Execute the given motion. More...
 
void move (const std::shared_ptr< Motion< franka::Torques >> &motion, bool async=false)
 Execute the given motion. More...
 

Static Public Member Functions

static Vector7d inverseKinematics (const Affine &target, const Vector7d &q0)
 Calculate the inverse kinematics for the given target pose. More...
 
static Affine forwardKinematics (const Vector7d &q)
 Calculate the forward kinematics for the given joint positions. More...
 

Public Attributes

const KinematicChain< 7 > kinematics
 The kinematic chain of the robot. More...
 

Static Public Attributes

static constexpr double max_translation_velocity {1.7}
 
static constexpr double max_rotation_velocity {2.5}
 
static constexpr double max_elbow_velocity {2.175}
 
static constexpr double max_translation_acceleration {13.0}
 
static constexpr double max_rotation_acceleration {25.0}
 
static constexpr double max_elbow_acceleration {10.0}
 
static constexpr double max_translation_jerk {6500.0}
 
static constexpr double max_rotation_jerk {12500.0}
 
static constexpr double max_elbow_jerk {5000.0}
 
static constexpr std::array< double, 7 > max_joint_velocity
 
static constexpr std::array< double, 7 > max_joint_acceleration
 
static constexpr std::array< double, 7 > max_joint_jerk
 
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.

Member Typedef Documentation

◆ ScalarOrArray

template<size_t dims>
using franky::Robot::ScalarOrArray = std::variant<double, std::array<double, dims>, Eigen::Vector<double, dims> >

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 ( )

Returns the current joint positions of the robot.

Returns
The current joint positions of the robot.

◆ currentJointState()

JointState franky::Robot::currentJointState ( )

Returns the current joint state of the robot.

Returns
The current joint state of the robot.

◆ currentJointVelocities()

Vector7d franky::Robot::currentJointVelocities ( )

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.

◆ forwardKinematics()

Affine franky::Robot::forwardKinematics ( const Vector7d q)
static

Calculate the forward kinematics for the given joint positions.

Parameters
qThe joint positions.
Returns
The forward kinematics.

◆ hasErrors()

bool franky::Robot::hasErrors ( )

Returns whether the robot has errors.

Returns
Whether the robot has errors.

◆ inverseKinematics()

Vector7d franky::Robot::inverseKinematics ( const Affine target,
const Vector7d q0 
)
static

Calculate the inverse kinematics for the given target pose.

Parameters
targetThe target pose.
q0The initial guess for the joint positions.
Returns
A vector containing the joint positions.

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

◆ 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()

franka::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

◆ kinematics

const KinematicChain<7> franky::Robot::kinematics
Initial value:
= KinematicChain<7>(
{{
{0.0, 0.333, 0.0},
{-M_PI / 2, 0.0, 0.0},
{M_PI / 2, 0.316, 0.0},
{M_PI / 2, 0.0, 0.0825},
{-M_PI / 2, 0.384, -0.0825},
{M_PI / 2, 0.0, 0.0},
{M_PI / 2, 0.0, 0.088}}},
Affine().fromPositionOrientationScale(
Eigen::Vector3d(0, 0, 0.107),
Euler(M_PI / 4, 0, M_PI),
Eigen::Matrix<double, 3, 1>::Ones())
)
Eigen::EulerAngles< double, Eigen::EulerSystemXYZ > Euler
Definition: types.hpp:11
Eigen::Affine3d Affine
Definition: types.hpp:13

The kinematic chain of the robot.

◆ max_elbow_acceleration

constexpr double franky::Robot::max_elbow_acceleration {10.0}
staticconstexpr

Maximum elbow acceleration [rad/s²]

◆ max_elbow_jerk

constexpr double franky::Robot::max_elbow_jerk {5000.0}
staticconstexpr

Maximum elbow jerk [rad/s³]

◆ max_elbow_velocity

constexpr double franky::Robot::max_elbow_velocity {2.175}
staticconstexpr

Maximum elbow velocity [rad/s]

◆ max_joint_acceleration

constexpr std::array<double, 7> franky::Robot::max_joint_acceleration
staticconstexpr
Initial value:
{
{15.0, 7.5, 10.0, 12.5, 15.0, 20.0, 20.0}
}

Maximum joint acceleration [rad/s²]

◆ max_joint_jerk

constexpr std::array<double, 7> franky::Robot::max_joint_jerk
staticconstexpr
Initial value:
{
{7500.0, 3750.0, 5000.0, 6250.0, 7500.0, 10000.0, 10000.0}
}

Maximum joint jerk [rad/s³]

◆ max_joint_velocity

constexpr std::array<double, 7> franky::Robot::max_joint_velocity
staticconstexpr
Initial value:
{
{2.175, 2.175, 2.175, 2.175, 2.610, 2.610, 2.610}
}

Maximum joint velocity [rad/s]

◆ max_rotation_acceleration

constexpr double franky::Robot::max_rotation_acceleration {25.0}
staticconstexpr

Maximum rotational acceleration [rad/s²]

◆ max_rotation_jerk

constexpr double franky::Robot::max_rotation_jerk {12500.0}
staticconstexpr

Maximum rotational jerk [rad/s³]

◆ max_rotation_velocity

constexpr double franky::Robot::max_rotation_velocity {2.5}
staticconstexpr

Maximum rotational velocity [rad/s]

◆ max_translation_acceleration

constexpr double franky::Robot::max_translation_acceleration {13.0}
staticconstexpr

Maximum translational acceleration [m/s²]

◆ max_translation_jerk

constexpr double franky::Robot::max_translation_jerk {6500.0}
staticconstexpr

Maximum translational jerk [m/s³]

◆ max_translation_velocity

constexpr double franky::Robot::max_translation_velocity {1.7}
staticconstexpr

Maximum translational velocity [m/s]


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