Franky 1.1.0
A High-Level Motion API for Franka
Loading...
Searching...
No Matches
cartesian_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
9
10namespace franky {
11
20 public:
36 double finish_wait_factor{1.2};
37 };
38
43 explicit CartesianImpedanceMotion(const Affine &target, franka::Duration duration);
44
50 explicit CartesianImpedanceMotion(const Affine &target, franka::Duration duration, const Params &params);
51
52 protected:
53 void initImpl(const RobotState &robot_state, const std::optional<franka::Torques> &previous_command) override;
54
55 std::tuple<Affine, bool> update(
56 const RobotState &robot_state, franka::Duration time_step, franka::Duration time) override;
57
58 private:
59 Affine initial_pose_;
60 franka::Duration duration_;
61 Params params_;
62};
63
64} // namespace franky
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