Main Page
Namespaces
Classes
Files
File List
File Members
include
mrpt_bridge
pose.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 <cstring>
// size_t
13
14
#include <mrpt/version.h>
15
#if MRPT_VERSION < 0x199
16
#include <
mrpt/math/CMatrixFixedNumeric.h
>
17
#else
18
#include <mrpt/math/CMatrixFixed.h>
19
#endif
20
21
namespace
std
22
{
23
template
<
class
T>
24
class
allocator;
25
}
26
27
namespace
tf
28
{
29
class
Transform;
30
class
Matrix3x3;
31
}
// namespace tf
32
33
namespace
geometry_msgs
34
{
35
template
<
class
ContainerAllocator>
36
struct
Pose_;
37
typedef
Pose_<std::allocator<void>>
Pose
;
38
template
<
class
ContainerAllocator>
39
struct
PoseWithCovariance_
;
40
typedef
PoseWithCovariance_<std::allocator<void>
>
PoseWithCovariance
;
41
template
<
class
ContainerAllocator>
42
struct
Quaternion_
;
43
typedef
Quaternion_<std::allocator<void>
>
Quaternion
;
44
}
// namespace geometry_msgs
45
46
namespace
mrpt
47
{
48
namespace
math
49
{
50
template
<
class
T>
51
class
CQuaternion;
52
struct
TPose3D;
53
struct
TPose2D;
54
}
// namespace math
55
namespace
poses
56
{
57
class
CPose2D;
58
class
CPose3D;
59
class
CPosePDFGaussian;
60
class
CPosePDFGaussianInf;
61
class
CPose3DPDFGaussian;
62
class
CPose3DPDFGaussianInf
;
63
typedef
math::CQuaternion<double>
CQuaternionDouble
;
64
}
// namespace poses
65
}
// namespace mrpt
66
67
namespace
mrpt_bridge
68
{
73
tf::Matrix3x3
&
convert
(
74
const
mrpt::math::CMatrixDouble33
& _src,
tf::Matrix3x3
& _des);
75
77
tf::Transform
&
convert
(
const
mrpt::poses::CPose3D
& _src,
tf::Transform
& _des);
78
80
tf::Transform
&
convert
(
const
mrpt::math::TPose3D
& _src,
tf::Transform
& _des);
82
tf::Transform
&
convert
(
const
mrpt::poses::CPose2D
& _src,
tf::Transform
& _des);
84
tf::Transform
&
convert
(
const
mrpt::math::TPose2D
& _src,
tf::Transform
& _des);
85
87
geometry_msgs::Pose
&
convert
(
88
const
mrpt::poses::CPose3D
& _src,
geometry_msgs::Pose
& _des);
89
91
geometry_msgs::Pose
&
convert
(
92
const
mrpt::math::TPose2D
& _src,
geometry_msgs::Pose
& _des);
93
95
geometry_msgs::Pose
&
convert
(
96
const
mrpt::poses::CPose2D
& _src,
geometry_msgs::Pose
& _des);
97
99
geometry_msgs::PoseWithCovariance
&
convert
(
100
const
mrpt::poses::CPose3DPDFGaussian
& _src,
101
geometry_msgs::PoseWithCovariance
& _des);
102
105
geometry_msgs::PoseWithCovariance
&
convert
(
106
const
mrpt::poses::CPose3DPDFGaussianInf
& _src,
107
geometry_msgs::PoseWithCovariance
& _des);
108
110
tf::Transform
&
convert
(
111
const
mrpt::poses::CPose3DPDFGaussian
& _src,
tf::Transform
& _des);
112
115
geometry_msgs::PoseWithCovariance
&
convert
(
116
const
mrpt::poses::CPosePDFGaussian
& _src,
117
geometry_msgs::PoseWithCovariance
& _des);
118
121
geometry_msgs::PoseWithCovariance
&
convert
(
122
const
mrpt::poses::CPosePDFGaussianInf
& _src,
123
geometry_msgs::PoseWithCovariance
& _des);
124
126
geometry_msgs::Quaternion
&
convert
(
127
const
mrpt::poses::CQuaternionDouble
& _src,
128
geometry_msgs::Quaternion
& _des);
129
136
mrpt::poses::CPose3D
&
convert
(
137
const
tf::Transform
& _src,
mrpt::poses::CPose3D
& _des);
138
140
mrpt::math::CMatrixDouble33
&
convert
(
141
const
tf::Matrix3x3
& _src,
mrpt::math::CMatrixDouble33
& _des);
142
144
mrpt::poses::CPose2D
&
convert
(
145
const
geometry_msgs::Pose
& _src,
mrpt::poses::CPose2D
& _des);
146
148
mrpt::poses::CPose3D
&
convert
(
149
const
geometry_msgs::Pose
& _src,
mrpt::poses::CPose3D
& _des);
150
152
mrpt::poses::CPose3DPDFGaussian
&
convert
(
153
const
geometry_msgs::PoseWithCovariance
& _src,
154
mrpt::poses::CPose3DPDFGaussian
& _des);
155
158
mrpt::poses::CPose3DPDFGaussianInf
&
convert
(
159
const
geometry_msgs::PoseWithCovariance
& _src,
160
mrpt::poses::CPose3DPDFGaussianInf
& _des);
161
164
mrpt::poses::CPosePDFGaussian
&
convert
(
165
const
geometry_msgs::PoseWithCovariance
& _src,
166
mrpt::poses::CPosePDFGaussian
& _des);
167
170
mrpt::poses::CPosePDFGaussianInf
&
convert
(
171
const
geometry_msgs::PoseWithCovariance
& _src,
172
mrpt::poses::CPosePDFGaussianInf
& _des);
173
175
mrpt::poses::CQuaternionDouble
&
convert
(
176
const
geometry_msgs::Quaternion
& _src,
177
mrpt::poses::CQuaternionDouble
& _des);
178
180
}
// namespace mrpt_bridge
mrpt::poses::CPose2D
geometry_msgs::PoseWithCovariance
PoseWithCovariance_< std::allocator< void > > PoseWithCovariance
Definition:
pose.h:39
geometry_msgs::Quaternion
Quaternion_< std::allocator< void > > Quaternion
Definition:
pose.h:42
geometry_msgs::Pose_
Definition:
include/mrpt_bridge/beacon.h:24
std
tf
mrpt::math::TPose3D
tf::Matrix3x3
CMatrixFixedNumeric.h
mrpt::poses::CPosePDFGaussianInf
mrpt_bridge
File includes methods for converting CNetworkOfPoses*DInf <=> NetworkOfPoses message types...
Definition:
include/mrpt_bridge/beacon.h:52
tf::Transform
geometry_msgs::Quaternion_
Definition:
pose.h:42
mrpt::poses::CPose3D
geometry_msgs::PoseWithCovariance_
Definition:
pose.h:39
geometry_msgs
mrpt
mrpt::poses::CPosePDFGaussian
mrpt_bridge::convert
mrpt::poses::CQuaternionDouble & convert(const geometry_msgs::Quaternion &_src, mrpt::poses::CQuaternionDouble &_des)
Definition:
pose.cpp:338
CMatrixFixedNumeric< double, 3, 3 >
mrpt::poses::CPose3DPDFGaussian
mrpt::poses::CPose3DPDFGaussianInf
mrpt::math::CQuaternion
Definition:
pose.h:51
mrpt::math::TPose2D
mrpt_bridge
Author(s): Markus Bader
, Raphael Zack
autogenerated on Fri Feb 28 2020 03:22:14