Franky  0.9.1
A High-Level Motion API for Franka
robot_velocity.hpp
Go to the documentation of this file.
1 #pragma once
2 
3 #include <optional>
4 #include <Eigen/Core>
5 #include <franka/control_types.h>
6 
7 #include "franky/types.hpp"
8 #include "franky/twist.hpp"
9 
10 namespace franky {
11 
19  public:
21 
22  RobotVelocity(const RobotVelocity &robot_velocity);
23 
24  // Suppress implicit conversion warning
25 #pragma clang diagnostic push
26 #pragma clang diagnostic ignored "-Wimplicit-conversion"
32 #pragma clang diagnostic pop
33 
37  explicit RobotVelocity(const Vector7d &vector_repr);
38 
42  explicit RobotVelocity(franka::CartesianVelocities franka_velocity);
43 
50  [[nodiscard]] Vector7d vector_repr() const;
51 
57  [[nodiscard]] franka::CartesianVelocities as_franka_velocity() const;
58 
65  [[nodiscard]] inline RobotVelocity transform(const Affine &affine) const {
66  return transform(affine.rotation());
67  }
68 
75  template<typename RotationMatrixType>
76  [[nodiscard]] inline RobotVelocity transform(const RotationMatrixType &rotation) const {
77  return {rotation * end_effector_twist_, elbow_velocity_};
78  }
79 
87  [[nodiscard]] inline RobotVelocity changeEndEffectorFrame(const Eigen::Vector3d &offset_world_frame) const {
88  return {end_effector_twist_.propagateThroughLink(offset_world_frame), elbow_velocity_};
89  }
90 
96  [[nodiscard]] inline Twist end_effector_twist() const {
97  return end_effector_twist_;
98  }
99 
105  [[nodiscard]] inline std::optional<double> elbow_velocity() const {
106  return elbow_velocity_;
107  }
108 
109  private:
110  Twist end_effector_twist_;
111  double elbow_velocity_ = 0.0;
112 };
113 
114 inline RobotVelocity operator*(const Affine &affine, const RobotVelocity &robot_velocity) {
115  return robot_velocity.transform(affine);
116 }
117 
118 template<typename RotationMatrixType>
119 inline RobotVelocity operator*(const RotationMatrixType &rotation, const RobotVelocity &robot_velocity) {
120  return robot_velocity.transform(rotation);
121 }
122 
123 } // namespace franky
Cartesian velocity of a robot.
Definition: robot_velocity.hpp:18
RobotVelocity(const RobotVelocity &robot_velocity)
RobotVelocity transform(const RotationMatrixType &rotation) const
Transform the frame of the velocity by applying the given rotation.
Definition: robot_velocity.hpp:76
RobotVelocity transform(const Affine &affine) const
Transform the frame of the velocity by applying the given affine transform.
Definition: robot_velocity.hpp:65
Vector7d vector_repr() const
Get the vector representation of the velocity. It consists of the linear and angular velocity of the ...
Definition: robot_velocity.cpp:30
RobotVelocity changeEndEffectorFrame(const Eigen::Vector3d &offset_world_frame) const
Change the end-effector frame by adding the given offset to the current end-effector frame....
Definition: robot_velocity.hpp:87
franka::CartesianVelocities as_franka_velocity() const
Get the franka velocity.
Definition: robot_velocity.cpp:36
Twist end_effector_twist() const
Get the end effector twist.
Definition: robot_velocity.hpp:96
std::optional< double > elbow_velocity() const
Get the elbow velocity.
Definition: robot_velocity.hpp:105
Twist of a frame.
Definition: twist.hpp:12
Twist propagateThroughLink(const Eigen::Vector3d &link_translation) const
Propagate the twist through a link with the given translation. Hence, suppose this twist is the twist...
Definition: twist.hpp:71
Definition: gripper.cpp:3
CartesianState operator*(const Affine &transform, const CartesianState &cartesian_state)
Definition: cartesian_state.hpp:76
Eigen::Vector< double, 7 > Vector7d
Definition: types.hpp:9
@ CartesianVelocities
Definition: control_signal_type.hpp:12
Eigen::Affine3d Affine
Definition: types.hpp:13