40 result << linear_acceleration_, angular_acceleration_;
60 template<
typename RotationMatrixType>
82 linear_acceleration_ +
95 return linear_acceleration_;
104 return angular_acceleration_;
110 Eigen::Vector3d linear_acceleration_;
111 Eigen::Vector3d angular_acceleration_;
118template<
typename RotationMatrixType>
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:50
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:77
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:29
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:123
TwistAcceleration(const TwistAcceleration &twist_acceleration_acceleration)=default
Eigen::Vector3d linear_acceleration() const
Get the linear acceleration.
Definition twist_acceleration.hpp:94
Vector6d vector_repr() const
Get the vector representation of the twist acceleration. It consists of the linear and angular veloci...
Definition twist_acceleration.hpp:38
TwistAcceleration transformWith(const RotationMatrixType &rotation) const
Transform the frame of the twist acceleration by applying the given rotation.
Definition twist_acceleration.hpp:61
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