Franky 0.12.0
A High-Level Motion API for Franka
Loading...
Searching...
No Matches
twist.hpp
Go to the documentation of this file.
1#pragma once
2
3#include <Eigen/Core>
4
5#include "franky/types.hpp"
6#include "franky/util.hpp"
7
8namespace franky {
9
13class Twist {
14 public:
15 Twist(const Twist &twist) = default;
16
21 explicit Twist(Eigen::Vector3d linear_velocity = Eigen::Vector3d::Zero(),
22 Eigen::Vector3d angular_velocity = Eigen::Vector3d::Zero())
23 : linear_velocity_(std::move(linear_velocity)), angular_velocity_(std::move(angular_velocity)) {}
24
29 return Twist{vector_repr.head<3>(), vector_repr.tail<3>()};
30 }
31
39 result << linear_velocity_, angular_velocity_;
40 return result;
41 }
42
50 return transformWith(transformation.rotation());
51 }
52
59 template<typename RotationMatrixType>
61 return Twist{rotation * linear_velocity_, rotation * angular_velocity_};
62 }
63
72 [[nodiscard]] Twist propagateThroughLink(const Eigen::Vector3d &link_translation) const {
73 return Twist{linear_velocity_ + angular_velocity_.cross(link_translation), angular_velocity_};
74 }
75
81 [[nodiscard]] Eigen::Vector3d linear_velocity() const {
82 return linear_velocity_;
83 }
84
90 [[nodiscard]] Eigen::Vector3d angular_velocity() const {
91 return angular_velocity_;
92 }
93
94 friend std::ostream& operator<<(std::ostream& os, const Twist& twist);
95
96 private:
97 Eigen::Vector3d linear_velocity_;
98 Eigen::Vector3d angular_velocity_;
99};
100
101inline Twist operator*(const Affine &affine, const Twist &twist) {
102 return twist.transformWith(affine);
103}
104
105template<typename RotationMatrixType>
109
110inline std::ostream& operator<<(std::ostream& os, const Twist& twist) {
111 os << "Twist(lin=" <<twist.linear_velocity_ << ", ang=" << twist.angular_velocity_ << ")";
112 return os;
113}
114
115} // namespace franky
CartesianState transformWith(const Affine &transform) const
Transform the frame of the state by applying the given affine transform.
Definition cartesian_state.hpp:42
Twist of a frame.
Definition twist.hpp:13
Vector6d vector_repr() const
Get the vector representation of the twist. It consists of the linear and angular velocities.
Definition twist.hpp:37
static Twist fromVectorRepr(const Vector6d &vector_repr)
Definition twist.hpp:28
Twist transformWith(const Affine &transformation) const
Transform the frame of the twist by applying the given affine transform.
Definition twist.hpp:49
Eigen::Vector3d linear_velocity() const
Get the linear velocity.
Definition twist.hpp:81
Twist transformWith(const RotationMatrixType &rotation) const
Transform the frame of the twist by applying the given rotation.
Definition twist.hpp:60
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:72
Twist(Eigen::Vector3d linear_velocity=Eigen::Vector3d::Zero(), Eigen::Vector3d angular_velocity=Eigen::Vector3d::Zero())
Definition twist.hpp:21
friend std::ostream & operator<<(std::ostream &os, const Twist &twist)
Definition twist.hpp:110
Twist(const Twist &twist)=default
Eigen::Vector3d angular_velocity() const
Get the angular velocity.
Definition twist.hpp:90
Definition dynamics_limit.cpp:8
std::ostream & operator<<(std::ostream &os, const DynamicsLimit< Vector7d > &limit)
Definition dynamics_limit.cpp:47
std::array< double, dims > toStdD(const Eigen::Matrix< double, dims, 1 > &vector)
Definition util.hpp:18
CartesianState operator*(const Affine &transform, const CartesianState &cartesian_state)
Definition cartesian_state.hpp:78
Eigen::Vector< double, 6 > Vector6d
Definition types.hpp:11
Eigen::Affine3d Affine
Definition types.hpp:16