MRPT  1.9.9
pointcloud2_unittest.cpp
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 /*
11  * test_pose_conversions.cpp
12  *
13  * Created on: Mar 15, 2012
14  * Author: Pablo IƱigo Blasco
15  */
16 
17 #include <gtest/gtest.h>
20 
21 #if MRPT_HAVE_PCL_CONVERSIONS
22 #include <pcl/common/common_headers.h>
23 #include <pcl/conversions.h>
24 #include <pcl/point_cloud.h>
25 #include <pcl_conversions/pcl_conversions.h>
26 
27 TEST(PointCloud2, basicTest)
28 {
29  pcl::PointCloud<pcl::PointXYZ> point_cloud;
30 
31  point_cloud.height = 10;
32  point_cloud.width = 10;
33  point_cloud.is_dense = true;
34 
35  int num_points = point_cloud.height * point_cloud.width;
36  point_cloud.points.resize(num_points);
37 
38  float i_f = 0;
39  for (int i = 0; i < num_points; i++)
40  {
41  pcl::PointXYZ& point = point_cloud.points[i];
42  point.x = i_f;
43  point.y = -i_f;
44  point.z = -2 * i_f;
45  i_f += 1.0;
46  }
47 
48  sensor_msgs::PointCloud2 point_cloud2_msg;
49  pcl::toROSMsg(point_cloud, point_cloud2_msg);
50 
52 
53  mrpt::ros1bridge::fromROS(point_cloud2_msg, mrpt_pc);
54 
55  i_f = 0;
56  for (int i = 0; i < num_points; i++)
57  {
58  float mrpt_x, mrpt_y, mrpt_z;
59  mrpt_pc.getPoint(i, mrpt_x, mrpt_y, mrpt_z);
60  EXPECT_FLOAT_EQ(mrpt_x, i_f);
61  EXPECT_FLOAT_EQ(mrpt_y, -i_f);
62  EXPECT_FLOAT_EQ(mrpt_z, -2 * i_f);
63 
64  i_f += 1.0;
65  }
66  //;
67 }
68 
69 #endif
void getPoint(size_t index, float &x, float &y, float &z) const
Access to a given point from map, as a 2D point.
Definition: CPointsMap.cpp:192
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans. ...
TEST(ICP_SLAM_App, MapFromRawlog_PointMap)
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 1.9.9 Git: c7a3bec24 Sun Mar 29 18:33:13 2020 +0200 at dom mar 29 18:50:38 CEST 2020