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
00037
00038
00039
00040 #include <gtest/gtest.h>
00041
00042 #include <pcl/point_types.h>
00043 #include <pcl/io/pcd_io.h>
00044 #include <pcl/features/normal_3d.h>
00045 #include <pcl/visualization/pcl_visualizer.h>
00046
00047 using namespace pcl;
00048 using namespace pcl::io;
00049 using namespace pcl::visualization;
00050 using namespace std;
00051
00052 PointCloud<PointXYZ>::Ptr cloud (new PointCloud<PointXYZ>);
00053 PointCloud<PointNormal>::Ptr cloud_with_normals (new PointCloud<PointNormal>);
00054 search::KdTree<PointXYZ>::Ptr tree;
00055 search::KdTree<PointNormal>::Ptr tree2;
00056
00057
00058 PointCloud<PointXYZ>::Ptr cloud1 (new PointCloud<PointXYZ>);
00059 PointCloud<PointNormal>::Ptr cloud_with_normals1 (new PointCloud<PointNormal>);
00060 search::KdTree<PointXYZ>::Ptr tree3;
00061 search::KdTree<PointNormal>::Ptr tree4;
00062
00064 TEST (PCL, PCLVisualizer_camera)
00065 {
00066 PCLVisualizer visualizer;
00067 visualizer.initCameraParameters ();
00068
00069
00070 Eigen::Matrix3f given_intrinsics (Eigen::Matrix3f::Identity ());
00071 given_intrinsics (0, 0) = 525.f;
00072 given_intrinsics (1, 1) = 525.f;
00073 given_intrinsics (0, 2) = 320.f;
00074 given_intrinsics (1, 2) = 240.f;
00075
00076 float M_PIf = static_cast<float> (M_PI);
00077 Eigen::Matrix4f given_extrinsics (Eigen::Matrix4f::Identity ());
00078 given_extrinsics.block<3, 3> (0, 0) = Eigen::AngleAxisf (30.f * M_PIf / 180.f, Eigen::Vector3f (1.f, 0.f, 0.f)).matrix ();
00079 given_extrinsics.block<3, 1> (0, 3) = Eigen::Vector3f (10.f, 15.f, 20.f);
00080
00081 visualizer.setCameraParameters (given_intrinsics, given_extrinsics);
00082 Eigen::Matrix4f viewer_pose = visualizer.getViewerPose ().matrix ();
00083
00084 for (size_t i = 0; i < 4; ++i)
00085 for (size_t j = 0; j < 4; ++j)
00086 EXPECT_NEAR (given_extrinsics (i, j), viewer_pose (i, j), 1e-6);
00087
00088
00089
00090
00091 Eigen::Vector3f trans (10.f, 2.f, 20.f);
00092 visualizer.setCameraPosition (trans[0], trans[1], trans[2], trans[0] + 1., trans[1], trans[2], 0., 1., 0.);
00093 viewer_pose = visualizer.getViewerPose ().matrix ();
00094 Eigen::Matrix3f expected_rotation = Eigen::AngleAxisf (M_PIf / 2.0f, Eigen::Vector3f (0.f, 1.f, 0.f)).matrix ();
00095 for (size_t i = 0; i < 3; ++i)
00096 for (size_t j = 0; j < 3; ++j)
00097 EXPECT_NEAR (viewer_pose (i, j), expected_rotation (i, j), 1e-6);
00098 for (size_t i = 0; i < 3; ++i)
00099 EXPECT_NEAR (viewer_pose (i, 3), trans[i], 1e-6);
00100
00101
00102
00103
00105
00106
00107
00108
00109
00110
00111 }
00112
00113
00114
00115
00116
00117 int
00118 main (int argc, char** argv)
00119 {
00120 if (argc < 2)
00121 {
00122 std::cerr << "No test file given. Please download `bunny.pcd` and pass its path to the test." << std::endl;
00123 return (-1);
00124 }
00125
00126
00127 pcl::PCLPointCloud2 cloud_blob;
00128 loadPCDFile (argv[1], cloud_blob);
00129 fromPCLPointCloud2 (cloud_blob, *cloud);
00130
00131
00132 tree.reset (new search::KdTree<PointXYZ> (false));
00133 tree->setInputCloud (cloud);
00134
00135
00136 NormalEstimation<PointXYZ, Normal> n;
00137 PointCloud<Normal>::Ptr normals (new PointCloud<Normal> ());
00138 n.setInputCloud (cloud);
00139
00140 n.setSearchMethod (tree);
00141 n.setKSearch (20);
00142 n.compute (*normals);
00143
00144
00145 pcl::concatenateFields (*cloud, *normals, *cloud_with_normals);
00146
00147
00148 tree2.reset (new search::KdTree<PointNormal>);
00149 tree2->setInputCloud (cloud_with_normals);
00150
00151
00152 if (argc == 3)
00153 {
00154 pcl::PCLPointCloud2 cloud_blob1;
00155 loadPCDFile (argv[2], cloud_blob1);
00156 fromPCLPointCloud2 (cloud_blob1, *cloud1);
00157
00158 tree3.reset (new search::KdTree<PointXYZ> (false));
00159 tree3->setInputCloud (cloud1);
00160
00161
00162 NormalEstimation<PointXYZ, Normal> n1;
00163 PointCloud<Normal>::Ptr normals1 (new PointCloud<Normal> ());
00164 n1.setInputCloud (cloud1);
00165
00166 n1.setSearchMethod (tree3);
00167 n1.setKSearch (20);
00168 n1.compute (*normals1);
00169
00170
00171 pcl::concatenateFields (*cloud1, *normals1, *cloud_with_normals1);
00172
00173 tree4.reset (new search::KdTree<PointNormal>);
00174 tree4->setInputCloud (cloud_with_normals1);
00175 }
00176
00177
00178 testing::InitGoogleTest (&argc, argv);
00179 return (RUN_ALL_TESTS ());
00180 }
00181