Functions | |
static void | angularRateFromImuMsg (const sensor_msgs::Imu::ConstPtr &msg, Eigen::Vector3d &v) |
retrieve the angular rate from an IMU message | |
static void | eigenPose2Msg (const Eigen::Affine3d &pose, geometry_msgs::PoseStamped &msg) |
Eigen::Affine3d to geometry_msgs::PoseStamped. | |
static void | 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 | matrixPtrToEigen (const boost::array< T, r *c > &matPtr, Eigen::Matrix< T, r, c > &mat) |
convert from boost array to eigen matrix | |
static void | quaternionFromImuMsg (const sensor_msgs::Imu::ConstPtr &msg, Eigen::Quaterniond &q) |
retrieve the quaternion from an IMU message | |
static void | quaternionToMsg (const Eigen::Quaterniond &q, geometry_msgs::Quaternion &msg) |
convert Eigen Quaternion to geometry_msgs::Quaternion | |
static void | vec3ToMsg (const Eigen::Vector3d &v, geometry_msgs::Vector3 &msg) |
Eigen::Vector3d to geometry_msgs::Vector3. |
static void imu_filter::message_helper::angularRateFromImuMsg | ( | const sensor_msgs::Imu::ConstPtr & | msg, |
Eigen::Vector3d & | v | ||
) | [inline, static] |
retrieve the angular rate from an IMU message
Definition at line 78 of file message_helper.h.
static void imu_filter::message_helper::eigenPose2Msg | ( | const Eigen::Affine3d & | pose, |
geometry_msgs::PoseStamped & | msg | ||
) | [inline, static] |
Eigen::Affine3d to geometry_msgs::PoseStamped.
Definition at line 119 of file message_helper.h.
static void imu_filter::message_helper::linearAccelerationFromImuMsg | ( | const sensor_msgs::Imu::ConstPtr & | msg, |
Eigen::Vector3d & | v | ||
) | [inline, static] |
retrieve the linear acceleration from an IMU message
Definition at line 88 of file message_helper.h.
static void imu_filter::message_helper::matrixPtrToEigen | ( | const boost::array< T, r *c > & | matPtr, |
Eigen::Matrix< T, r, c > & | mat | ||
) | [inline, static] |
convert from boost array to eigen matrix
Definition at line 57 of file message_helper.h.
static void imu_filter::message_helper::quaternionFromImuMsg | ( | const sensor_msgs::Imu::ConstPtr & | msg, |
Eigen::Quaterniond & | q | ||
) | [inline, static] |
retrieve the quaternion from an IMU message
Definition at line 67 of file message_helper.h.
static void imu_filter::message_helper::quaternionToMsg | ( | const Eigen::Quaterniond & | q, |
geometry_msgs::Quaternion & | msg | ||
) | [inline, static] |
convert Eigen Quaternion to geometry_msgs::Quaternion
Definition at line 98 of file message_helper.h.
static void imu_filter::message_helper::vec3ToMsg | ( | const Eigen::Vector3d & | v, |
geometry_msgs::Vector3 & | msg | ||
) | [inline, static] |
Eigen::Vector3d to geometry_msgs::Vector3.
Definition at line 109 of file message_helper.h.