point_cloud.cpp
Go to the documentation of this file.
1 
3 #include <ros/console.h>
4 
5 namespace mrpt_bridge
6 {
12  const sensor_msgs::PointCloud& msg, CSimplePointsMap& obj)
13 {
14  const size_t N = msg.points.size();
15 
16  obj.clear();
17  obj.reserve(N);
18  for (size_t i = 0; i < N; i++)
19  obj.insertPoint(msg.points[i].x, msg.points[i].y, msg.points[i].z);
20 
21  return true;
22 }
23 
33  const CSimplePointsMap& obj, const std_msgs::Header& msg_header,
34  sensor_msgs::PointCloud& msg)
35 {
36  // 1) sensor_msgs::PointCloud:: header
37  msg.header = msg_header;
38 
39  // 2) sensor_msgs::PointCloud:: points
40  const size_t N = obj.size();
41  msg.points.resize(N);
42  for (size_t i = 0; i < N; i++)
43  {
44  geometry_msgs::Point32& pt = msg.points[i];
45  obj.getPoint(i, pt.x, pt.y, pt.z);
46  }
47 
48  // 3) sensor_msgs::PointCloud:: channels
49  msg.channels.clear();
50 
51  return true;
52 }
53 
54 } // namespace mrpt_bridge
File includes methods for converting CNetworkOfPoses*DInf <=> NetworkOfPoses message types...
bool mrpt2ros(const CSimplePointsMap &obj, const std_msgs::Header &msg_header, sensor_msgs::PointCloud &msg)
Definition: point_cloud.cpp:32
bool ros2mrpt(const sensor_msgs::PointCloud &msg, CSimplePointsMap &obj)
Definition: point_cloud.cpp:11


mrpt_bridge
Author(s): Markus Bader , Raphael Zack
autogenerated on Sat Apr 28 2018 02:49:17