namespace of quaternion_operation ROS package More...
Functions | |
geometry_msgs::Quaternion | conjugate (geometry_msgs::Quaternion quat1) |
get conjugate Quaternion More... | |
geometry_msgs::Quaternion | convertEulerAngleToQuaternion (geometry_msgs::Vector3 euler) |
convert Euler angles to Quaternion More... | |
geometry_msgs::Vector3 | convertQuaternionToEulerAngle (geometry_msgs::Quaternion quat) |
convert Quaternion to the Euler angle More... | |
Eigen::MatrixXd | convertToEigenMatrix (geometry_msgs::Quaternion quat) |
convert geometry_msgs::Quaternion to Eigen::MatrixXd More... | |
bool | equals (double a, double b) |
checke 2 double values are equal or not More... | |
bool | equals (geometry_msgs::Quaternion quat1, geometry_msgs::Quaternion quat2) |
check 2 Quaternion values are equal or not More... | |
geometry_msgs::Quaternion | getRotation (geometry_msgs::Quaternion from, geometry_msgs::Quaternion to) |
Get the Rotation from 2 Quaternions. More... | |
Eigen::Matrix3d | getRotationMatrix (geometry_msgs::Quaternion quat) |
Get the Rotation Matrix from geometry_msgs::Quaternion. More... | |
geometry_msgs::Quaternion | rotation (geometry_msgs::Quaternion from, geometry_msgs::Quaternion rotation) |
rotate Quaternion More... | |
geometry_msgs::Quaternion | slerp (geometry_msgs::Quaternion quat1, geometry_msgs::Quaternion quat2, double t) |
Spherical linear interpolation function for geometry_msgs::Quaternion. More... | |
namespace of quaternion_operation ROS package
geometry_msgs::Quaternion quaternion_operation::conjugate | ( | geometry_msgs::Quaternion | quat1 | ) |
get conjugate Quaternion
quat1 | input Quaternion |
Definition at line 123 of file quaternion_operation.cpp.
geometry_msgs::Quaternion quaternion_operation::convertEulerAngleToQuaternion | ( | geometry_msgs::Vector3 | euler | ) |
convert Euler angles to Quaternion
euler | Euler angles |
Definition at line 36 of file quaternion_operation.cpp.
geometry_msgs::Vector3 quaternion_operation::convertQuaternionToEulerAngle | ( | geometry_msgs::Quaternion | quat | ) |
convert Quaternion to the Euler angle
quat | Quaternion |
Definition at line 78 of file quaternion_operation.cpp.
Eigen::MatrixXd quaternion_operation::convertToEigenMatrix | ( | geometry_msgs::Quaternion | quat | ) |
convert geometry_msgs::Quaternion to Eigen::MatrixXd
quat | input Quaternion |
Definition at line 116 of file quaternion_operation.cpp.
bool quaternion_operation::equals | ( | double | a, |
double | b | ||
) |
checke 2 double values are equal or not
a | |
b |
Definition at line 98 of file quaternion_operation.cpp.
bool quaternion_operation::equals | ( | geometry_msgs::Quaternion | quat1, |
geometry_msgs::Quaternion | quat2 | ||
) |
check 2 Quaternion values are equal or not
quat1 | |
quat2 |
Definition at line 107 of file quaternion_operation.cpp.
geometry_msgs::Quaternion quaternion_operation::getRotation | ( | geometry_msgs::Quaternion | from, |
geometry_msgs::Quaternion | to | ||
) |
Get the Rotation from 2 Quaternions.
from | from pose orientation |
to | to pose orientation |
Definition at line 137 of file quaternion_operation.cpp.
Eigen::Matrix3d quaternion_operation::getRotationMatrix | ( | geometry_msgs::Quaternion | quat | ) |
Get the Rotation Matrix from geometry_msgs::Quaternion.
quat | input geometry_msgs::Quaternion |
Definition at line 64 of file quaternion_operation.cpp.
geometry_msgs::Quaternion quaternion_operation::rotation | ( | geometry_msgs::Quaternion | from, |
geometry_msgs::Quaternion | rotation | ||
) |
rotate Quaternion
from | from pose orientation |
rotation | Rotation quaternion |
Definition at line 132 of file quaternion_operation.cpp.
geometry_msgs::Quaternion quaternion_operation::slerp | ( | geometry_msgs::Quaternion | quat1, |
geometry_msgs::Quaternion | quat2, | ||
double | t | ||
) |
Spherical linear interpolation function for geometry_msgs::Quaternion.
quat1 | |
quat2 | |
t | parameter for interpolation (if t=0,return==quat1),(if t=1,return==quat2) |
Definition at line 144 of file quaternion_operation.cpp.