Main Page
Namespaces
Classes
Files
File List
File Members
include
mrpt_bridge
laser_scan.h
Go to the documentation of this file.
1
/* +------------------------------------------------------------------------+
2
| Mobile Robot Programming Toolkit (MRPT) |
3
| http://www.mrpt.org/ |
4
| |
5
| Copyright (c) 2005-2018, Individual contributors, see AUTHORS file |
6
| See: http://www.mrpt.org/Authors - All rights reserved. |
7
| Released under BSD License. See details in http://www.mrpt.org/License |
8
+------------------------------------------------------------------------+ */
9
10
#pragma once
11
12
#include <cstdint>
13
#include <string>
14
15
namespace
std
16
{
17
template
<
class
T>
18
class
allocator;
19
}
20
21
namespace
geometry_msgs
22
{
23
template
<
class
ContainerAllocator>
24
struct
Pose_;
25
typedef
Pose_<std::allocator<void>>
Pose
;
26
}
// namespace geometry_msgs
27
28
namespace
sensor_msgs
29
{
30
template
<
class
ContainerAllocator>
31
struct
LaserScan_
;
32
typedef
LaserScan_<std::allocator<void>
>
LaserScan
;
33
}
// namespace sensor_msgs
34
35
namespace
mrpt
36
{
37
namespace
poses
38
{
39
class
CPose3D;
40
}
41
}
// namespace mrpt
42
#include <mrpt/version.h>
43
namespace
mrpt
44
{
45
namespace
obs
46
{
47
class
CObservation2DRangeScan;
48
}
49
}
// namespace mrpt
50
51
namespace
mrpt_bridge
52
{
61
bool
convert
(
62
const
sensor_msgs::LaserScan
& _msg,
const
mrpt::poses::CPose3D
& _pose,
63
mrpt::obs::CObservation2DRangeScan
& _obj);
64
70
bool
convert
(
71
const
mrpt::obs::CObservation2DRangeScan
& _obj,
72
sensor_msgs::LaserScan
& _msg);
73
79
bool
convert
(
80
const
mrpt::obs::CObservation2DRangeScan
& _obj,
81
sensor_msgs::LaserScan
& _msg,
geometry_msgs::Pose
& _pose);
82
85
}
// namespace mrpt_bridge
geometry_msgs::Pose_
Definition:
include/mrpt_bridge/beacon.h:24
std
sensor_msgs::LaserScan_
Definition:
laser_scan.h:31
mrpt_bridge
File includes methods for converting CNetworkOfPoses*DInf <=> NetworkOfPoses message types...
Definition:
include/mrpt_bridge/beacon.h:52
obs
obs
sensor_msgs
tf::Transform
mrpt::poses::CPose3D
mrpt_bridge::convert
bool convert(const mrpt::obs::CObservation2DRangeScan &_obj, sensor_msgs::LaserScan &_msg, geometry_msgs::Pose &_pose)
Definition:
laser_scan.cpp:92
geometry_msgs
mrpt
sensor_msgs::LaserScan
LaserScan_< std::allocator< void > > LaserScan
Definition:
laser_scan.h:31
mrpt::obs::CObservation2DRangeScan
mrpt_bridge
Author(s): Markus Bader
, Raphael Zack
autogenerated on Fri Feb 28 2020 03:22:14