quaternion_operation.h
Go to the documentation of this file.
1 #ifndef QUATERNION_OPERATION_QUATERNION_OPERATION_H_INCLUDED
2 #define QUATERNION_OPERATION_QUATERNION_OPERATION_H_INCLUDED
3 
15 //headers in ROS
16 #include <geometry_msgs/Quaternion.h>
17 #include <geometry_msgs/Vector3.h>
19 
20 //headers in Eigen
21 #define EIGEN_MPL2_ONLY
22 #include <Eigen/Core>
23 #include <Eigen/Geometry>
24 
32 geometry_msgs::Quaternion operator+(geometry_msgs::Quaternion quat1,geometry_msgs::Quaternion quat2);
33 
41 geometry_msgs::Quaternion operator*(geometry_msgs::Quaternion quat1,geometry_msgs::Quaternion quat2);
42 
48 {
55  geometry_msgs::Quaternion convertEulerAngleToQuaternion(geometry_msgs::Vector3 euler);
56 
63  Eigen::Matrix3d getRotationMatrix(geometry_msgs::Quaternion quat);
64 
71  geometry_msgs::Vector3 convertQuaternionToEulerAngle(geometry_msgs::Quaternion quat);
72 
81  bool equals(double a,double b);
82 
91  bool equals(geometry_msgs::Quaternion quat1,geometry_msgs::Quaternion quat2);
92 
99  Eigen::MatrixXd convertToEigenMatrix(geometry_msgs::Quaternion quat);
100 
107  geometry_msgs::Quaternion conjugate(geometry_msgs::Quaternion quat1);
108 
116  geometry_msgs::Quaternion rotation(geometry_msgs::Quaternion from,geometry_msgs::Quaternion rotation);
117 
126  geometry_msgs::Quaternion getRotation(geometry_msgs::Quaternion from,geometry_msgs::Quaternion to);
127 
136  geometry_msgs::Quaternion slerp(geometry_msgs::Quaternion quat1,geometry_msgs::Quaternion quat2,double t);
137 }
138 
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.


quaternion_operation
Author(s):
autogenerated on Mon Feb 28 2022 23:20:03