|
ethzasl-msf - Modular Sensor Fusion
Time delay compensated single and multi sensor fusion framework based on an EKF
|
#include <Eigen/Dense>#include <Eigen/Geometry>#include <geometry_msgs/Quaternion.h>#include <geometry_msgs/Point.h>Go to the source code of this file.
Namespaces | |
| namespace | eigen_conversions |
Functions | |
| template<class Scalar > | |
| void | eigen_conversions::quaternionToMsg (const Eigen::Quaternion< Scalar > &q_in, geometry_msgs::Quaternion &q_out) |
| Copies eigen quaternion to geometry_msgs/quaternion. | |
| template<class Scalar > | |
| geometry_msgs::Quaternion | eigen_conversions::quaternionToMsg (const Eigen::Quaternion< Scalar > &q_in) |
| Copies eigen quaternion to geometry_msgs/quaternion. | |
| template<class Derived , class Point > | |
| void | eigen_conversions::vector3dToPoint (const Eigen::MatrixBase< Derived > &vec, Point &point) |
| Copies an eigen 3d vector to a 3d Point struct. point has to have members x,y,z! | |
| template<class Derived , class Point > | |
| Point | eigen_conversions::vector3dToPoint (const Eigen::MatrixBase< Derived > &vec) |
| Copies an eigen 3d vector to a 3d Point struct. point has to have members x,y,z! | |
1.8.1.2