7 #include <Eigen/Geometry>
44 std::tuple<Affine, bool>
45 update(
const franka::RobotState &robot_state, franka::Duration time_step,
double time)
override;
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