MRPT
2.0.4
mrpt
ros1bridge
imu.h
Go to the documentation of this file.
1
/* +------------------------------------------------------------------------+
2
| Mobile Robot Programming Toolkit (MRPT) |
3
| https://www.mrpt.org/ |
4
| |
5
| Copyright (c) 2005-2020, Individual contributors, see AUTHORS file |
6
| See: https://www.mrpt.org/Authors - All rights reserved. |
7
| Released under BSD License. See: https://www.mrpt.org/License |
8
+------------------------------------------------------------------------+ */
9
10
/*---------------------------------------------------------------
11
APPLICATION: mrpt_ros bridge
12
FILE: imu.h
13
AUTHOR: Raghavender Sahdev <raghavendersahdev@gmail.com>
14
---------------------------------------------------------------*/
15
#pragma once
16
17
#include <geometry_msgs/Pose.h>
18
#include <geometry_msgs/Quaternion.h>
19
#include <
mrpt/obs/CObservationIMU.h
>
20
#include <sensor_msgs/Imu.h>
21
#include <cstring>
// size_t
22
23
/// ROS message: http://docs.ros.org/api/sensor_msgs/html/msg/Imu.html
24
/// MRPT message:
25
/// https://github.com/MRPT/mrpt/blob/master/libs/obs/include/mrpt/obs/CObservationIMU.h
26
27
namespace
mrpt::ros1bridge
28
{
29
/** \addtogroup mrpt_ros1bridge_grp
30
* @{ */
31
32
/** Convert sensor_msgs/Imu -> mrpt::obs::CObservationIMU
33
* // STILL NEED TO WRITE CODE FOR COVARIANCE
34
* \return true on sucessful conversion, false on any error.
35
*/
36
bool
fromROS
(
const
sensor_msgs::Imu& msg,
mrpt::obs::CObservationIMU
& obj);
37
38
/** Convert mrpt::obs::CObservationIMU -> sensor_msgs/Imu
39
* The user must supply the "msg_header" field to be copied into the output
40
* message object, since that part does not appear in MRPT classes.
41
*
42
* Since COnservationIMU does not contain covariance terms NEED TO fix those.
43
* \return true on sucessful conversion, false on any error.
44
*/
45
bool
toROS
(
46
const
mrpt::obs::CObservationIMU
& obj,
const
std_msgs::Header& msg_header,
47
sensor_msgs::Imu& msg);
48
49
/** @} */
50
51
}
// namespace mrpt::ros1bridge
mrpt::obs::CObservationIMU
This class stores measurements from an Inertial Measurement Unit (IMU) (attitude estimation,...
Definition:
CObservationIMU.h:111
CObservationIMU.h
mrpt::ros1bridge::fromROS
bool fromROS(const sensor_msgs::NavSatFix &msg, mrpt::obs::CObservationGPS &obj)
Convert sensor_msgs/NavSatFix -> mrpt::obs::CObservationGPS.
Definition:
gps.cpp:20
mrpt::ros1bridge
ROS message: http://docs.ros.org/api/sensor_msgs/html/msg/NavSatFix.html MRPT message: https://github...
Definition:
gps.h:28
mrpt::ros1bridge::toROS
bool toROS(const mrpt::obs::CObservationGPS &obj, const std_msgs::Header &msg_header, sensor_msgs::NavSatFix &msg)
Convert mrpt::obs::CObservationGPS -> sensor_msgs/NavSatFix The user must supply the "msg_header" fie...
Definition:
gps.cpp:48
Page generated by
Doxygen 1.8.17
for MRPT 2.0.4 at Sun Jul 19 17:54:30 UTC 2020