MRPT  2.0.4
point_cloud.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 
14 #include <sensor_msgs/PointCloud.h>
15 
16 namespace mrpt::ros1bridge
17 {
18 /** \addtogroup mrpt_ros1bridge_grp
19  * @{ */
20 
21 /** @name Point clouds: ROS <-> MRPT
22  * @{ */
23 
24 /** Convert sensor_msgs/PointCloud -> mrpt::maps::CSimplePointsMap
25  * CSimplePointsMap only contains (x,y,z) data, so
26  * sensor_msgs::PointCloud::channels are ignored.
27  * \return true on sucessful conversion, false on any error.
28  * \sa toROS
29  */
30 bool fromROS(
31  const sensor_msgs::PointCloud& msg, mrpt::maps::CSimplePointsMap& obj);
32 
33 /** Convert mrpt::maps::CSimplePointsMap -> sensor_msgs/PointCloud
34  * The user must supply the "msg_header" field to be copied into the output
35  * message object, since that part does not appear in MRPT classes.
36  *
37  * Since CSimplePointsMap only contains (x,y,z) data,
38  * sensor_msgs::PointCloud::channels will be empty.
39  * \return true on sucessful conversion, false on any error.
40  * \sa fromROS
41  */
42 bool toROS(
43  const mrpt::maps::CSimplePointsMap& obj, const std_msgs::Header& msg_header,
44  sensor_msgs::PointCloud& msg);
45 
46 /** @} @}
47  */
48 
49 } // namespace mrpt::ros1bridge
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans. ...
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
bool fromROS(const sensor_msgs::NavSatFix &msg, mrpt::obs::CObservationGPS &obj)
Convert sensor_msgs/NavSatFix -> mrpt::obs::CObservationGPS.
Definition: gps.cpp:20



Page generated by Doxygen 1.8.14 for MRPT 2.0.4 Git: 33de1d0ad Sat Jun 20 11:02:42 2020 +0200 at sáb jun 20 17:35:17 CEST 2020