Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00039 #include <gtest/gtest.h>
00040 #include <pcl/point_types.h>
00041 #include <sensor_msgs/PointCloud2.h>
00042 #include <pcl_ros/io/bag_io.h>
00043 #include <pcl/ros/conversions.h>
00044
00045 using namespace pcl;
00046 using namespace pcl_ros;
00047
00049 TEST (PCL_ROS, BAGReader)
00050 {
00051 sensor_msgs::PointCloud2ConstPtr cloud_blob, cloud_blob_prev;
00052 PointCloud<PointXYZRGB> cloud;
00053
00054 BAGReader reader;
00055 bool res = reader.open ("test_io_bag.bag", "/narrow_stereo_textured/points2");
00056 EXPECT_EQ ((bool)res, true);
00057 int cnt = 0;
00058 do
00059 {
00060 cloud_blob_prev = cloud_blob;
00061 cloud_blob = reader.getNextCloud ();
00062 if (cloud_blob_prev != cloud_blob)
00063 {
00064 EXPECT_EQ ((int)cloud_blob->width, 640);
00065 EXPECT_EQ ((int)cloud_blob->height, 480);
00066 EXPECT_EQ ((bool)cloud_blob->is_dense, true);
00067 EXPECT_EQ ((size_t)cloud_blob->data.size () * 2,
00068 cloud_blob->width * cloud_blob->height * sizeof (PointXYZRGB));
00069 cnt++;
00070 }
00071 }
00072 while (cloud_blob != cloud_blob_prev);
00073
00074 EXPECT_EQ (cnt, 4);
00075
00076
00077 pcl::fromROSMsg (*cloud_blob, cloud);
00078
00079 EXPECT_NEAR ((float)cloud.points[12345].x, -0.157809, 1e-5);
00080 EXPECT_NEAR ((float)cloud.points[12345].y, -0.239234, 1e-5);
00081 EXPECT_NEAR ((float)cloud.points[12345].z, 1.1289, 1e-5);
00082 }
00083
00084
00085 int
00086 main (int argc, char** argv)
00087 {
00088 testing::InitGoogleTest (&argc, argv);
00089 return (RUN_ALL_TESTS ());
00090 }
00091