Franky
0.9.1
A High-Level Motion API for Franka
|
A class representing a Franka robot. More...
#include <robot.hpp>
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 ¶ms) | |
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< ControlSignalType > | current_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} |
A class representing a Franka robot.
This class extends the franka::Robot class and adds additional functionality to it.
using franky::Robot::ScalarOrArray = std::variant<double, std::array<double, dims>, Eigen::Vector<double, dims> > |
|
explicit |
Connects to a robot at the given FCI IP address.
fci_hostname | The hostname or IP address of the robot. |
|
explicit |
fci_hostname | The hostname or IP address of the robot. |
params | The parameters for the robot. |
std::optional< ControlSignalType > franky::Robot::current_control_signal_type | ( | ) |
The type of the current control signal.
|
inline |
Returns the current cartesian state of the robot.
|
inline |
Returns the current cartesian velocity of the robot.
Vector7d franky::Robot::currentJointPositions | ( | ) |
Returns the current joint positions of the robot.
JointState franky::Robot::currentJointState | ( | ) |
Returns the current joint state of the robot.
Vector7d franky::Robot::currentJointVelocities | ( | ) |
Returns the current joint velocities of the robot.
|
inline |
Returns the current pose of the robot.
std::string franky::Robot::fci_hostname | ( | ) | const |
The hostname of the robot.
Calculate the forward kinematics for the given joint positions.
q | The joint positions. |
bool franky::Robot::hasErrors | ( | ) |
Returns whether the robot has errors.
Calculate the inverse kinematics for the given target pose.
target | The target pose. |
q0 | The initial guess for the joint positions. |
bool franky::Robot::is_in_control | ( | ) |
Whether the robot is currently in control, i.e. a motion is being executed.
|
inline |
Wait for the current motion to finish. Throw any exceptions that occurred during the motion.
|
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.
timeout | The timeout to wait for the motion to finish. |
|
inline |
Execute the given motion.
motion | The motion to execute. |
async | Whether to execute the motion asynchronously. |
|
inline |
Execute the given motion.
motion | The motion to execute. |
async | Whether to execute the motion asynchronously. |
|
inline |
Execute the given motion.
motion | The motion to execute. |
async | Whether to execute the motion asynchronously. |
|
inline |
Execute the given motion.
motion | The motion to execute. |
async | Whether to execute the motion asynchronously. |
|
inline |
Execute the given motion.
motion | The motion to execute. |
async | Whether to execute the motion asynchronously. |
|
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.
bool franky::Robot::recoverFromErrors | ( | ) |
Calls the automatic error recovery of the robot and returns whether the recovery was successful.
RelativeDynamicsFactor franky::Robot::relative_dynamics_factor | ( | ) |
Returns the current global relative dynamics factor of the robot.
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.
lower_torque_threshold | The lower torque threshold for the collision behavior in Nm. |
upper_torque_threshold | The upper torque threshold for the collision behavior in Nm. |
lower_force_threshold | The lower force threshold for the collision behavior in N. |
upper_force_threshold | The upper force threshold for the collision behavior in N. |
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.
lower_torque_threshold_acceleration | The lower torque threshold for the collision behavior in Nm during acceleration. |
upper_torque_threshold_acceleration | The upper torque threshold for the collision behavior in Nm during acceleration. |
lower_torque_threshold_nominal | The lower torque threshold for the collision behavior in Nm during nominal operation. |
upper_torque_threshold_nominal | The upper torque threshold for the collision behavior in Nm during nominal operation. |
lower_force_threshold_acceleration | The lower force threshold for the collision behavior in N during acceleration. |
upper_force_threshold_acceleration | The upper force threshold for the collision behavior in N during acceleration. |
lower_force_threshold_nominal | The lower force threshold for the collision behavior in N during nominal operation. |
upper_force_threshold_nominal | The upper force threshold for the collision behavior in N during nominal operation. |
void franky::Robot::setCollisionBehavior | ( | const ScalarOrArray< 7 > & | torque_threshold, |
const ScalarOrArray< 6 > & | force_threshold | ||
) |
Set the collision behavior of the robot.
torque_threshold | The torque threshold for the collision behavior in Nm. |
force_threshold | The force threshold for the collision behavior in N. |
void franky::Robot::setRelativeDynamicsFactor | ( | const RelativeDynamicsFactor & | relative_dynamics_factor | ) |
Sets the global relative dynamics factor of the robot.
relative_dynamics_factor | The relative dynamics factor to set. |
franka::RobotState franky::Robot::state | ( | ) |
Returns the current state of the robot.
|
staticconstexpr |
Control rate of the robot [s]
|
staticconstexpr |
Number of degrees of freedom of the robot
const KinematicChain<7> franky::Robot::kinematics |
The kinematic chain of the robot.
|
staticconstexpr |
Maximum elbow acceleration [rad/s²]
|
staticconstexpr |
Maximum elbow jerk [rad/s³]
|
staticconstexpr |
Maximum elbow velocity [rad/s]
|
staticconstexpr |
Maximum joint acceleration [rad/s²]
|
staticconstexpr |
Maximum joint jerk [rad/s³]
|
staticconstexpr |
Maximum joint velocity [rad/s]
|
staticconstexpr |
Maximum rotational acceleration [rad/s²]
|
staticconstexpr |
Maximum rotational jerk [rad/s³]
|
staticconstexpr |
Maximum rotational velocity [rad/s]
|
staticconstexpr |
Maximum translational acceleration [m/s²]
|
staticconstexpr |
Maximum translational jerk [m/s³]
|
staticconstexpr |
Maximum translational velocity [m/s]