test_pcl_conversions.cpp
Go to the documentation of this file.
1 #include <string>
2 
3 #include "gtest/gtest.h"
4 
6 
7 namespace {
8 
9 class PCLConversionTests : public ::testing::Test {
10 protected:
11  virtual void SetUp() {
12  pcl_image.header.frame_id = "pcl";
13  pcl_image.height = 1;
14  pcl_image.width = 2;
15  pcl_image.step = 1;
16  pcl_image.is_bigendian = true;
17  pcl_image.encoding = "bgr8";
18  pcl_image.data.resize(2);
19  pcl_image.data[0] = 0x42;
20  pcl_image.data[1] = 0x43;
21 
22  pcl_pc2.header.frame_id = "pcl";
23  pcl_pc2.height = 1;
24  pcl_pc2.width = 2;
25  pcl_pc2.point_step = 1;
26  pcl_pc2.row_step = 1;
27  pcl_pc2.is_bigendian = true;
28  pcl_pc2.is_dense = true;
29  pcl_pc2.fields.resize(2);
30  pcl_pc2.fields[0].name = "XYZ";
31  pcl_pc2.fields[0].datatype = pcl::PCLPointField::INT8;
32  pcl_pc2.fields[0].count = 3;
33  pcl_pc2.fields[0].offset = 0;
34  pcl_pc2.fields[1].name = "RGB";
35  pcl_pc2.fields[1].datatype = pcl::PCLPointField::INT8;
36  pcl_pc2.fields[1].count = 3;
37  pcl_pc2.fields[1].offset = 8 * 3;
38  pcl_pc2.data.resize(2);
39  pcl_pc2.data[0] = 0x42;
40  pcl_pc2.data[1] = 0x43;
41  }
42 
43  pcl::PCLImage pcl_image;
44  sensor_msgs::Image image;
45 
46  pcl::PCLPointCloud2 pcl_pc2;
47  sensor_msgs::PointCloud2 pc2;
48 };
49 
50 template<class T>
51 void test_image(T &image) {
52  EXPECT_EQ(std::string("pcl"), image.header.frame_id);
53  EXPECT_EQ(1, image.height);
54  EXPECT_EQ(2, image.width);
55  EXPECT_EQ(1, image.step);
56  EXPECT_TRUE(image.is_bigendian);
57  EXPECT_EQ(std::string("bgr8"), image.encoding);
58  EXPECT_EQ(2, image.data.size());
59  EXPECT_EQ(0x42, image.data[0]);
60  EXPECT_EQ(0x43, image.data[1]);
61 }
62 
63 TEST_F(PCLConversionTests, imageConversion) {
64  pcl_conversions::fromPCL(pcl_image, image);
65  test_image(image);
66  pcl::PCLImage pcl_image2;
67  pcl_conversions::toPCL(image, pcl_image2);
68  test_image(pcl_image2);
69 }
70 
71 template<class T>
72 void test_pc(T &pc) {
73  EXPECT_EQ(std::string("pcl"), pc.header.frame_id);
74  EXPECT_EQ(1, pc.height);
75  EXPECT_EQ(2, pc.width);
76  EXPECT_EQ(1, pc.point_step);
77  EXPECT_EQ(1, pc.row_step);
78  EXPECT_TRUE(pc.is_bigendian);
79  EXPECT_TRUE(pc.is_dense);
80  EXPECT_EQ("XYZ", pc.fields[0].name);
81  EXPECT_EQ(pcl::PCLPointField::INT8, pc.fields[0].datatype);
82  EXPECT_EQ(3, pc.fields[0].count);
83  EXPECT_EQ(0, pc.fields[0].offset);
84  EXPECT_EQ("RGB", pc.fields[1].name);
85  EXPECT_EQ(pcl::PCLPointField::INT8, pc.fields[1].datatype);
86  EXPECT_EQ(3, pc.fields[1].count);
87  EXPECT_EQ(8 * 3, pc.fields[1].offset);
88  EXPECT_EQ(2, pc.data.size());
89  EXPECT_EQ(0x42, pc.data[0]);
90  EXPECT_EQ(0x43, pc.data[1]);
91 }
92 
93 TEST_F(PCLConversionTests, pointcloud2Conversion) {
94  pcl_conversions::fromPCL(pcl_pc2, pc2);
95  test_pc(pc2);
96  pcl::PCLPointCloud2 pcl_pc2_2;
97  pcl_conversions::toPCL(pc2, pcl_pc2_2);
98  test_pc(pcl_pc2_2);
99 }
100 
101 } // namespace
102 
103 
105 {
108 
109  explicit StampTestData(const ros::Time &stamp)
110  : stamp_(stamp)
111  {
112  pcl::uint64_t pcl_stamp;
113  pcl_conversions::toPCL(stamp_, pcl_stamp);
114  pcl_conversions::fromPCL(pcl_stamp, stamp2_);
115  }
116 };
117 
118 TEST(PCLConversionStamp, Stamps)
119 {
120  {
121  const StampTestData d(ros::Time(1.000001));
122  EXPECT_TRUE(d.stamp_==d.stamp2_);
123  }
124 
125  {
126  const StampTestData d(ros::Time(1.999999));
127  EXPECT_TRUE(d.stamp_==d.stamp2_);
128  }
129 
130  {
131  const StampTestData d(ros::Time(1.999));
132  EXPECT_TRUE(d.stamp_==d.stamp2_);
133  }
134 
135  {
136  const StampTestData d(ros::Time(1423680574, 746000000));
137  EXPECT_TRUE(d.stamp_==d.stamp2_);
138  }
139 
140  {
141  const StampTestData d(ros::Time(1423680629, 901000000));
142  EXPECT_TRUE(d.stamp_==d.stamp2_);
143  }
144 }
145 
146 int main(int argc, char **argv) {
147  try {
148  ::testing::InitGoogleTest(&argc, argv);
149  return RUN_ALL_TESTS();
150  } catch (std::exception &e) {
151  std::cerr << "Unhandled Exception: " << e.what() << std::endl;
152  }
153  return 1;
154 }
d
int main(int argc, char **argv)
void fromPCL(const pcl::uint64_t &pcl_stamp, ros::Time &stamp)
TEST(PCLConversionStamp, Stamps)
const ros::Time stamp_
StampTestData(const ros::Time &stamp)
TEST_F(XmlRpcTest, Introspection)
void toPCL(const ros::Time &stamp, pcl::uint64_t &pcl_stamp)


pcl_conversions
Author(s): William Woodall
autogenerated on Wed Jun 5 2019 20:24:15