franky 1.1.1
A High-Level Motion API for Franka
Loading...
Searching...
No Matches
robot.hpp
Go to the documentation of this file.
1#pragma once
2
3#include <franka/control_types.h>
4#include <franka/duration.h>
5#include <franka/exception.h>
6#include <franka/robot.h>
7#include <franka/robot_state.h>
8
9#include <exception>
10#include <future>
11#include <optional>
12#include <stdexcept>
13#include <variant>
14
19#include "franky/model.hpp"
23#include "franky/robot_pose.hpp"
26#include "franky/types.hpp"
27#include "franky/util.hpp"
28
29namespace franky {
30
37struct InvalidMotionTypeException : std::runtime_error {
38 using std::runtime_error::runtime_error;
39};
40
47class Robot : public franka::Robot {
48 public:
52 struct Params {
60
65
70
76 franka::ControllerMode controller_mode{franka::ControllerMode::kJointImpedance};
77
83 franka::RealtimeConfig realtime_config{franka::RealtimeConfig::kEnforce};
84
88 double kalman_q_process_var = 0.0001;
89
93 double kalman_dq_process_var = 0.001;
94
99
104
109 double kalman_q_obs_var = 0.01;
110
115 double kalman_dq_obs_var = 0.1;
116
121 double kalman_q_d_obs_var = 0.0001;
122
127 double kalman_dq_d_obs_var = 0.0001;
128
133 double kalman_ddq_d_obs_var = 0.0001;
134
140 };
141
143 static constexpr size_t degrees_of_freedoms{7};
144
146 static constexpr double control_rate{0.001};
147
151 explicit Robot(const std::string &fci_hostname);
152
157 explicit Robot(const std::string &fci_hostname, const Params &params);
158
159 using franka::Robot::setCollisionBehavior;
160
169
185
213
219 bool recoverFromErrors();
220
225 [[nodiscard]] bool hasErrors();
226
232
238
244 auto s = state();
245 return {
246 {Affine(Eigen::Matrix4d::Map(s.O_T_EE.data())), ElbowState{s.elbow}}, RobotVelocity(s.O_dP_EE_c, s.delbow_c)};
247 }
248
254 auto s = state();
255 return {s.q, s.dq};
256 }
257
263
269
275
281
287
292 [[nodiscard]] bool is_in_control();
293
297 [[nodiscard]] std::string fci_hostname() const;
298
302 [[nodiscard]] std::optional<ControlSignalType> current_control_signal_type();
303
310 [[nodiscard]] std::shared_ptr<const Model> model() const { return model_; }
311
312#ifdef FRANKA_0_15
317 [[nodiscard]] std::string model_urdf() const { return model_urdf_; }
318#endif
319
324 bool joinMotion() {
325 std::unique_lock lock(*control_mutex_);
326 return joinMotionUnsafe(lock);
327 }
328
337 template <class Rep, class Period>
338 bool joinMotion(const std::chrono::duration<Rep, Period> &timeout) {
339 std::unique_lock lock(*control_mutex_);
341 }
342
349 [[nodiscard]]
350 bool pollMotion() {
351 return joinMotion(std::chrono::milliseconds(0));
352 }
353
354 // These helper functions are needed as the implicit template deduction does
355 // not work on subclasses of Motion
356
362 void move(const std::shared_ptr<Motion<franka::CartesianPose>> &motion, bool async = false) {
364 motion, [this](const ControlFunc<franka::CartesianPose> &m) { control(m, params_.controller_mode); }, async);
365 }
366
372 void move(const std::shared_ptr<Motion<franka::CartesianVelocities>> &motion, bool async = false) {
374 motion,
375 [this](const ControlFunc<franka::CartesianVelocities> &m) { control(m, params_.controller_mode); },
376 async);
377 }
378
384 void move(const std::shared_ptr<Motion<franka::JointPositions>> &motion, bool async = false) {
386 motion, [this](const ControlFunc<franka::JointPositions> &m) { control(m, params_.controller_mode); }, async);
387 }
388
394 void move(const std::shared_ptr<Motion<franka::JointVelocities>> &motion, bool async = false) {
396 motion, [this](const ControlFunc<franka::JointVelocities> &m) { control(m, params_.controller_mode); }, async);
397 }
398
404 void move(const std::shared_ptr<Motion<franka::Torques>> &motion, bool async = false) {
405 moveInternal<franka::Torques>(motion, [this](const ControlFunc<franka::Torques> &m) { control(m); }, async);
406 }
407
408 private:
409 std::shared_ptr<const Model> model_;
410#ifdef FRANKA_0_15
411 std::string model_urdf_;
412#endif
413
414 template <typename ControlSignalType>
415 using ControlFunc = std::function<ControlSignalType(const franka::RobotState &, franka::Duration)>;
416 using MotionGeneratorVariant = std::variant<
420
422 std::string fci_hostname_;
423 Params params_;
424 RobotState current_state_;
425 std::mutex state_mutex_;
426 std::shared_ptr<std::mutex> control_mutex_;
427 std::condition_variable control_finished_condition_;
428 std::exception_ptr control_exception_;
429 std::thread control_thread_;
430 MotionGeneratorVariant motion_generator_{std::nullopt};
431 bool motion_generator_running_{false};
432
433 [[nodiscard]] bool is_in_control_unsafe() const;
434
435 public:
436 // IMPORTANT: this has to come after control_mutex_ as otherwise
437 // control_mutex_ will be uninitialized when passed to the constructor of the
438 // DynamicsLimit class Limits provided by Franka for the FR3:
439 // https://frankaemika.github.io/docs/control_parameters.html
440 // clang-format off
445
450
455
460
465
470
475
480
485
490
495
500
501 // clang-format on
502
503 private:
504 template <class Rep = long, class Period = std::ratio<1>>
505 bool joinMotionUnsafe(
506 std::unique_lock<std::mutex> &lock,
507 const std::optional<std::chrono::duration<Rep, Period>> &timeout = std::nullopt) {
508 while (motion_generator_running_) {
509 if (timeout.has_value()) {
510 if (control_finished_condition_.wait_for(lock, timeout.value()) == std::cv_status::timeout) {
511 return false;
512 }
513 } else {
514 control_finished_condition_.wait(lock);
515 }
516 }
517 if (control_thread_.joinable()) control_thread_.join();
518 if (control_exception_ != nullptr) {
519 auto control_exception = control_exception_;
520 control_exception_ = nullptr;
521 std::rethrow_exception(control_exception);
522 }
523 return true;
524 }
525
526 template <typename ControlSignalType>
527 void moveInternal(
528 const std::shared_ptr<Motion<ControlSignalType>> &motion,
529 const std::function<void(const ControlFunc<ControlSignalType> &)> &control_func_executor, bool async) {
530 if (motion == nullptr) {
531 throw std::invalid_argument("The motion must not be null.");
532 }
533 { // Do not remove brace, it is needed to scope the lock
534 std::unique_lock lock(*control_mutex_);
535 if (is_in_control_unsafe() && motion_generator_running_) {
536 if (!std::holds_alternative<MotionGenerator<ControlSignalType>>(motion_generator_)) {
537 throw InvalidMotionTypeException(
538 "The type of motion cannot change during runtime. Please ensure "
539 "that the "
540 "previous motion finished before using a new type of motion.");
541 }
542 std::get<MotionGenerator<ControlSignalType>>(motion_generator_).updateMotion(motion);
543 } else {
544 joinMotionUnsafe(lock);
545
546 motion_generator_.emplace<MotionGenerator<ControlSignalType>>(this, motion);
547 auto motion_generator = &std::get<MotionGenerator<ControlSignalType>>(motion_generator_);
548 motion_generator->registerUpdateCallback(
549 [this](const RobotState &robot_state, franka::Duration duration, franka::Duration time) {
550 std::lock_guard lock(state_mutex_);
551 current_state_ = robot_state;
552 });
553 motion_generator_running_ = true;
554 control_thread_ = std::thread([this, control_func_executor, motion_generator]() {
555 try {
556 bool done = false;
557 RobotStateEstimator robot_state_estimator(
558 params_.kalman_q_process_var,
559 params_.kalman_dq_process_var,
560 params_.kalman_ddq_process_var,
561 params_.kalman_control_process_var,
562 params_.kalman_q_obs_var,
563 params_.kalman_dq_obs_var,
564 params_.kalman_q_d_obs_var,
565 params_.kalman_dq_d_obs_var,
566 params_.kalman_ddq_d_obs_var,
567 params_.kalman_control_adaptation_rate);
568 while (!done) {
570 [this, motion_generator, &robot_state_estimator](const franka::RobotState &rs, franka::Duration d) {
571 return (*motion_generator)(robot_state_estimator.update(rs, *model_), d);
572 });
573 std::unique_lock lock(*control_mutex_);
574
575 // This code is just for the case that a new motion is set just
576 // after the old one terminates. If this happens, we need to
577 // continue with this motion, unless an exception occurs.
578 done = !motion_generator->has_new_motion();
579 if (motion_generator->has_new_motion()) {
580 motion_generator->resetTimeUnsafe();
581 } else {
582 done = true;
583 motion_generator_running_ = false;
584 control_finished_condition_.notify_all();
585 }
586 }
587 } catch (...) {
588 std::unique_lock lock(*control_mutex_);
589 control_exception_ = std::current_exception();
590 motion_generator_running_ = false;
591 control_finished_condition_.notify_all();
592 }
593 });
594 }
595 }
596 if (!async) joinMotion();
597 }
598};
599
600} // namespace franky
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:47
DynamicsLimit< Vector7d > joint_acceleration_limit
Joint acceleration limit [rad/s²].
Definition robot.hpp:494
void move(const std::shared_ptr< Motion< franka::JointPositions > > &motion, bool async=false)
Execute the given motion.
Definition robot.hpp:384
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:338
std::optional< ControlSignalType > current_control_signal_type()
The type of the current control signal.
Definition robot.cpp:112
void move(const std::shared_ptr< Motion< franka::CartesianPose > > &motion, bool async=false)
Execute the given motion.
Definition robot.hpp:362
std::string fci_hostname() const
The hostname of the robot.
Definition robot.cpp:110
Vector7d currentJointVelocities()
Returns the current joint velocities of the robot.
Definition robot.hpp:268
bool joinMotion()
Wait for the current motion to finish. Throw any exceptions that occurred during the motion.
Definition robot.hpp:324
static constexpr double control_rate
Definition robot.hpp:146
DynamicsLimit< double > elbow_acceleration_limit
Elbow acceleration limit [rad/s²].
Definition robot.hpp:469
RelativeDynamicsFactor relative_dynamics_factor()
Returns the current global relative dynamics factor of the robot.
Definition robot.cpp:123
Vector7d currentJointPositions()
Returns the current joint positions of the robot.
Definition robot.hpp:262
void move(const std::shared_ptr< Motion< franka::Torques > > &motion, bool async=false)
Execute the given motion.
Definition robot.hpp:404
CartesianState currentCartesianState()
Returns the current cartesian state of the robot.
Definition robot.hpp:243
DynamicsLimit< Vector7d > joint_velocity_limit
Joint velocity limit [rad/s].
Definition robot.hpp:489
RobotState state()
Returns the current state of the robot.
Definition robot.cpp:60
DynamicsLimit< double > translation_jerk_limit
Translational jerk limit [m/s³].
Definition robot.hpp:474
DynamicsLimit< double > translation_velocity_limit
Translational velocity limit [m/s].
Definition robot.hpp:444
bool recoverFromErrors()
Calls the automatic error recovery of the robot and returns whether the recovery was successful.
Definition robot.cpp:55
DynamicsLimit< double > elbow_velocity_limit
Elbow velocity limit [rad/s].
Definition robot.hpp:454
DynamicsLimit< double > rotation_velocity_limit
Rotational velocity limit [rad/s].
Definition robot.hpp:449
DynamicsLimit< double > elbow_jerk_limit
Elbow jerk limit [rad/s³].
Definition robot.hpp:484
bool is_in_control()
Whether the robot is currently in control, i.e. a motion is being executed.
Definition robot.cpp:105
void move(const std::shared_ptr< Motion< franka::JointVelocities > > &motion, bool async=false)
Execute the given motion.
Definition robot.hpp:394
DynamicsLimit< Vector7d > joint_jerk_limit
Joint jerk limit [rad/s³].
Definition robot.hpp:499
JointState currentJointState()
Returns the current joint state of the robot.
Definition robot.hpp:253
void setCollisionBehavior(const ScalarOrArray< 7 > &torque_threshold, const ScalarOrArray< 6 > &force_threshold)
Set the collision behavior of the robot.
Definition robot.cpp:72
static constexpr size_t degrees_of_freedoms
Definition robot.hpp:143
RobotVelocity currentCartesianVelocity()
Returns the current cartesian velocity of the robot.
Definition robot.hpp:237
DynamicsLimit< double > rotation_jerk_limit
Rotational jerk limit [rad/s³].
Definition robot.hpp:479
void move(const std::shared_ptr< Motion< franka::CartesianVelocities > > &motion, bool async=false)
Execute the given motion.
Definition robot.hpp:372
void setRelativeDynamicsFactor(const RelativeDynamicsFactor &relative_dynamics_factor)
Sets the global relative dynamics factor of the robot.
Definition robot.cpp:128
std::shared_ptr< const Model > model() const
The model of the robot.
Definition robot.hpp:310
DynamicsLimit< double > translation_acceleration_limit
Translational acceleration limit [m/s²].
Definition robot.hpp:459
bool hasErrors()
Returns whether the robot has errors.
Definition robot.cpp:53
RobotPose currentPose()
Returns the current pose of the robot.
Definition robot.hpp:231
DynamicsLimit< double > rotation_acceleration_limit
Rotational acceleration limit [rad/s²].
Definition robot.hpp:464
bool pollMotion()
Check whether the robot is still in motion. This function is non-blocking and returns immediately....
Definition robot.hpp:350
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:37
Global parameters for the robot.
Definition robot.hpp:52
double kalman_dq_process_var
Kalman parameter: process noise variance of the velocity.
Definition robot.hpp:93
RelativeDynamicsFactor relative_dynamics_factor
Relative dynamics factor for the robot.
Definition robot.hpp:59
double default_force_threshold
Default force threshold for collision behavior.
Definition robot.hpp:69
double kalman_control_adaptation_rate
Kalman parameter: rate of adaptation of the robot state to the desired robot state.
Definition robot.hpp:139
double kalman_dq_obs_var
Kalman parameter: observation noise variance of measured joint velocities.
Definition robot.hpp:115
double kalman_q_obs_var
Kalman parameter: observation noise variance of measured joint positions.
Definition robot.hpp:109
double kalman_dq_d_obs_var
Kalman parameter: observation noise variance of desired joint velocities.
Definition robot.hpp:127
franka::ControllerMode controller_mode
Default controller mode for the robot.
Definition robot.hpp:76
double kalman_control_process_var
Kalman parameter: process noise variance of the control signal.
Definition robot.hpp:103
double kalman_q_d_obs_var
Kalman parameter: observation noise variance of desired joint positions.
Definition robot.hpp:121
franka::RealtimeConfig realtime_config
Default realtime configuration for the robot.
Definition robot.hpp:83
double kalman_ddq_d_obs_var
Kalman parameter: observation noise variance of desired joint accelerations.
Definition robot.hpp:133
double default_torque_threshold
Default torque threshold for collision behavior.
Definition robot.hpp:64
double kalman_ddq_process_var
Kalman parameter: process noise variance of the acceleration.
Definition robot.hpp:98
double kalman_q_process_var
Kalman parameter: process noise variance of the position.
Definition robot.hpp:88
Full state of the robot.
Definition robot_state.hpp:23