Franky 1.1.0
A High-Level Motion API for Franka
Loading...
Searching...
No Matches
impedance_motion.hpp
Go to the documentation of this file.
1#pragma once
2
3#include <Eigen/Core>
4#include <Eigen/Geometry>
5#include <map>
6#include <optional>
7
10#include "franky/robot_pose.hpp"
11
12namespace franky {
13
21class ImpedanceMotion : public Motion<franka::Torques> {
22 public:
26 struct Params {
29
32
35
37 Eigen::Vector<double, 6> force_constraints;
38
40 Eigen::Vector<bool, 6> force_constraints_active{Eigen::Vector<bool, 6>::Zero()};
41 };
42
47 explicit ImpedanceMotion(Affine target, const Params &params);
48
49 protected:
50 void initImpl(const RobotState &robot_state, const std::optional<franka::Torques> &previous_command) override;
51
52 franka::Torques nextCommandImpl(
53 const RobotState &robot_state, franka::Duration time_step, franka::Duration rel_time, franka::Duration abs_time,
54 const std::optional<franka::Torques> &previous_command) override;
55
56 [[nodiscard]] inline Affine intermediate_target() const { return intermediate_target_; }
57
58 [[nodiscard]] inline Affine target() const { return absolute_target_; }
59
60 virtual std::tuple<Affine, bool> update(
61 const RobotState &robot_state, franka::Duration time_step, franka::Duration time) = 0;
62
63 private:
64 Affine absolute_target_;
65 Affine target_;
66 Params params_;
67
68 Eigen::Matrix<double, 6, 6> stiffness, damping;
69 Affine intermediate_target_;
70
71 std::unique_ptr<franka::Model> model_;
72};
73
74} // namespace franky
Base class for client-side cartesian impedance motions.
Definition impedance_motion.hpp:21
Affine target() const
Definition impedance_motion.hpp:58
franka::Torques nextCommandImpl(const RobotState &robot_state, franka::Duration time_step, franka::Duration rel_time, franka::Duration abs_time, const std::optional< franka::Torques > &previous_command) override
Definition impedance_motion.cpp:32
void initImpl(const RobotState &robot_state, const std::optional< franka::Torques > &previous_command) override
Definition impedance_motion.cpp:23
Affine intermediate_target() const
Definition impedance_motion.hpp:56
virtual std::tuple< Affine, bool > update(const RobotState &robot_state, franka::Duration time_step, franka::Duration time)=0
Base class for motions.
Definition motion.hpp:24
Definition dynamics_limit.cpp:8
ReferenceType
Enum class for reference types.
Definition reference_type.hpp:11
Eigen::Affine3d Affine
Definition types.hpp:15
Parameters for the impedance motion.
Definition impedance_motion.hpp:26
double translational_stiffness
Definition impedance_motion.hpp:31
ReferenceType target_type
Definition impedance_motion.hpp:28
Eigen::Vector< double, 6 > force_constraints
Definition impedance_motion.hpp:37
Eigen::Vector< bool, 6 > force_constraints_active
Definition impedance_motion.hpp:40
double rotational_stiffness
Definition impedance_motion.hpp:34
Full state of the robot.
Definition robot_state.hpp:23