Franky  0.9.1
A High-Level Motion API for Franka
exponential_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"
11 
12 namespace franky {
13 
22  public:
27  struct Params : public ImpedanceMotion::Params {
29  double exponential_decay{0.005};
30  };
31 
35  explicit ExponentialImpedanceMotion(const Affine &target);
36 
41  explicit ExponentialImpedanceMotion(const Affine &target, const Params &params);
42 
43  protected:
44  std::tuple<Affine, bool>
45  update(const franka::RobotState &robot_state, franka::Duration time_step, double time) override;
46 
47  private:
48  Params params_;
49 };
50 
51 } // namespace franky
Exponential cartesian impedance motion.
Definition: exponential_impedance_motion.hpp:21
ExponentialImpedanceMotion(const Affine &target)
Definition: exponential_impedance_motion.cpp:12
std::tuple< Affine, bool > update(const franka::RobotState &robot_state, franka::Duration time_step, double time) override
Definition: exponential_impedance_motion.cpp:20
Base class for client-side cartesian impedance motions.
Definition: impedance_motion.hpp:22
Affine target() const
Definition: impedance_motion.hpp:65
Definition: gripper.cpp:3
Eigen::Affine3d Affine
Definition: types.hpp:13
Parameters for the exponential cartesian impedance motion.
Definition: exponential_impedance_motion.hpp:27
double exponential_decay
Definition: exponential_impedance_motion.hpp:29
Parameters for the impedance motion.
Definition: impedance_motion.hpp:27