31#include "Eigen/Geometry"
35#include "modules/common_msgs/basic_msgs/geometry.pb.h"
56inline double QuaternionToHeading(
const double qw,
const double qx,
57 const double qy,
const double qz) {
73inline T QuaternionToHeading(
const Eigen::Quaternion<T> &q) {
74 return static_cast<T
>(QuaternionToHeading(q.w(), q.x(), q.y(), q.z()));
104 const Eigen::Vector3d &original) {
105 Eigen::Quaternion<double> quaternion(orientation.
qw(), orientation.
qx(),
106 orientation.
qy(), orientation.
qz());
107 return static_cast<Eigen::Vector3d
>(quaternion.toRotationMatrix() * original);
111 const Eigen::Vector3d &rotated) {
112 Eigen::Quaternion<double> quaternion(orientation.
qw(), orientation.
qx(),
113 orientation.
qy(), orientation.
qz());
114 return static_cast<Eigen::Vector3d
>(quaternion.toRotationMatrix().inverse() *
Any orientation of a rigid body on a 3-D space can be achieved by composing three rotations about the...
Eigen::Quaternion< T > ToQuaternion() const
Converts to a quaternion with a non-negative scalar part
Defines the EulerAnglesZXY class.
Math-related util functions.
Eigen::Vector3d QuaternionRotate(const Quaternion &orientation, const Eigen::Vector3d &original)
Eigen::Quaternion< T > HeadingToQuaternion(T heading)
EulerAnglesZXY< double > EulerAnglesZXYd
Eigen::Vector3d InverseQuaternionRotate(const Quaternion &orientation, const Eigen::Vector3d &rotated)
double NormalizeAngle(const double angle)
Normalize angle to [-PI, PI).