utest.h
Go to the documentation of this file.
00001 #ifndef UTEST_HPP_
00002 #define UTEST_HPP_
00003 
00004 #include "pointmatcher/PointMatcher.h"
00005 #include "pointmatcher/IO.h"
00006 #include "../contrib/gtest/gtest.h"
00007 
00008 #include <string>
00009 #include <fstream>
00010 
00011 #include "boost/filesystem.hpp"
00012 #include "boost/filesystem/path.hpp"
00013 #include "boost/filesystem/operations.hpp"
00014 
00015 typedef PointMatcher<float> PM;
00016 typedef PM::DataPoints DP;
00017 
00018 extern std::string dataPath;
00019 
00020 extern DP ref2D;
00021 extern DP data2D;
00022 extern DP ref3D;
00023 extern DP data3D;
00024 extern PM::TransformationParameters validT2d;
00025 extern PM::TransformationParameters validT3d;
00026 
00027 //---------------------------
00028 // Base for ICP tests
00029 //---------------------------
00030 
00031 class IcpHelper: public testing::Test
00032 {
00033 public:
00034         
00035         PM::ICP icp;
00036         
00037         PM::Parameters params;
00038 
00039         virtual void dumpVTK()
00040         {
00041                 // Make available a VTK inspector for manual inspection
00042                 icp.inspector =
00043                         PM::get().InspectorRegistrar.create(
00044                                 "VTKFileInspector", 
00045                                 {{"baseFileName", "./unitTest"}}
00046                         );
00047         }
00048         
00049         void validate2dTransformation()
00050         {
00051                 const PM::TransformationParameters testT = icp(data2D, ref2D);
00052                 const int dim = validT2d.cols();
00053 
00054                 const BOOST_AUTO(validTrans, validT2d.block(0, dim-1, dim-1, 1).norm());
00055                 const BOOST_AUTO(testTrans, testT.block(0, dim-1, dim-1, 1).norm());
00056         
00057                 const BOOST_AUTO(validAngle, acos(validT2d(0,0)));
00058                 const BOOST_AUTO(testAngle, acos(testT(0,0)));
00059                 
00060                 EXPECT_NEAR(validTrans, testTrans, 0.05);
00061                 EXPECT_NEAR(validAngle, testAngle, 0.05);
00062         }
00063 
00064         void validate3dTransformation()
00065         {
00066                 //dumpVTK();
00067 
00068                 const PM::TransformationParameters testT = icp(data3D, ref3D);
00069                 const int dim = validT2d.cols();
00070 
00071                 const BOOST_AUTO(validTrans, validT3d.block(0, dim-1, dim-1, 1).norm());
00072                 const BOOST_AUTO(testTrans, testT.block(0, dim-1, dim-1, 1).norm());
00073         
00074                 const BOOST_AUTO(testRotation, Eigen::Quaternion<float>(Eigen::Matrix<float,3,3>(testT.topLeftCorner(3,3))));
00075                 const BOOST_AUTO(validRotation, Eigen::Quaternion<float>(Eigen::Matrix<float,3,3>(validT3d.topLeftCorner(3,3))));
00076                 
00077                 const BOOST_AUTO(angleDist, validRotation.angularDistance(testRotation));
00078                 
00079                 //cout << testT << endl;
00080                 //cout << "angleDist: " << angleDist << endl;
00081                 //cout << "transDist: " << abs(validTrans-testTrans) << endl;
00082                 EXPECT_NEAR(validTrans, testTrans, 0.1);
00083                 EXPECT_NEAR(angleDist, 0.0, 0.1);
00084 
00085         }
00086 };
00087 
00088 #endif /* UTEST_HPP_ */
00089 
00090 


libpointmatcher
Author(s):
autogenerated on Thu Jun 20 2019 19:51:32