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
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>
41 template <class ContainerAllocator>
42 struct 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;
64 } // namespace poses
65 } // namespace mrpt
66 
67 namespace mrpt_bridge
68 {
74  const mrpt::math::CMatrixDouble33& _src, tf::Matrix3x3& _des);
75 
78 
85 
88  const mrpt::poses::CPose3D& _src, geometry_msgs::Pose& _des);
89 
92  const mrpt::math::TPose2D& _src, geometry_msgs::Pose& _des);
93 
96  const mrpt::poses::CPose2D& _src, geometry_msgs::Pose& _des);
97 
102 
108 
112 
116  const mrpt::poses::CPosePDFGaussian& _src,
118 
124 
127  const mrpt::poses::CQuaternionDouble& _src,
129 
137  const tf::Transform& _src, mrpt::poses::CPose3D& _des);
138 
141  const tf::Matrix3x3& _src, mrpt::math::CMatrixDouble33& _des);
142 
145  const geometry_msgs::Pose& _src, mrpt::poses::CPose2D& _des);
146 
149  const geometry_msgs::Pose& _src, mrpt::poses::CPose3D& _des);
150 
155 
161 
167 
173 
176  const geometry_msgs::Quaternion& _src,
178 
180 } // namespace mrpt_bridge
PoseWithCovariance_< std::allocator< void > > PoseWithCovariance
Definition: pose.h:39
Quaternion_< std::allocator< void > > Quaternion
Definition: pose.h:42
File includes methods for converting CNetworkOfPoses*DInf <=> NetworkOfPoses message types...
mrpt::poses::CQuaternionDouble & convert(const geometry_msgs::Quaternion &_src, mrpt::poses::CQuaternionDouble &_des)
Definition: pose.cpp:338


mrpt_bridge
Author(s): Markus Bader , Raphael Zack
autogenerated on Fri Feb 28 2020 03:22:14