Franky 1.1.0
A High-Level Motion API for Franka
Loading...
Searching...
No Matches
twist_acceleration.hpp
Go to the documentation of this file.
1#pragma once
2
3#include <Eigen/Core>
4
5#include "franky/twist.hpp"
6#include "franky/types.hpp"
7#include "franky/util.hpp"
8
9namespace franky {
10
15 public:
17
23 Eigen::Vector3d linear_acceleration = Eigen::Vector3d::Zero(),
24 Eigen::Vector3d angular_acceleration = Eigen::Vector3d::Zero())
25 : linear_acceleration_(std::move(linear_acceleration)), angular_acceleration_(std::move(angular_acceleration)) {}
26
31 return TwistAcceleration{vector_repr.head<3>(), vector_repr.tail<3>()};
32 }
33
42 result << linear_acceleration_, angular_acceleration_;
43 return result;
44 }
45
56
64 template <typename RotationMatrixType>
66 return TwistAcceleration{rotation * linear_acceleration_, rotation * angular_acceleration_};
67 }
68
83 const Eigen::Vector3d &link_translation, const Eigen::Vector3d &base_angular_velocity) const {
84 Eigen::Vector3d propagated_linear_acceleration =
85 linear_acceleration_ + angular_acceleration_.cross(link_translation) +
87
88 return TwistAcceleration{propagated_linear_acceleration, angular_acceleration_};
89 }
90
96 [[nodiscard]] Eigen::Vector3d linear_acceleration() const { return linear_acceleration_; }
97
103 [[nodiscard]] Eigen::Vector3d angular_acceleration() const { return angular_acceleration_; }
104
105 friend std::ostream &operator<<(std::ostream &os, const TwistAcceleration &twist_acceleration);
106
107 private:
108 Eigen::Vector3d linear_acceleration_;
109 Eigen::Vector3d angular_acceleration_;
110};
111
115
116template <typename RotationMatrixType>
120
121inline std::ostream &operator<<(std::ostream &os, const TwistAcceleration &twist_acceleration) {
122 os << "TwistAcceleration(lin=" << twist_acceleration.linear_acceleration_
123 << ", ang=" << twist_acceleration.angular_acceleration_ << ")";
124 return os;
125}
126
127} // 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
TwistAcceleration acceleration of a frame (2nd derivative of a pose).
Definition twist_acceleration.hpp:14
TwistAcceleration transformWith(const Affine &transformation) const
Transform the frame of the twist acceleration by applying the given affine transform.
Definition twist_acceleration.hpp:53
TwistAcceleration propagateThroughLink(const Eigen::Vector3d &link_translation, const Eigen::Vector3d &base_angular_velocity) const
Propagate the twist acceleration through a link with the given translation. Hence,...
Definition twist_acceleration.hpp:82
TwistAcceleration(Eigen::Vector3d linear_acceleration=Eigen::Vector3d::Zero(), Eigen::Vector3d angular_acceleration=Eigen::Vector3d::Zero())
Definition twist_acceleration.hpp:22
static TwistAcceleration fromVectorRepr(const Vector6d &vector_repr)
Definition twist_acceleration.hpp:30
Eigen::Vector3d angular_acceleration() const
Get the angular acceleration.
Definition twist_acceleration.hpp:103
friend std::ostream & operator<<(std::ostream &os, const TwistAcceleration &twist_acceleration)
Definition twist_acceleration.hpp:121
TwistAcceleration(const TwistAcceleration &twist_acceleration_acceleration)=default
Eigen::Vector3d linear_acceleration() const
Get the linear acceleration.
Definition twist_acceleration.hpp:96
Vector6d vector_repr() const
Get the vector representation of the twist acceleration. It consists of the linear and angular veloci...
Definition twist_acceleration.hpp:40
TwistAcceleration transformWith(const RotationMatrixType &rotation) const
Transform the frame of the twist acceleration by applying the given rotation.
Definition twist_acceleration.hpp:65
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