test_pointcloud2.cpp
Go to the documentation of this file.
1 /*
2  * test_pose_conversions.cpp
3  *
4  * Created on: Mar 15, 2012
5  * Author: Pablo IƱigo Blasco
6  */
7 
8 #include <mrpt/ros1bridge/point_cloud2.h>
9 #include <mrpt/maps/CSimplePointsMap.h>
10 #include <pcl/conversions.h>
11 #include <pcl/point_cloud.h>
13 #include <gtest/gtest.h>
14 
15 TEST(PointCloud2, basicTest)
16 {
17  pcl::PointCloud<pcl::PointXYZ> point_cloud;
18 
19  point_cloud.height = 10;
20  point_cloud.width = 10;
21  point_cloud.is_dense = true;
22 
23  int num_points = point_cloud.height * point_cloud.width;
24  point_cloud.points.resize(num_points);
25 
26  float i_f = 0;
27  for (int i = 0; i < num_points; i++)
28  {
29  pcl::PointXYZ& point = point_cloud.points[i];
30  point.x = i_f;
31  point.y = -i_f;
32  point.z = -2 * i_f;
33  i_f += 1.0;
34  }
35 
36  sensor_msgs::PointCloud2 point_cloud2_msg;
37  // pcl_conversions::fromPCL(point_cloud, point_cloud2_msg);
38  pcl::toROSMsg(point_cloud, point_cloud2_msg);
39 
40  mrpt::maps::CSimplePointsMap mrpt_pc;
41 
42  // printf("step 3\n");
43  mrpt::ros1bridge::fromROS(point_cloud2_msg, mrpt_pc);
44 
45  i_f = 0;
46  for (int i = 0; i < num_points; i++)
47  {
48  float mrpt_x, mrpt_y, mrpt_z;
49  mrpt_pc.getPoint(i, mrpt_x, mrpt_y, mrpt_z);
50  EXPECT_FLOAT_EQ(mrpt_x, i_f);
51  EXPECT_FLOAT_EQ(mrpt_y, -i_f);
52  EXPECT_FLOAT_EQ(mrpt_z, -2 * i_f);
53 
54  i_f += 1.0;
55  }
56  //;
57 }
#define EXPECT_FLOAT_EQ(a, b)
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
TEST(PointCloud2, basicTest)


mrpt_bridge
Author(s): Markus Bader , Raphael Zack
autogenerated on Thu May 12 2022 02:26:47