7 #include <Eigen/Geometry>
51 void initImpl(
const franka::RobotState &robot_state,
const std::optional<franka::Torques> &previous_command)
override;
53 std::tuple<Affine, bool>
54 update(
const franka::RobotState &robot_state, franka::Duration time_step,
double time)
override;
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