Functions
mrpt_bridge::imu Namespace Reference

Functions

bool mrpt2ros (const CObservationIMU &obj, const std_msgs::Header &msg_header, sensor_msgs::Imu &msg)
bool ros2mrpt (const sensor_msgs::Imu &msg, CObservationIMU obj)

Function Documentation

bool mrpt_bridge::imu::mrpt2ros ( const CObservationIMU &  obj,
const std_msgs::Header &  msg_header,
sensor_msgs::Imu &  msg 
)

Convert mrpt::obs::CObservationIMU -> sensor_msgs/Imu The user must supply the "msg_header" field to be copied into the output message object, since that part does not appear in MRPT classes.

Since COnservationIMU does not contain covariance terms NEED TO fix those.

Returns:
true on sucessful conversion, false on any error.

computing acceleration in global navigation frame not in local vehicle frame, might be the other way round

following covariance assignments might be wrong, covariances need to be double checked as per ROS message

Definition at line 46 of file imu.cpp.

bool mrpt_bridge::imu::ros2mrpt ( const sensor_msgs::Imu &  msg,
CObservationIMU  obj 
)

Convert sensor_msgs/Imu -> mrpt::obs::CObservationIMU // STILL NEED TO WRITE CODE FOR COVARIANCE

Returns:
true on sucessful conversion, false on any error.

Definition at line 25 of file imu.cpp.



mrpt_bridge
Author(s): Markus Bader , Raphael Zack
autogenerated on Mon Sep 18 2017 03:12:06