Franky  0.9.1
A High-Level Motion API for Franka
impedance_motion.hpp
Go to the documentation of this file.
1 #pragma once
2 
3 #include <map>
4 #include <optional>
5 
6 #include <Eigen/Core>
7 #include <Eigen/Geometry>
8 
9 #include "franky/robot_pose.hpp"
10 #include "franky/motion/motion.hpp"
12 
13 namespace franky {
14 
22 class ImpedanceMotion : public Motion<franka::Torques> {
23  public:
27  struct Params {
30 
33 
35  double rotational_stiffness{200};
36 
38  Eigen::Vector<double, 6> force_constraints;
39 
41  Eigen::Vector<bool, 6> force_constraints_active{Eigen::Vector<bool, 6>::Zero()};
42  };
43 
48  explicit ImpedanceMotion(Affine target, const Params &params);
49 
50  protected:
51  void initImpl(const franka::RobotState &robot_state, const std::optional<franka::Torques> &previous_command) override;
52 
55  const franka::RobotState &robot_state,
56  franka::Duration time_step,
57  double rel_time,
58  double abs_time,
59  const std::optional<franka::Torques> &previous_command) override;
60 
61  [[nodiscard]] inline Affine intermediate_target() const {
62  return intermediate_target_;
63  }
64 
65  [[nodiscard]] inline Affine target() const {
66  return absolute_target_;
67  }
68 
69  virtual std::tuple<Affine, bool>
70  update(const franka::RobotState &robot_state, franka::Duration time_step, double time) = 0;
71 
72  private:
73  Affine absolute_target_;
74  Affine target_;
75  Params params_;
76 
77  Eigen::Matrix<double, 6, 6> stiffness, damping;
78  Affine intermediate_target_;
79 
80  std::unique_ptr<franka::Model> model_;
81 };
82 
83 } // namespace franky
Base class for client-side cartesian impedance motions.
Definition: impedance_motion.hpp:22
Affine target() const
Definition: impedance_motion.hpp:65
void initImpl(const franka::RobotState &robot_state, const std::optional< franka::Torques > &previous_command) override
Definition: impedance_motion.cpp:24
ImpedanceMotion(Affine target, const Params &params)
Definition: impedance_motion.cpp:14
franka::Torques nextCommandImpl(const franka::RobotState &robot_state, franka::Duration time_step, double rel_time, double abs_time, const std::optional< franka::Torques > &previous_command) override
Definition: impedance_motion.cpp:37
Affine intermediate_target() const
Definition: impedance_motion.hpp:61
virtual std::tuple< Affine, bool > update(const franka::RobotState &robot_state, franka::Duration time_step, double time)=0
Base class for motions.
Definition: motion.hpp:22
Definition: gripper.cpp:3
ReferenceType
Enum class for reference types.
Definition: reference_type.hpp:10
@ Torques
Definition: control_signal_type.hpp:9
Eigen::Affine3d Affine
Definition: types.hpp:13
Parameters for the impedance motion.
Definition: impedance_motion.hpp:27
double translational_stiffness
Definition: impedance_motion.hpp:32
ReferenceType target_type
Definition: impedance_motion.hpp:29
Eigen::Vector< double, 6 > force_constraints
Definition: impedance_motion.hpp:38
Eigen::Vector< bool, 6 > force_constraints_active
Definition: impedance_motion.hpp:41
double rotational_stiffness
Definition: impedance_motion.hpp:35