Franky 0.12.0
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 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 ¶ms) | |
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< ControlSignalType > | current_control_signal_type () |
The type of the current control signal. | |
std::shared_ptr< const Model > | model () 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< double > | translation_velocity_limit |
Translational velocity limit [m/s]. | |
DynamicsLimit< double > | rotation_velocity_limit |
Rotational velocity limit [rad/s]. | |
DynamicsLimit< double > | elbow_velocity_limit |
Elbow velocity limit [rad/s]. | |
DynamicsLimit< double > | translation_acceleration_limit |
Translational acceleration limit [m/s²]. | |
DynamicsLimit< double > | rotation_acceleration_limit |
Rotational acceleration limit [rad/s²]. | |
DynamicsLimit< double > | elbow_acceleration_limit |
Elbow acceleration limit [rad/s²]. | |
DynamicsLimit< double > | translation_jerk_limit |
Translational jerk limit [m/s³]. | |
DynamicsLimit< double > | rotation_jerk_limit |
Rotational jerk limit [rad/s³]. | |
DynamicsLimit< double > | elbow_jerk_limit |
Elbow jerk limit [rad/s³]. | |
DynamicsLimit< Vector7d > | joint_velocity_limit |
DynamicsLimit< Vector7d > | joint_acceleration_limit |
DynamicsLimit< Vector7d > | joint_jerk_limit |
Static Public Attributes | |
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.
|
explicit |
Connects to a robot at the given FCI IP address.
fci_hostname | The hostname or IP address of the robot. |
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.
|
inline |
Returns the current joint positions of the robot.
|
inline |
Returns the current joint state of the robot.
|
inline |
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.
bool franky::Robot::hasErrors | ( | ) |
Returns whether the robot has errors.
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.
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. |
The model of the robot.
The model is loaded in the constructor, so calling this function does not incur any overhead.
|
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. |
RobotState franky::Robot::state | ( | ) |
Returns the current state of the robot.
Number of degrees of freedom of the robot
DynamicsLimit<double> franky::Robot::elbow_acceleration_limit |
Elbow acceleration limit [rad/s²].
DynamicsLimit<double> franky::Robot::elbow_jerk_limit |
Elbow jerk limit [rad/s³].
DynamicsLimit<double> franky::Robot::elbow_velocity_limit |
Elbow velocity limit [rad/s].
DynamicsLimit<Vector7d> franky::Robot::joint_acceleration_limit |
DynamicsLimit<Vector7d> franky::Robot::joint_jerk_limit |
DynamicsLimit<Vector7d> franky::Robot::joint_velocity_limit |
DynamicsLimit<double> franky::Robot::rotation_acceleration_limit |
Rotational acceleration limit [rad/s²].
DynamicsLimit<double> franky::Robot::rotation_jerk_limit |
Rotational jerk limit [rad/s³].
DynamicsLimit<double> franky::Robot::rotation_velocity_limit |
Rotational velocity limit [rad/s].
DynamicsLimit<double> franky::Robot::translation_acceleration_limit |
Translational acceleration limit [m/s²].
DynamicsLimit<double> franky::Robot::translation_jerk_limit |
Translational jerk limit [m/s³].
DynamicsLimit<double> franky::Robot::translation_velocity_limit |
Translational velocity limit [m/s].