#include <geometry_msgs/Quaternion.h>
#include <tf2/LinearMath/Quaternion.h>
#include <eigen3/Eigen/Core>
Go to the source code of this file.
|
| void | quatToRPY (const geometry_msgs::Quaternion &q, double &roll, double &pitch, double &yaw) |
| |
| double | yawFromQuat (const geometry_msgs::Quaternion &q) |
| |
| tf2::Quaternion | getAverageQuaternion (const std::vector< tf2::Quaternion > &quaternions, const std::vector< double > &weights) |
| |
| tf2::Quaternion | rotationMatrixToQuaternion (const Eigen::Map< Eigen::Matrix3d > &rot) |
| |
◆ getAverageQuaternion()
| tf2::Quaternion getAverageQuaternion |
( |
const std::vector< tf2::Quaternion > & | quaternions, |
|
|
const std::vector< double > & | weights ) |
◆ quatToRPY()
| void quatToRPY |
( |
const geometry_msgs::Quaternion & | q, |
|
|
double & | roll, |
|
|
double & | pitch, |
|
|
double & | yaw ) |
Convert a quaternion to RPY. Uses ZYX order (yaw-pitch-roll), but returns angles in (roll, pitch, yaw).
◆ rotationMatrixToQuaternion()
| tf2::Quaternion rotationMatrixToQuaternion |
( |
const Eigen::Map< Eigen::Matrix3d > & | rot | ) |
|
◆ yawFromQuat()
| double yawFromQuat |
( |
const geometry_msgs::Quaternion & | q | ) |
|