Franky  0.9.1
A High-Level Motion API for Franka
cartesian_waypoint_motion.hpp
Go to the documentation of this file.
1 #pragma once
2 
3 #include <atomic>
4 #include <optional>
5 #include <ruckig/ruckig.hpp>
6 
7 #include <franka/robot_state.h>
8 
9 #include "franky/robot_pose.hpp"
10 #include "franky/robot.hpp"
12 #include "franky/util.hpp"
15 
16 namespace franky {
17 
23 class CartesianWaypointMotion : public WaypointMotion<franka::CartesianPose, CartesianState> {
24  public:
29  struct Params : WaypointMotion<franka::CartesianPose, CartesianState>::Params {
34  Affine frame{Affine::Identity()};
35  };
36 
40  explicit CartesianWaypointMotion(const std::vector<Waypoint<CartesianState>> &waypoints);
41 
46  explicit CartesianWaypointMotion(const std::vector<Waypoint<CartesianState>> &waypoints, Params params);
47 
48  protected:
49  void initWaypointMotion(
50  const franka::RobotState &robot_state,
51  const std::optional<franka::CartesianPose> &previous_command,
52  ruckig::InputParameter<7> &input_parameter) override;
53 
54  void setNewWaypoint(
55  const franka::RobotState &robot_state,
56  const std::optional<franka::CartesianPose> &previous_command,
57  const Waypoint<CartesianState> &new_waypoint,
58  ruckig::InputParameter<7> &input_parameter) override;
59 
60  [[nodiscard]] std::tuple<Vector7d, Vector7d, Vector7d> getAbsoluteInputLimits() const override;
61 
62  [[nodiscard]] franka::CartesianPose getControlSignal(const ruckig::InputParameter<7> &input_parameter) const override;
63 
64  private:
65  Params params_;
66 
67  CartesianState target_state_;
68  Affine ref_frame_;
69 
70  static inline Vector7d vec_cart_rot_elbow(double cart, double rot, double elbow) {
71  return {cart, cart, cart, rot, rot, rot, elbow};
72  }
73 };
74 
75 } // namespace franky
Definition: cartesian_state.hpp:17
Cartesian waypoint motion.
Definition: cartesian_waypoint_motion.hpp:23
void initWaypointMotion(const franka::RobotState &robot_state, const std::optional< franka::CartesianPose > &previous_command, ruckig::InputParameter< 7 > &input_parameter) override
Definition: cartesian_waypoint_motion.cpp:19
CartesianWaypointMotion(const std::vector< Waypoint< CartesianState >> &waypoints)
Definition: cartesian_waypoint_motion.cpp:12
std::tuple< Vector7d, Vector7d, Vector7d > getAbsoluteInputLimits() const override
Definition: cartesian_waypoint_motion.cpp:117
franka::CartesianPose getControlSignal(const ruckig::InputParameter< 7 > &input_parameter) const override
Definition: cartesian_waypoint_motion.cpp:38
void setNewWaypoint(const franka::RobotState &robot_state, const std::optional< franka::CartesianPose > &previous_command, const Waypoint< CartesianState > &new_waypoint, ruckig::InputParameter< 7 > &input_parameter) override
Definition: cartesian_waypoint_motion.cpp:44
A motion following multiple waypoints in a time-optimal way. Works with arbitrary initial conditions.
Definition: waypoint_motion.hpp:51
Definition: gripper.cpp:3
Eigen::Vector< double, 7 > Vector7d
Definition: types.hpp:9
@ CartesianPose
Definition: control_signal_type.hpp:13
Eigen::Affine3d Affine
Definition: types.hpp:13
Parameters for the Cartesian waypoint motion.
Definition: cartesian_waypoint_motion.hpp:29
Affine frame
Definition: cartesian_waypoint_motion.hpp:34
A waypoint with a target and optional parameters.
Definition: waypoint_motion.hpp:34