point_cloud.cpp
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 
11 #include <ros/console.h>
12 
13 using namespace mrpt::maps;
14 
15 namespace mrpt_bridge
16 {
22  const sensor_msgs::PointCloud& msg, CSimplePointsMap& obj)
23 {
24  const size_t N = msg.points.size();
25 
26  obj.clear();
27  obj.reserve(N);
28  for (size_t i = 0; i < N; i++)
29  obj.insertPoint(msg.points[i].x, msg.points[i].y, msg.points[i].z);
30 
31  return true;
32 }
33 
43  const CSimplePointsMap& obj, const std_msgs::Header& msg_header,
44  sensor_msgs::PointCloud& msg)
45 {
46  // 1) sensor_msgs::PointCloud:: header
47  msg.header = msg_header;
48 
49  // 2) sensor_msgs::PointCloud:: points
50  const size_t N = obj.size();
51  msg.points.resize(N);
52  for (size_t i = 0; i < N; i++)
53  {
54  geometry_msgs::Point32& pt = msg.points[i];
55  obj.getPoint(i, pt.x, pt.y, pt.z);
56  }
57 
58  // 3) sensor_msgs::PointCloud:: channels
59  msg.channels.clear();
60 
61  return true;
62 }
63 
64 } // namespace mrpt_bridge
mrpt_bridge::GPS::mrpt2ros
bool mrpt2ros(const CObservationGPS &obj, const std_msgs::Header &msg_header, sensor_msgs::NavSatFix &msg)
Definition: GPS.cpp:54
point_cloud.h
console.h
std_msgs::Header_
Definition: map.h:24
mrpt_bridge
File includes methods for converting CNetworkOfPoses*DInf <=> NetworkOfPoses message types.
Definition: include/mrpt_bridge/beacon.h:52
mrpt::maps
Definition: map.h:38
mrpt_bridge::GPS::ros2mrpt
bool ros2mrpt(const sensor_msgs::NavSatFix &msg, CObservationGPS &obj)
Definition: GPS.cpp:23


mrpt_bridge
Author(s): Markus Bader , Raphael Zack
autogenerated on Sun Mar 6 2022 03:48:10