Franky 0.12.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 <map>
4#include <optional>
5
6#include <Eigen/Core>
7#include <Eigen/Geometry>
8
10
11namespace franky {
12
20 public:
34 double finish_wait_factor{1.2};
35 };
36
41 explicit CartesianImpedanceMotion(const Affine &target, franka::Duration duration);
42
48 explicit CartesianImpedanceMotion(const Affine &target, franka::Duration duration, const Params &params);
49
50 protected:
51 void initImpl(const RobotState &robot_state, const std::optional<franka::Torques> &previous_command) override;
52
53 std::tuple<Affine, bool> update(
54 const RobotState &robot_state, franka::Duration time_step, franka::Duration time) override;
55
56 private:
57 Affine initial_pose_;
58 franka::Duration duration_;
59 Params params_;
60};
61
62} // 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:19
std::tuple< Affine, bool > update(const RobotState &robot_state, franka::Duration time_step, franka::Duration time) override
Definition cartesian_impedance_motion.cpp:27
Base class for client-side cartesian impedance motions.
Definition impedance_motion.hpp:22
Affine target() const
Definition impedance_motion.hpp:65
Definition dynamics_limit.cpp:8
Eigen::Affine3d Affine
Definition types.hpp:16
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
Full state of the robot.
Definition robot_state.hpp:20