#include <Eigen/Eigen>#include <Eigen/Geometry>#include <boost/array.hpp>#include <sensor_msgs/Imu.h>

Go to the source code of this file.
Namespaces | |
| namespace | imu_filter |
| namespace | imu_filter::message_helper |
Functions | |
| static void | imu_filter::message_helper::angularRateFromImuMsg (const sensor_msgs::Imu::ConstPtr &msg, Eigen::Vector3d &v) |
| retrieve the angular rate from an IMU message | |
| static void | imu_filter::message_helper::eigenPose2Msg (const Eigen::Affine3d &pose, geometry_msgs::PoseStamped &msg) |
| Eigen::Affine3d to geometry_msgs::PoseStamped. | |
| static void | imu_filter::message_helper::linearAccelerationFromImuMsg (const sensor_msgs::Imu::ConstPtr &msg, Eigen::Vector3d &v) |
| retrieve the linear acceleration from an IMU message | |
| template<typename T , size_t r, size_t c> | |
| static void | imu_filter::message_helper::matrixPtrToEigen (const boost::array< T, r *c > &matPtr, Eigen::Matrix< T, r, c > &mat) |
| convert from boost array to eigen matrix | |
| static void | imu_filter::message_helper::quaternionFromImuMsg (const sensor_msgs::Imu::ConstPtr &msg, Eigen::Quaterniond &q) |
| retrieve the quaternion from an IMU message | |
| static void | imu_filter::message_helper::quaternionToMsg (const Eigen::Quaterniond &q, geometry_msgs::Quaternion &msg) |
| convert Eigen Quaternion to geometry_msgs::Quaternion | |
| static void | imu_filter::message_helper::vec3ToMsg (const Eigen::Vector3d &v, geometry_msgs::Vector3 &msg) |
| Eigen::Vector3d to geometry_msgs::Vector3. | |