Franky 1.1.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(
22 Eigen::Vector3d linear_velocity = Eigen::Vector3d::Zero(),
23 Eigen::Vector3d angular_velocity = Eigen::Vector3d::Zero())
24 : linear_velocity_(std::move(linear_velocity)), angular_velocity_(std::move(angular_velocity)) {}
25
30 return Twist{vector_repr.head<3>(), vector_repr.tail<3>()};
31 }
32
41 result << linear_velocity_, angular_velocity_;
42 return result;
43 }
44
53 return transformWith(transformation.rotation());
54 }
55
62 template <typename RotationMatrixType>
64 return Twist{rotation * linear_velocity_, rotation * angular_velocity_};
65 }
66
77 [[nodiscard]] Twist propagateThroughLink(const Eigen::Vector3d &link_translation) const {
78 return Twist{linear_velocity_ + angular_velocity_.cross(link_translation), angular_velocity_};
79 }
80
86 [[nodiscard]] Eigen::Vector3d linear_velocity() const { return linear_velocity_; }
87
93 [[nodiscard]] Eigen::Vector3d angular_velocity() const { return angular_velocity_; }
94
95 friend std::ostream &operator<<(std::ostream &os, const Twist &twist);
96
97 private:
98 Eigen::Vector3d linear_velocity_;
99 Eigen::Vector3d angular_velocity_;
100};
101
102inline Twist operator*(const Affine &affine, const Twist &twist) { return twist.transformWith(affine); }
103
104template <typename RotationMatrixType>
108
109inline std::ostream &operator<<(std::ostream &os, const Twist &twist) {
110 os << "Twist(lin=" << twist.linear_velocity_ << ", ang=" << twist.angular_velocity_ << ")";
111 return os;
112}
113
114} // 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:39
static Twist fromVectorRepr(const Vector6d &vector_repr)
Definition twist.hpp:29
Twist transformWith(const Affine &transformation) const
Transform the frame of the twist by applying the given affine transform.
Definition twist.hpp:52
Eigen::Vector3d linear_velocity() const
Get the linear velocity.
Definition twist.hpp:86
Twist transformWith(const RotationMatrixType &rotation) const
Transform the frame of the twist by applying the given rotation.
Definition twist.hpp:63
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:77
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:109
Twist(const Twist &twist)=default
Eigen::Vector3d angular_velocity() const
Get the angular velocity.
Definition twist.hpp:93
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:76
Eigen::Vector< double, 6 > Vector6d
Definition types.hpp:10
Eigen::Affine3d Affine
Definition types.hpp:15