Main Page
Namespaces
Classes
Files
File List
File Members
include
mrpt_bridge
landmark.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
/*
11
* File: landmark.h
12
* Author: Vladislav Tananaev
13
*
14
*/
15
16
#pragma once
17
18
#include <cstdint>
19
#include <string>
20
21
namespace
std
22
{
23
template
<
class
T>
24
class
allocator;
25
}
26
27
namespace
geometry_msgs
28
{
29
template
<
class
ContainerAllocator>
30
struct
Pose_;
31
typedef
Pose_<std::allocator<void>>
Pose
;
32
}
// namespace geometry_msgs
33
34
namespace
mrpt_msgs
35
{
36
template
<
class
ContainerAllocator>
37
struct
ObservationRangeBearing_
;
38
typedef
ObservationRangeBearing_<std::allocator<void>
>
ObservationRangeBearing
;
39
}
// namespace mrpt_msgs
40
41
namespace
mrpt
42
{
43
namespace
poses
44
{
45
class
CPose3D;
46
}
47
}
// namespace mrpt
48
#include <mrpt/version.h>
49
50
namespace
mrpt
51
{
52
namespace
obs
53
{
54
class
CObservationBearingRange;
55
}
56
}
// namespace mrpt
57
58
namespace
mrpt_bridge
59
{
68
bool
convert
(
69
const
mrpt_msgs::ObservationRangeBearing
& _msg,
70
const
mrpt::poses::CPose3D
& _pose,
mrpt::obs::CObservationBearingRange
& _obj
71
72
);
73
79
bool
convert
(
80
const
mrpt::obs::CObservationBearingRange
& _obj,
81
mrpt_msgs::ObservationRangeBearing
& _msg);
82
89
bool
convert
(
90
const
mrpt::obs::CObservationBearingRange
& _obj,
91
mrpt_msgs::ObservationRangeBearing
& _msg,
geometry_msgs::Pose
& _pose);
92
95
}
// namespace mrpt_bridge
mrpt_msgs::ObservationRangeBearing
ObservationRangeBearing_< std::allocator< void > > ObservationRangeBearing
Definition:
landmark.h:37
geometry_msgs::Pose_
Definition:
include/mrpt_bridge/beacon.h:24
mrpt_msgs
Definition:
include/mrpt_bridge/beacon.h:28
mrpt_bridge::convert
bool convert(const mrpt::obs::CObservationBearingRange &_obj, mrpt_msgs::ObservationRangeBearing &_msg, geometry_msgs::Pose &_pose)
Definition:
landmark.cpp:102
std
mrpt_msgs::ObservationRangeBearing_
Definition:
landmark.h:37
mrpt_bridge
File includes methods for converting CNetworkOfPoses*DInf <=> NetworkOfPoses message types...
Definition:
include/mrpt_bridge/beacon.h:52
obs
obs
tf::Transform
mrpt::poses::CPose3D
geometry_msgs
mrpt
mrpt::obs::CObservationBearingRange
mrpt_bridge
Author(s): Markus Bader
, Raphael Zack
autogenerated on Fri Feb 28 2020 03:22:14