MRPT  1.9.9
pose.h
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | https://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2020, Individual contributors, see AUTHORS file |
6  | See: https://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See: https://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 
10 #pragma once
11 
12 #include <geometry_msgs/PoseWithCovariance.h>
13 #include <geometry_msgs/Quaternion.h>
14 #include <mrpt/math/CMatrixFixed.h>
15 #include <mrpt/math/CQuaternion.h>
16 #include <mrpt/math/TPose2D.h>
17 #include <mrpt/math/TPose3D.h>
18 #include <mrpt/poses/poses_frwds.h>
19 #include <tf2/LinearMath/Matrix3x3.h>
20 #include <tf2/LinearMath/Transform.h>
21 #include <cstring> // size_t
22 
23 namespace mrpt::ros1bridge
24 {
25 /** \addtogroup mrpt_ros1bridge_grp
26  * @{ */
27 
28 tf2::Matrix3x3 toROS(const mrpt::math::CMatrixDouble33& src);
29 
30 tf2::Transform toROS_tfTransform(const mrpt::poses::CPose2D& src);
31 geometry_msgs::Pose toROS_Pose(const mrpt::poses::CPose2D& src);
32 
33 tf2::Transform toROS_tfTransform(const mrpt::math::TPose2D& src);
34 geometry_msgs::Pose toROS_Pose(const mrpt::math::TPose2D& src);
35 
36 tf2::Transform toROS_tfTransform(const mrpt::poses::CPose3D& src);
37 geometry_msgs::Pose toROS_Pose(const mrpt::poses::CPose3D& src);
38 
39 tf2::Transform toROS_tfTransform(const mrpt::math::TPose3D& src);
40 geometry_msgs::Pose toROS_Pose(const mrpt::math::TPose3D& src);
41 
42 geometry_msgs::PoseWithCovariance toROS_Pose(
44 
45 geometry_msgs::PoseWithCovariance toROS(
47 
48 geometry_msgs::PoseWithCovariance toROS(
50 
51 geometry_msgs::PoseWithCovariance toROS(
53 
54 geometry_msgs::Quaternion toROS(const mrpt::math::CQuaternionDouble& src);
55 
56 mrpt::poses::CPose3D fromROS(const tf2::Transform& src);
57 mrpt::math::CMatrixDouble33 fromROS(const tf2::Matrix3x3& src);
58 mrpt::poses::CPose3D fromROS(const geometry_msgs::Pose& src);
60  const geometry_msgs::PoseWithCovariance& src);
61 mrpt::math::CQuaternionDouble fromROS(const geometry_msgs::Quaternion& src);
62 
63 /** @} */
64 } // namespace mrpt::ros1bridge
Declares a class that represents a Probability Density function (PDF) of a 2D pose ...
bool toROS(const mrpt::obs::CObservationGPS &obj, const std_msgs::Header &msg_header, sensor_msgs::NavSatFix &msg)
Convert mrpt::obs::CObservationGPS -> sensor_msgs/NavSatFix The user must supply the "msg_header" fie...
Definition: gps.cpp:48
A Probability Density function (PDF) of a 2D pose as a Gaussian with a mean and the inverse of the c...
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
Definition: CPose2D.h:39
ROS message: http://docs.ros.org/api/sensor_msgs/html/msg/NavSatFix.html MRPT message: https://github...
Definition: gps.h:28
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:85
bool fromROS(const sensor_msgs::NavSatFix &msg, mrpt::obs::CObservationGPS &obj)
Convert sensor_msgs/NavSatFix -> mrpt::obs::CObservationGPS.
Definition: gps.cpp:20
Lightweight 3D pose (three spatial coordinates, plus three angular coordinates).
Definition: TPose3D.h:24
Declares a class that represents a Probability Density function (PDF) of a 3D pose as a Gaussian des...
Lightweight 2D pose.
Definition: TPose2D.h:22
Declares a class that represents a Probability Density function (PDF) of a 3D pose ...
tf2::Transform toROS_tfTransform(const mrpt::poses::CPose2D &src)
Definition: pose.cpp:49
geometry_msgs::Pose toROS_Pose(const mrpt::poses::CPose2D &src)
Definition: pose.cpp:54
A quaternion, which can represent a 3D rotation as pair , with a real part "r" and a 3D vector ...
Definition: CQuaternion.h:44



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: c7a3bec24 Sun Mar 29 18:33:13 2020 +0200 at dom mar 29 18:50:38 CEST 2020