1 #ifndef QUATERNION_OPERATION_QUATERNION_OPERATION_H_INCLUDED 2 #define QUATERNION_OPERATION_QUATERNION_OPERATION_H_INCLUDED 16 #include <geometry_msgs/Quaternion.h> 17 #include <geometry_msgs/Vector3.h> 21 #define EIGEN_MPL2_ONLY 23 #include <Eigen/Geometry> 32 geometry_msgs::Quaternion
operator+(geometry_msgs::Quaternion quat1,geometry_msgs::Quaternion quat2);
41 geometry_msgs::Quaternion
operator*(geometry_msgs::Quaternion quat1,geometry_msgs::Quaternion quat2);
81 bool equals(
double a,
double b);
91 bool equals(geometry_msgs::Quaternion quat1,geometry_msgs::Quaternion quat2);
107 geometry_msgs::Quaternion
conjugate(geometry_msgs::Quaternion quat1);
116 geometry_msgs::Quaternion
rotation(geometry_msgs::Quaternion from,geometry_msgs::Quaternion
rotation);
126 geometry_msgs::Quaternion
getRotation(geometry_msgs::Quaternion from,geometry_msgs::Quaternion to);
136 geometry_msgs::Quaternion
slerp(geometry_msgs::Quaternion quat1,geometry_msgs::Quaternion quat2,
double t);
139 #endif //QUATERNION_OPERATION_QUATERNION_OPERATION_H_INCLUDED geometry_msgs::Quaternion convertEulerAngleToQuaternion(geometry_msgs::Vector3 euler)
convert Euler angles to Quaternion
Eigen::MatrixXd convertToEigenMatrix(geometry_msgs::Quaternion quat)
convert geometry_msgs::Quaternion to Eigen::MatrixXd
geometry_msgs::Quaternion getRotation(geometry_msgs::Quaternion from, geometry_msgs::Quaternion to)
Get the Rotation from 2 Quaternions.
geometry_msgs::Quaternion operator*(geometry_msgs::Quaternion quat1, geometry_msgs::Quaternion quat2)
Operator overload for geometry_msgs::Quaternion (Multiplication)
geometry_msgs::Quaternion conjugate(geometry_msgs::Quaternion quat1)
get conjugate Quaternion
namespace of quaternion_operation ROS package
geometry_msgs::Quaternion rotation(geometry_msgs::Quaternion from, geometry_msgs::Quaternion rotation)
rotate Quaternion
geometry_msgs::Vector3 convertQuaternionToEulerAngle(geometry_msgs::Quaternion quat)
convert Quaternion to the Euler angle
bool equals(double a, double b)
checke 2 double values are equal or not
geometry_msgs::Quaternion slerp(geometry_msgs::Quaternion quat1, geometry_msgs::Quaternion quat2, double t)
Spherical linear interpolation function for geometry_msgs::Quaternion.
geometry_msgs::Quaternion operator+(geometry_msgs::Quaternion quat1, geometry_msgs::Quaternion quat2)
Operator overload for geometry_msgs::Quaternion (Addition)
Eigen::Matrix3d getRotationMatrix(geometry_msgs::Quaternion quat)
Get the Rotation Matrix from geometry_msgs::Quaternion.