imu.h
Go to the documentation of this file.
00001 /* +------------------------------------------------------------------------+
00002    |                     Mobile Robot Programming Toolkit (MRPT)            |
00003    |                          http://www.mrpt.org/                          |
00004    |                                                                        |
00005    | Copyright (c) 2005-2017, Individual contributors, see AUTHORS file     |
00006    | See: http://www.mrpt.org/Authors - All rights reserved.                |
00007    | Released under BSD License. See details in http://www.mrpt.org/License |
00008    +------------------------------------------------------------------------+ */
00009 
00010 /*---------------------------------------------------------------
00011         APPLICATION: mrpt_ros bridge
00012         FILE: imu.h
00013         AUTHOR: Raghavender Sahdev <raghavendersahdev@gmail.com>
00014   ---------------------------------------------------------------*/
00015 #ifndef MRPT_BRIDGE_IMU_H
00016 #define MRPT_BRIDGE_IMU_H
00017 
00018 #include <cstring> // size_t
00019 #include <sensor_msgs/Imu.h>
00020 #include <mrpt/obs/CObservationIMU.h>
00021 #include <geometry_msgs/Pose.h>
00022 #include <geometry_msgs/Quaternion.h>
00023 
00024 
00025 using namespace mrpt::obs;
00026 
00027 
00030 
00031 namespace mrpt_bridge
00032 {
00033     namespace imu
00034     {
00035 
00040         bool ros2mrpt(const sensor_msgs::Imu &msg, CObservationIMU obj);
00041 
00048         bool mrpt2ros(const CObservationIMU &obj, const std_msgs::Header &msg_header, sensor_msgs::Imu &msg);
00049 
00050     }
00051 }
00052 
00053 
00054 
00055 #endif //MRPT_BRIDGE_IMU_H
00056 
00057 
00058 


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