10 #include <mrpt/version.h> 11 #include <mrpt/maps/CSimplePointsMap.h> 12 #include <pcl/conversions.h> 13 #include <pcl/point_cloud.h> 15 #include <gtest/gtest.h> 19 pcl::PointCloud<pcl::PointXYZ> point_cloud;
21 point_cloud.height = 10;
22 point_cloud.width = 10;
23 point_cloud.is_dense =
true;
25 int num_points = point_cloud.height * point_cloud.width;
26 point_cloud.points.resize(num_points);
29 for (
int i = 0; i < num_points; i++)
31 pcl::PointXYZ& point = point_cloud.points[i];
42 mrpt::maps::CSimplePointsMap mrpt_pc;
48 for (
int i = 0; i < num_points; i++)
50 float mrpt_x, mrpt_y, mrpt_z;
51 mrpt_pc.getPoint(i, mrpt_x, mrpt_y, mrpt_z);
52 EXPECT_FLOAT_EQ(mrpt_x, i_f);
53 EXPECT_FLOAT_EQ(mrpt_y, -i_f);
54 EXPECT_FLOAT_EQ(mrpt_z, -2 * i_f);
PointCloud2_< std::allocator< void > > PointCloud2
bool copy(const sensor_msgs::PointCloud2 &msg, mrpt::maps::CSimplePointsMap &obj)
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
TEST(PointCloud2, basicTest)