7 #include <Eigen/Geometry>
51 void initImpl(
const franka::RobotState &robot_state,
const std::optional<franka::Torques> &previous_command)
override;
55 const franka::RobotState &robot_state,
56 franka::Duration time_step,
59 const std::optional<franka::Torques> &previous_command)
override;
62 return intermediate_target_;
66 return absolute_target_;
69 virtual std::tuple<Affine, bool>
70 update(
const franka::RobotState &robot_state, franka::Duration time_step,
double time) = 0;
77 Eigen::Matrix<double, 6, 6> stiffness, damping;
78 Affine intermediate_target_;
80 std::unique_ptr<franka::Model> model_;
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 ¶ms)
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