Main Page
Namespaces
Classes
Files
File List
File Members
include
mrpt_bridge
point_cloud2.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
namespace
std
13
{
14
template
<
class
T>
15
class
allocator;
16
}
17
18
namespace
std_msgs
19
{
20
template
<
class
ContainerAllocator>
21
struct
Header_;
22
typedef
Header_<std::allocator<void>>
Header
;
23
}
// namespace std_msgs
24
25
namespace
sensor_msgs
26
{
27
template
<
class
ContainerAllocator>
28
struct
PointCloud2_
;
29
typedef
PointCloud2_<std::allocator<void>
>
PointCloud2
;
30
}
// namespace sensor_msgs
31
32
#include <mrpt/version.h>
33
namespace
mrpt
34
{
35
namespace
maps
36
{
37
class
CSimplePointsMap;
38
class
CColouredPointsMap;
39
}
// namespace maps
40
}
// namespace mrpt
41
42
namespace
mrpt_bridge
43
{
53
bool
copy
(
54
const
sensor_msgs::PointCloud2
& msg,
mrpt::maps::CSimplePointsMap
&
obj
);
55
65
bool
copy
(
66
const
mrpt::maps::CSimplePointsMap
&
obj
,
const
std_msgs::Header
& msg_header,
67
sensor_msgs::PointCloud2
& msg);
68
71
}
// namespace mrpt_bridge
Header
std
mrpt::maps::CSimplePointsMap
sensor_msgs::PointCloud2
PointCloud2_< std::allocator< void > > PointCloud2
Definition:
point_cloud2.h:28
mrpt_bridge
File includes methods for converting CNetworkOfPoses*DInf <=> NetworkOfPoses message types...
Definition:
include/mrpt_bridge/beacon.h:52
sensor_msgs
obj
GLhandleARB obj
std_msgs
mrpt
sensor_msgs::PointCloud2_
Definition:
point_cloud2.h:28
std_msgs::Header_
Definition:
map.h:24
mrpt_bridge::copy
bool copy(const mrpt::maps::CSimplePointsMap &obj, const std_msgs::Header &msg_header, sensor_msgs::PointCloud2 &msg)
Definition:
point_cloud2.cpp:113
mrpt_bridge
Author(s): Markus Bader
, Raphael Zack
autogenerated on Fri Feb 28 2020 03:22:14