12 const sensor_msgs::PointCloud& msg, CSimplePointsMap& obj)
14 const size_t N = msg.points.size();
18 for (
size_t i = 0; i < N; i++)
19 obj.insertPoint(msg.points[i].x, msg.points[i].y, msg.points[i].z);
34 sensor_msgs::PointCloud& msg)
37 msg.header = msg_header;
40 const size_t N = obj.size();
42 for (
size_t i = 0; i < N; i++)
44 geometry_msgs::Point32& pt = msg.points[i];
45 obj.getPoint(i, pt.x, pt.y, pt.z);
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)
bool ros2mrpt(const sensor_msgs::PointCloud &msg, CSimplePointsMap &obj)