3#include <franka/control_types.h>
4#include <franka/duration.h>
5#include <franka/exception.h>
6#include <franka/model.h>
7#include <franka/robot.h>
8#include <franka/robot_state.h>
39 using std::runtime_error::runtime_error;
47class Robot :
public franka::Robot {
99 "translational velocity", 1.7, 0.7, control_mutex_, [
this] {
return is_in_control_unsafe(); }};
105 "rotational velocity", 2.5, 2.5, control_mutex_, [
this] {
return is_in_control_unsafe(); }};
111 "elbow velocity", 2.175, 2.175, control_mutex_, [
this] {
return is_in_control_unsafe(); }};
117 "translational acceleration", 13.0, 2.0, control_mutex_, [
this] {
return is_in_control_unsafe(); }};
123 "rotational acceleration", 25.0, 10.0, control_mutex_, [
this] {
return is_in_control_unsafe(); }};
129 "elbow acceleration", 10.0, 4.0, control_mutex_, [
this] {
return is_in_control_unsafe(); }};
135 "translational jerk", 6500.0, 500.0, control_mutex_, [
this] {
return is_in_control_unsafe(); }};
141 "rotational jerk", 12500.0, 2000.0, control_mutex_, [
this] {
return is_in_control_unsafe(); }};
147 "elbow jerk", 5000.0, 800.0, control_mutex_, [
this] {
return is_in_control_unsafe(); }};
152#define MAX_JOINT_VEL toEigenD<7>({2.175, 2.175, 2.175, 2.175, 2.610, 2.610, 2.610})
155 [
this] {
return is_in_control_unsafe(); }
161#define MAX_JOINT_ACC toEigenD<7>({15.0, 7.5, 10.0, 12.5, 15.0, 20.0, 20.0})
164 [
this] {
return is_in_control_unsafe(); }
170#define MAX_JOINT_JERK toEigenD<7>({7500.0, 3750.0, 5000.0, 6250.0, 7500.0, 10000.0, 10000.0})
173 [
this] {
return is_in_control_unsafe(); }
195 using franka::Robot::setCollisionBehavior;
352 std::unique_lock
lock(*control_mutex_);
353 return joinMotionUnsafe(
lock);
363 template <
class Rep,
class Period>
365 std::unique_lock
lock(*control_mutex_);
376 return joinMotion(std::chrono::milliseconds(0));
433 std::shared_ptr<const Model> model_;
438 template <
typename ControlSignalType>
439 using ControlFunc = std::function<
ControlSignalType(
const franka::RobotState &, franka::Duration)>;
440 using MotionGeneratorVariant = std::variant<
446 std::string fci_hostname_;
449 std::mutex state_mutex_;
450 std::shared_ptr<std::mutex> control_mutex_;
451 std::condition_variable control_finished_condition_;
452 std::exception_ptr control_exception_;
453 std::thread control_thread_;
454 MotionGeneratorVariant motion_generator_{std::nullopt};
455 bool motion_generator_running_{
false};
463 [[
nodiscard]]
bool is_in_control_unsafe()
const;
465 template <
class Rep =
long,
class Period = std::ratio<1>>
466 bool joinMotionUnsafe(
467 std::unique_lock<std::mutex> &
lock,
468 const std::optional<std::chrono::duration<Rep, Period>> &
timeout = std::nullopt) {
469 while (motion_generator_running_) {
471 if (control_finished_condition_.wait_for(
lock,
timeout.value()) == std::cv_status::timeout) {
475 control_finished_condition_.wait(
lock);
478 if (control_thread_.joinable()) control_thread_.join();
479 if (control_exception_ !=
nullptr) {
481 control_exception_ =
nullptr;
487 template <
typename ControlSignalType>
492 throw std::invalid_argument(
"The motion must not be null.");
495 std::unique_lock
lock(*control_mutex_);
496 if (is_in_control_unsafe() && motion_generator_running_) {
498 throw InvalidMotionTypeException(
499 "The type of motion cannot change during runtime. Please ensure that the "
500 "previous motion finished before using a new type of motion.");
502 std::get<MotionGenerator<ControlSignalType>>(motion_generator_).updateMotion(
motion);
504 joinMotionUnsafe(
lock);
507 auto motion_generator = &std::get<MotionGenerator<ControlSignalType>>(motion_generator_);
510 std::lock_guard
lock(state_mutex_);
513 motion_generator_running_ =
true;
527 std::unique_lock
lock(*control_mutex_);
536 motion_generator_running_ =
false;
537 control_finished_condition_.notify_all();
541 std::unique_lock
lock(*control_mutex_);
542 control_exception_ = std::current_exception();
543 motion_generator_running_ =
false;
544 control_finished_condition_.notify_all();
Definition cartesian_state.hpp:17
RobotPose pose() const
Definition cartesian_state.hpp:60
RobotVelocity velocity() const
Definition cartesian_state.hpp:67
A template class representing a dynamics limit with a maximum value.
Definition dynamics_limit.hpp:21
Elbow state of the robot.
Definition elbow_state.hpp:27
Joint state of a robot.
Definition joint_state.hpp:15
Vector7d velocity() const
The velocity component of the state.
Definition joint_state.hpp:49
Vector7d position() const
The position component of the state.
Definition joint_state.hpp:42
Helper class for handling motions and reactions.
Definition motion_generator.hpp:31
Base class for motions.
Definition motion.hpp:23
Relative dynamics factors.
Definition relative_dynamics_factor.hpp:13
A class representing a Franka robot.
Definition robot.hpp:47
DynamicsLimit< Vector7d > joint_acceleration_limit
Definition robot.hpp:162
void move(const std::shared_ptr< Motion< franka::JointPositions > > &motion, bool async=false)
Execute the given motion.
Definition robot.hpp:408
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 m...
Definition robot.hpp:364
std::optional< ControlSignalType > current_control_signal_type()
The type of the current control signal.
Definition robot.cpp:117
void move(const std::shared_ptr< Motion< franka::CartesianPose > > &motion, bool async=false)
Execute the given motion.
Definition robot.hpp:386
std::string fci_hostname() const
The hostname of the robot.
Definition robot.cpp:113
Vector7d currentJointVelocities()
Returns the current joint velocities of the robot.
Definition robot.hpp:298
bool joinMotion()
Wait for the current motion to finish. Throw any exceptions that occurred during the motion.
Definition robot.hpp:351
static constexpr double control_rate
Definition robot.hpp:182
DynamicsLimit< double > elbow_acceleration_limit
Elbow acceleration limit [rad/s²].
Definition robot.hpp:128
RelativeDynamicsFactor relative_dynamics_factor()
Returns the current global relative dynamics factor of the robot.
Definition robot.cpp:132
Vector7d currentJointPositions()
Returns the current joint positions of the robot.
Definition robot.hpp:292
void move(const std::shared_ptr< Motion< franka::Torques > > &motion, bool async=false)
Execute the given motion.
Definition robot.hpp:428
CartesianState currentCartesianState()
Returns the current cartesian state of the robot.
Definition robot.hpp:273
DynamicsLimit< Vector7d > joint_velocity_limit
Definition robot.hpp:153
RobotState state()
Returns the current state of the robot.
Definition robot.cpp:56
DynamicsLimit< double > translation_jerk_limit
Translational jerk limit [m/s³].
Definition robot.hpp:134
DynamicsLimit< double > translation_velocity_limit
Translational velocity limit [m/s].
Definition robot.hpp:98
bool recoverFromErrors()
Calls the automatic error recovery of the robot and returns whether the recovery was successful.
Definition robot.cpp:51
DynamicsLimit< double > elbow_velocity_limit
Elbow velocity limit [rad/s].
Definition robot.hpp:110
DynamicsLimit< double > rotation_velocity_limit
Rotational velocity limit [rad/s].
Definition robot.hpp:104
DynamicsLimit< double > elbow_jerk_limit
Elbow jerk limit [rad/s³].
Definition robot.hpp:146
bool is_in_control()
Whether the robot is currently in control, i.e. a motion is being executed.
Definition robot.cpp:108
void move(const std::shared_ptr< Motion< franka::JointVelocities > > &motion, bool async=false)
Execute the given motion.
Definition robot.hpp:418
DynamicsLimit< Vector7d > joint_jerk_limit
Definition robot.hpp:171
JointState currentJointState()
Returns the current joint state of the robot.
Definition robot.hpp:283
void setCollisionBehavior(const ScalarOrArray< 7 > &torque_threshold, const ScalarOrArray< 6 > &force_threshold)
Set the collision behavior of the robot.
Definition robot.cpp:67
static constexpr size_t degrees_of_freedoms
Definition robot.hpp:179
RobotVelocity currentCartesianVelocity()
Returns the current cartesian velocity of the robot.
Definition robot.hpp:267
DynamicsLimit< double > rotation_jerk_limit
Rotational jerk limit [rad/s³].
Definition robot.hpp:140
void move(const std::shared_ptr< Motion< franka::CartesianVelocities > > &motion, bool async=false)
Execute the given motion.
Definition robot.hpp:396
void setRelativeDynamicsFactor(const RelativeDynamicsFactor &relative_dynamics_factor)
Sets the global relative dynamics factor of the robot.
Definition robot.cpp:137
std::shared_ptr< const Model > model() const
The model of the robot.
Definition robot.hpp:338
DynamicsLimit< double > translation_acceleration_limit
Translational acceleration limit [m/s²].
Definition robot.hpp:116
bool hasErrors()
Returns whether the robot has errors.
Definition robot.cpp:47
RobotPose currentPose()
Returns the current pose of the robot.
Definition robot.hpp:261
DynamicsLimit< double > rotation_acceleration_limit
Rotational acceleration limit [rad/s²].
Definition robot.hpp:122
bool pollMotion()
Check whether the robot is still in motion. This function is non-blocking and returns immediately....
Definition robot.hpp:375
Cartesian pose of a robot.
Definition robot_pose.hpp:17
Cartesian velocity of a robot.
Definition robot_velocity.hpp:19
Definition dynamics_limit.cpp:8
std::array< double, dims > toStdD(const Eigen::Matrix< double, dims, 1 > &vector)
Definition util.hpp:18
Eigen::Vector< double, 7 > Vector7d
Definition types.hpp:12
ControlSignalType
Type of control signal.
Definition control_signal_type.hpp:8
std::variant< double, Array< dims > > ScalarOrArray
Definition types.hpp:22
Eigen::Affine3d Affine
Definition types.hpp:16
#define MAX_JOINT_JERK
Joint jerk limit [rad/s³].
Definition robot.hpp:170
#define MAX_JOINT_ACC
Joint acceleration limit [rad/s²].
Definition robot.hpp:161
#define MAX_JOINT_VEL
Joint velocity limit [rad/s].
Definition robot.hpp:152
Exception thrown when an invalid motion type is used.
Definition robot.hpp:38
Global parameters for the robot.
Definition robot.hpp:52
RelativeDynamicsFactor relative_dynamics_factor
Relative dynamics factor for the robot.
Definition robot.hpp:58
double default_force_threshold
Default force threshold for collision behavior.
Definition robot.hpp:68
franka::ControllerMode controller_mode
Default controller mode for the robot.
Definition robot.hpp:75
double joint_acceleration_estimator_decay
Joint acceleration estimator decay.
Definition robot.hpp:91
franka::RealtimeConfig realtime_config
Default realtime configuration for the robot.
Definition robot.hpp:82
double default_torque_threshold
Default torque threshold for collision behavior.
Definition robot.hpp:63
Full state of the robot.
Definition robot_state.hpp:20