test_pcl_conversions.cpp
Go to the documentation of this file.
00001 #include <string>
00002 
00003 #include "gtest/gtest.h"
00004 
00005 #include "pcl_conversions/pcl_conversions.h"
00006 
00007 namespace {
00008 
00009 class PCLConversionTests : public ::testing::Test {
00010 protected:
00011   virtual void SetUp() {
00012     pcl_image.header.frame_id = "pcl";
00013     pcl_image.height = 1;
00014     pcl_image.width = 2;
00015     pcl_image.step = 1;
00016     pcl_image.is_bigendian = true;
00017     pcl_image.encoding = "bgr8";
00018     pcl_image.data.resize(2);
00019     pcl_image.data[0] = 0x42;
00020     pcl_image.data[1] = 0x43;
00021 
00022     pcl_pc2.header.frame_id = "pcl";
00023     pcl_pc2.height = 1;
00024     pcl_pc2.width = 2;
00025     pcl_pc2.point_step = 1;
00026     pcl_pc2.row_step = 1;
00027     pcl_pc2.is_bigendian = true;
00028     pcl_pc2.is_dense = true;
00029     pcl_pc2.fields.resize(2);
00030     pcl_pc2.fields[0].name = "XYZ";
00031     pcl_pc2.fields[0].datatype = sensor_msgs::PointField::INT8;
00032     pcl_pc2.fields[0].count = 3;
00033     pcl_pc2.fields[0].offset = 0;
00034     pcl_pc2.fields[1].name = "RGB";
00035     pcl_pc2.fields[1].datatype = sensor_msgs::PointField::INT8;
00036     pcl_pc2.fields[1].count = 3;
00037     pcl_pc2.fields[1].offset = 8 * 3;
00038     pcl_pc2.data.resize(2);
00039     pcl_pc2.data[0] = 0x42;
00040     pcl_pc2.data[1] = 0x43;
00041   }
00042 
00043   sensor_msgs::Image pcl_image;
00044   sensor_msgs::Image image;
00045 
00046   sensor_msgs::PointCloud2 pcl_pc2;
00047   sensor_msgs::PointCloud2 pc2;
00048 };
00049 
00050 template<class T>
00051 void test_image(T &image) {
00052   EXPECT_EQ(std::string("pcl"), image.header.frame_id);
00053   EXPECT_EQ(1, image.height);
00054   EXPECT_EQ(2, image.width);
00055   EXPECT_EQ(1, image.step);
00056   EXPECT_TRUE(image.is_bigendian);
00057   EXPECT_EQ(std::string("bgr8"), image.encoding);
00058   EXPECT_EQ(2, image.data.size());
00059   EXPECT_EQ(0x42, image.data[0]);
00060   EXPECT_EQ(0x43, image.data[1]);
00061 }
00062 
00063 TEST_F(PCLConversionTests, imageConversion) {
00064   pcl_conversions::fromPCL(pcl_image, image);
00065   test_image(image);
00066   sensor_msgs::Image pcl_image2;
00067   pcl_conversions::toPCL(image, pcl_image2);
00068   test_image(pcl_image2);
00069 }
00070 
00071 template<class T>
00072 void test_pc(T &pc) {
00073   EXPECT_EQ(std::string("pcl"), pc.header.frame_id);
00074   EXPECT_EQ(1, pc.height);
00075   EXPECT_EQ(2, pc.width);
00076   EXPECT_EQ(1, pc.point_step);
00077   EXPECT_EQ(1, pc.row_step);
00078   EXPECT_TRUE(pc.is_bigendian);
00079   EXPECT_TRUE(pc.is_dense);
00080   EXPECT_EQ("XYZ", pc.fields[0].name);
00081   EXPECT_EQ(sensor_msgs::PointField::INT8, pc.fields[0].datatype);
00082   EXPECT_EQ(3, pc.fields[0].count);
00083   EXPECT_EQ(0, pc.fields[0].offset);
00084   EXPECT_EQ("RGB", pc.fields[1].name);
00085   EXPECT_EQ(sensor_msgs::PointField::INT8, pc.fields[1].datatype);
00086   EXPECT_EQ(3, pc.fields[1].count);
00087   EXPECT_EQ(8 * 3, pc.fields[1].offset);
00088   EXPECT_EQ(2, pc.data.size());
00089   EXPECT_EQ(0x42, pc.data[0]);
00090   EXPECT_EQ(0x43, pc.data[1]);
00091 }
00092 
00093 TEST_F(PCLConversionTests, pointcloud2Conversion) {
00094   pcl_conversions::fromPCL(pcl_pc2, pc2);
00095   test_pc(pc2);
00096   sensor_msgs::PointCloud2 pcl_pc2_2;
00097   pcl_conversions::toPCL(pc2, pcl_pc2_2);
00098   test_pc(pcl_pc2_2);
00099 }
00100 
00101 } // namespace
00102 
00103 int main(int argc, char **argv) {
00104   try {
00105     ::testing::InitGoogleTest(&argc, argv);
00106     return RUN_ALL_TESTS();
00107   } catch (std::exception &e) {
00108     std::cerr << "Unhandled Exception: " << e.what() << std::endl;
00109   }
00110   return 1;
00111 }


pcl_conversions
Author(s): William Woodall
autogenerated on Mon Oct 6 2014 03:14:55