4#include <Eigen/Geometry>
53 void initImpl(
const RobotState &robot_state,
const std::optional<franka::Torques> &previous_command)
override;
55 std::tuple<Affine, bool>
update(
56 const RobotState &robot_state, franka::Duration time_step, franka::Duration time)
override;
60 franka::Duration duration_;
Cartesian impedance motion.
Definition cartesian_impedance_motion.hpp:19
void initImpl(const RobotState &robot_state, const std::optional< franka::Torques > &previous_command) override
Definition cartesian_impedance_motion.cpp:18
std::tuple< Affine, bool > update(const RobotState &robot_state, franka::Duration time_step, franka::Duration time) override
Definition cartesian_impedance_motion.cpp:24
Base class for client-side cartesian impedance motions.
Definition impedance_motion.hpp:21
Affine target() const
Definition impedance_motion.hpp:58
Definition dynamics_limit.cpp:8
Eigen::Affine3d Affine
Definition types.hpp:15
Parameters for the Cartesian impedance motion.
Definition cartesian_impedance_motion.hpp:25
bool return_when_finished
Definition cartesian_impedance_motion.hpp:28
double finish_wait_factor
Definition cartesian_impedance_motion.hpp:36
Parameters for the impedance motion.
Definition impedance_motion.hpp:26
Full state of the robot.
Definition robot_state.hpp:23