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;
48class Robot :
public franka::Robot {
160 using franka::Robot::setCollisionBehavior;
326 std::unique_lock
lock(*control_mutex_);
327 return joinMotionUnsafe(
lock);
338 template <
class Rep,
class Period>
340 std::unique_lock
lock(*control_mutex_);
352 return joinMotion(std::chrono::milliseconds(0));
410 std::shared_ptr<const Model> model_;
415 template <
typename ControlSignalType>
416 using ControlFunc = std::function<
ControlSignalType(
const franka::RobotState &, franka::Duration)>;
417 using MotionGeneratorVariant = std::variant<
423 std::string fci_hostname_;
426 std::mutex state_mutex_;
427 std::shared_ptr<std::mutex> control_mutex_;
428 std::condition_variable control_finished_condition_;
429 std::exception_ptr control_exception_;
430 std::thread control_thread_;
431 MotionGeneratorVariant motion_generator_{std::nullopt};
432 bool motion_generator_running_{
false};
434 [[
nodiscard]]
bool is_in_control_unsafe()
const;
505 template <
class Rep =
long,
class Period = std::ratio<1>>
506 bool joinMotionUnsafe(
507 std::unique_lock<std::mutex> &
lock,
508 const std::optional<std::chrono::duration<Rep, Period>> &
timeout = std::nullopt) {
509 while (motion_generator_running_) {
511 if (control_finished_condition_.wait_for(
lock,
timeout.value()) == std::cv_status::timeout) {
515 control_finished_condition_.wait(
lock);
518 if (control_thread_.joinable()) control_thread_.join();
519 if (control_exception_ !=
nullptr) {
521 control_exception_ =
nullptr;
527 template <
typename ControlSignalType>
532 throw std::invalid_argument(
"The motion must not be null.");
535 std::unique_lock
lock(*control_mutex_);
536 if (is_in_control_unsafe() && motion_generator_running_) {
538 throw InvalidMotionTypeException(
539 "The type of motion cannot change during runtime. Please ensure "
541 "previous motion finished before using a new type of motion.");
543 std::get<MotionGenerator<ControlSignalType>>(motion_generator_).updateMotion(
motion);
545 joinMotionUnsafe(
lock);
548 auto motion_generator = &std::get<MotionGenerator<ControlSignalType>>(motion_generator_);
551 std::lock_guard
lock(state_mutex_);
554 motion_generator_running_ =
true;
559 params_.kalman_q_process_var,
560 params_.kalman_dq_process_var,
561 params_.kalman_ddq_process_var,
562 params_.kalman_control_process_var,
563 params_.kalman_q_obs_var,
564 params_.kalman_dq_obs_var,
565 params_.kalman_q_d_obs_var,
566 params_.kalman_dq_d_obs_var,
567 params_.kalman_ddq_d_obs_var,
568 params_.kalman_control_adaptation_rate);
574 std::unique_lock
lock(*control_mutex_);
584 motion_generator_running_ =
false;
585 control_finished_condition_.notify_all();
589 std::unique_lock
lock(*control_mutex_);
590 control_exception_ = std::current_exception();
591 motion_generator_running_ =
false;
592 control_finished_condition_.notify_all();
Definition cartesian_state.hpp:17
RobotPose pose() const
Definition cartesian_state.hpp:62
RobotVelocity velocity() const
Definition cartesian_state.hpp:67
A template class representing a dynamics limit with a maximum value.
Definition dynamics_limit.hpp:23
Elbow state of the robot.
Definition elbow_state.hpp:24
Joint state of a robot.
Definition joint_state.hpp:16
Vector7d velocity() const
The velocity component of the state.
Definition joint_state.hpp:48
Vector7d position() const
The position component of the state.
Definition joint_state.hpp:43
Helper class for handling motions and reactions.
Definition motion_generator.hpp:31
Base class for motions.
Definition motion.hpp:24
Relative dynamics factors.
Definition relative_dynamics_factor.hpp:13
A class representing a Franka robot.
Definition robot.hpp:48
DynamicsLimit< Vector7d > joint_acceleration_limit
Joint acceleration limit [rad/s²].
Definition robot.hpp:495
void move(const std::shared_ptr< Motion< franka::JointPositions > > &motion, bool async=false)
Execute the given motion.
Definition robot.hpp:385
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:339
std::optional< ControlSignalType > current_control_signal_type()
The type of the current control signal.
Definition robot.cpp:113
void move(const std::shared_ptr< Motion< franka::CartesianPose > > &motion, bool async=false)
Execute the given motion.
Definition robot.hpp:363
std::string fci_hostname() const
The hostname of the robot.
Definition robot.cpp:111
Vector7d currentJointVelocities()
Returns the current joint velocities of the robot.
Definition robot.hpp:269
bool joinMotion()
Wait for the current motion to finish. Throw any exceptions that occurred during the motion.
Definition robot.hpp:325
static constexpr double control_rate
Definition robot.hpp:147
DynamicsLimit< double > elbow_acceleration_limit
Elbow acceleration limit [rad/s²].
Definition robot.hpp:470
RelativeDynamicsFactor relative_dynamics_factor()
Returns the current global relative dynamics factor of the robot.
Definition robot.cpp:124
Vector7d currentJointPositions()
Returns the current joint positions of the robot.
Definition robot.hpp:263
void move(const std::shared_ptr< Motion< franka::Torques > > &motion, bool async=false)
Execute the given motion.
Definition robot.hpp:405
CartesianState currentCartesianState()
Returns the current cartesian state of the robot.
Definition robot.hpp:244
DynamicsLimit< Vector7d > joint_velocity_limit
Joint velocity limit [rad/s].
Definition robot.hpp:490
RobotState state()
Returns the current state of the robot.
Definition robot.cpp:61
DynamicsLimit< double > translation_jerk_limit
Translational jerk limit [m/s³].
Definition robot.hpp:475
DynamicsLimit< double > translation_velocity_limit
Translational velocity limit [m/s].
Definition robot.hpp:445
bool recoverFromErrors()
Calls the automatic error recovery of the robot and returns whether the recovery was successful.
Definition robot.cpp:56
DynamicsLimit< double > elbow_velocity_limit
Elbow velocity limit [rad/s].
Definition robot.hpp:455
DynamicsLimit< double > rotation_velocity_limit
Rotational velocity limit [rad/s].
Definition robot.hpp:450
DynamicsLimit< double > elbow_jerk_limit
Elbow jerk limit [rad/s³].
Definition robot.hpp:485
bool is_in_control()
Whether the robot is currently in control, i.e. a motion is being executed.
Definition robot.cpp:106
void move(const std::shared_ptr< Motion< franka::JointVelocities > > &motion, bool async=false)
Execute the given motion.
Definition robot.hpp:395
DynamicsLimit< Vector7d > joint_jerk_limit
Joint jerk limit [rad/s³].
Definition robot.hpp:500
JointState currentJointState()
Returns the current joint state of the robot.
Definition robot.hpp:254
void setCollisionBehavior(const ScalarOrArray< 7 > &torque_threshold, const ScalarOrArray< 6 > &force_threshold)
Set the collision behavior of the robot.
Definition robot.cpp:73
static constexpr size_t degrees_of_freedoms
Definition robot.hpp:144
RobotVelocity currentCartesianVelocity()
Returns the current cartesian velocity of the robot.
Definition robot.hpp:238
DynamicsLimit< double > rotation_jerk_limit
Rotational jerk limit [rad/s³].
Definition robot.hpp:480
void move(const std::shared_ptr< Motion< franka::CartesianVelocities > > &motion, bool async=false)
Execute the given motion.
Definition robot.hpp:373
void setRelativeDynamicsFactor(const RelativeDynamicsFactor &relative_dynamics_factor)
Sets the global relative dynamics factor of the robot.
Definition robot.cpp:129
std::shared_ptr< const Model > model() const
The model of the robot.
Definition robot.hpp:311
DynamicsLimit< double > translation_acceleration_limit
Translational acceleration limit [m/s²].
Definition robot.hpp:460
bool hasErrors()
Returns whether the robot has errors.
Definition robot.cpp:54
RobotPose currentPose()
Returns the current pose of the robot.
Definition robot.hpp:232
DynamicsLimit< double > rotation_acceleration_limit
Rotational acceleration limit [rad/s²].
Definition robot.hpp:465
bool pollMotion()
Check whether the robot is still in motion. This function is non-blocking and returns immediately....
Definition robot.hpp:351
Cartesian pose of a robot.
Definition robot_pose.hpp:19
Cartesian velocity of a robot.
Definition robot_velocity.hpp:20
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:11
ControlSignalType
Type of control signal.
Definition control_signal_type.hpp:8
std::variant< double, Array< dims > > ScalarOrArray
Definition types.hpp:21
Eigen::Affine3d Affine
Definition types.hpp:15
Exception thrown when an invalid motion type is used.
Definition robot.hpp:38
Global parameters for the robot.
Definition robot.hpp:53
double kalman_dq_process_var
Kalman parameter: process noise variance of the velocity.
Definition robot.hpp:94
RelativeDynamicsFactor relative_dynamics_factor
Relative dynamics factor for the robot.
Definition robot.hpp:60
double default_force_threshold
Default force threshold for collision behavior.
Definition robot.hpp:70
double kalman_control_adaptation_rate
Kalman parameter: rate of adaptation of the robot state to the desired robot state.
Definition robot.hpp:140
double kalman_dq_obs_var
Kalman parameter: observation noise variance of measured joint velocities.
Definition robot.hpp:116
double kalman_q_obs_var
Kalman parameter: observation noise variance of measured joint positions.
Definition robot.hpp:110
double kalman_dq_d_obs_var
Kalman parameter: observation noise variance of desired joint velocities.
Definition robot.hpp:128
franka::ControllerMode controller_mode
Default controller mode for the robot.
Definition robot.hpp:77
double kalman_control_process_var
Kalman parameter: process noise variance of the control signal.
Definition robot.hpp:104
double kalman_q_d_obs_var
Kalman parameter: observation noise variance of desired joint positions.
Definition robot.hpp:122
franka::RealtimeConfig realtime_config
Default realtime configuration for the robot.
Definition robot.hpp:84
double kalman_ddq_d_obs_var
Kalman parameter: observation noise variance of desired joint accelerations.
Definition robot.hpp:134
double default_torque_threshold
Default torque threshold for collision behavior.
Definition robot.hpp:65
double kalman_ddq_process_var
Kalman parameter: process noise variance of the acceleration.
Definition robot.hpp:99
double kalman_q_process_var
Kalman parameter: process noise variance of the position.
Definition robot.hpp:89
Full state of the robot.
Definition robot_state.hpp:23