Franky  0.9.1
A High-Level Motion API for Franka
cartesian_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 
10 
11 namespace franky {
12 
20  public:
25  struct Params : public ImpedanceMotion::Params {
34  double finish_wait_factor{1.2};
35  };
36 
41  explicit CartesianImpedanceMotion(const Affine &target, double duration);
42 
48  explicit CartesianImpedanceMotion(const Affine &target, double duration, const Params &params);
49 
50  protected:
51  void initImpl(const franka::RobotState &robot_state, const std::optional<franka::Torques> &previous_command) override;
52 
53  std::tuple<Affine, bool>
54  update(const franka::RobotState &robot_state, franka::Duration time_step, double time) override;
55 
56  private:
57  Affine initial_pose_;
58  double duration_;
59  Params params_;
60 };
61 
62 } // namespace franky
Cartesian impedance motion.
Definition: cartesian_impedance_motion.hpp:19
void initImpl(const franka::RobotState &robot_state, const std::optional< franka::Torques > &previous_command) override
Definition: cartesian_impedance_motion.cpp:19
std::tuple< Affine, bool > update(const franka::RobotState &robot_state, franka::Duration time_step, double time) override
Definition: cartesian_impedance_motion.cpp:27
CartesianImpedanceMotion(const Affine &target, double duration)
Definition: cartesian_impedance_motion.cpp:12
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 Cartesian impedance motion.
Definition: cartesian_impedance_motion.hpp:25
bool return_when_finished
Definition: cartesian_impedance_motion.hpp:27
double finish_wait_factor
Definition: cartesian_impedance_motion.hpp:34
Parameters for the impedance motion.
Definition: impedance_motion.hpp:27