MRPT  2.0.2
point_cloud2.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 
16 #include <sensor_msgs/PointCloud2.h>
17 #include <set>
18 #include <string>
19 
20 namespace mrpt::ros1bridge
21 {
22 /** \addtogroup mrpt_ros1bridge_grp
23  * @{ */
24 
25 /** @name sensor_msgs::PointCloud2: ROS <-> MRPT
26  * @{ */
27 
28 /** Convert sensor_msgs/PointCloud2 -> mrpt::slam::CSimplePointsMap
29  * Only (x,y,z) data is converted. To use the intensity channel, see
30  * the alternative signature for CPointsMapXYZI.
31  * Requires point cloud fields: x,y,z.
32  * \return true on sucessful conversion, false on any error.
33  * \sa toROS
34  */
35 bool fromROS(
36  const sensor_msgs::PointCloud2& msg, mrpt::maps::CSimplePointsMap& obj);
37 
38 /** \overload For (x,y,z,intensity) channels.
39  * Requires point cloud fields: x,y,z,intensity
40  */
41 bool fromROS(
42  const sensor_msgs::PointCloud2& msg, mrpt::maps::CPointsMapXYZI& obj);
43 
44 /** Convert sensor_msgs/PointCloud2 -> mrpt::obs::CObservationRotatingScan.
45  * Requires point cloud fields: x,y,z,intensity,ring
46  */
47 bool fromROS(
48  const sensor_msgs::PointCloud2& m, mrpt::obs::CObservationRotatingScan& o,
49  const mrpt::poses::CPose3D& sensorPoseOnRobot,
50  unsigned int num_azimuth_divisions = 360);
51 
52 /** Extract a list of fields found in the point cloud.
53  * Typically: {"x","y","z","intensity"}
54  */
55 std::set<std::string> extractFields(const sensor_msgs::PointCloud2& msg);
56 
57 /** Convert mrpt::slam::CSimplePointsMap -> sensor_msgs/PointCloud2
58  * The user must supply the "msg_header" field to be copied into the output
59  * message object, since that part does not appear in MRPT classes.
60  *
61  * Since CSimplePointsMap only contains (x,y,z) data,
62  * sensor_msgs::PointCloud2::channels will be empty.
63  * \return true on sucessful conversion, false on any error.
64  * \sa fromROS
65  */
66 bool toROS(
67  const mrpt::maps::CSimplePointsMap& obj, const std_msgs::Header& msg_header,
68  sensor_msgs::PointCloud2& msg);
69 
70 /** @} */
71 /** @} */
72 
73 } // namespace mrpt::ros1bridge
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans. ...
std::set< std::string > extractFields(const sensor_msgs::PointCloud2 &msg)
Extract a list of fields found in the point cloud.
A map of 3D points with reflectance/intensity (float).
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
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
A CObservation-derived class for raw range data from a 2D or 3D rotating scanner. ...



Page generated by Doxygen 1.8.14 for MRPT 2.0.2 Git: 9b4fd2465 Mon May 4 16:59:08 2020 +0200 at lun may 4 17:26:07 CEST 2020