MRPT
2.0.3
mrpt
ros1bridge
laser_scan.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
#pragma once
11
12
#include <geometry_msgs/Pose.h>
13
#include <
mrpt/obs/obs_frwds.h
>
14
#include <
mrpt/poses/poses_frwds.h
>
15
#include <sensor_msgs/LaserScan.h>
16
#include <cstdint>
17
#include <string>
18
19
namespace
mrpt::ros1bridge
20
{
21
/** \addtogroup mrpt_ros1bridge_grp
22
* @{ */
23
24
/** ROS->MRPT: Takes a sensor_msgs::LaserScan and the relative pose of the laser
25
* wrt base_link and builds a CObservation2DRangeScan
26
* \return true on sucessful conversion, false on any error.
27
* \sa toROS
28
*/
29
bool
fromROS
(
30
const
sensor_msgs::LaserScan& msg,
const
mrpt::poses::CPose3D
& pose,
31
mrpt::obs::CObservation2DRangeScan
& obj);
32
33
/** MRPT->ROS: Takes a CObservation2DRangeScan and outputs range data in
34
* sensor_msgs::LaserScan
35
* \return true on sucessful conversion, false on any error.
36
* \sa fromROS
37
*/
38
bool
toROS
(
39
const
mrpt::obs::CObservation2DRangeScan
& obj, sensor_msgs::LaserScan& msg);
40
41
/** MRPT->ROS: Takes a CObservation2DRangeScan and outputs range data in
42
* sensor_msgs::LaserScan + the relative pose of the laser wrt base_link
43
* \return true on sucessful conversion, false on any error.
44
* \sa fromROS
45
*/
46
bool
toROS
(
47
const
mrpt::obs::CObservation2DRangeScan
& obj, sensor_msgs::LaserScan& msg,
48
geometry_msgs::Pose& pose);
49
50
/** @} */
51
52
}
// namespace mrpt::ros1bridge
mrpt::obs::CObservation2DRangeScan
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
Definition:
CObservation2DRangeScan.h:54
mrpt::poses::CPose3D
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition:
CPose3D.h:85
obs_frwds.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
poses_frwds.h
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.3 at Fri May 15 23:51:15 UTC 2020