#include <gtest/gtest.h>#include <vector>#include <cstdio>#include <iostream>#include <pcl/common/time.h>#include <pcl/console/print.h>#include <pcl/point_cloud.h>#include <pcl/point_types.h>#include <pcl/outofcore/outofcore.h>#include <pcl/outofcore/outofcore_impl.h>#include <pcl/PCLPointCloud2.h>#include <boost/random/mersenne_twister.hpp>#include <boost/random/uniform_real.hpp>#include <boost/random/normal_distribution.hpp>#include <boost/foreach.hpp>
Go to the source code of this file.
Classes | |
| class | OutofcoreTest |
Typedefs | |
| typedef std::vector< PointT, Eigen::aligned_allocator < PointT > > | AlignedPointTVector |
| typedef OutofcoreOctreeBase < OutofcoreOctreeDiskContainer < PointT >, PointT > | octree_disk |
| typedef OutofcoreOctreeBaseNode < OutofcoreOctreeDiskContainer < PointT >, PointT > | octree_disk_node |
| typedef OutofcoreOctreeBase < OutofcoreOctreeRamContainer < PointT >, PointT > | octree_ram |
| typedef OutofcoreOctreeBaseNode < OutofcoreOctreeRamContainer < PointT >, PointT > | octree_ram_node |
| typedef pcl::PointXYZ | PointT |
Functions | |
| bool | compPt (const PointT &p1, const PointT &p2) |
| helper function to compare two points. is there a templated function in pcl to do this for arbitrary point types? | |
| int | main (int argc, char **argv) |
| static const uint64_t | numPts (10000) |
| Unit tests for UR out of core octree code which test public interface of OutofcoreOctreeBase. | |
| static const boost::filesystem::path | outofcore_path ("point_cloud_octree/tree_test.oct_idx") |
| void | point_test (octree_disk &t) |
| TEST (PCL, Outofcore_Octree_Build) | |
| TEST (PCL, Outofcore_Octree_Build_LOD) | |
| TEST (PCL, Outofcore_Bounding_Box) | |
| TEST (PCL, Outofcore_Point_Query) | |
| TEST_F (OutofcoreTest, Outofcore_Constructors) | |
| Thorough test of the constructors, including exceptions and specified behavior. | |
| TEST_F (OutofcoreTest, Outofcore_ConstructorSafety) | |
| TEST_F (OutofcoreTest, Outofcore_ConstructorBadPaths) | |
| TEST_F (OutofcoreTest, Outofcore_PointcloudConstructor) | |
| TEST_F (OutofcoreTest, Outofcore_PointsOnBoundaries) | |
| TEST_F (OutofcoreTest, Outofcore_MultiplePointClouds) | |
| TEST_F (OutofcoreTest, Outofcore_PointCloudInput_LOD) | |
| TEST_F (OutofcoreTest, PointCloud2_Constructors) | |
| TEST_F (OutofcoreTest, PointCloud2_Insertion) | |
| TEST_F (OutofcoreTest, PointCloud2_MultiplePointCloud) | |
| TEST_F (OutofcoreTest, PointCloud2_QueryBoundingBox) | |
| TEST_F (OutofcoreTest, PointCloud2_Query) | |
Variables | |
| static const boost::filesystem::path | filename_otreeA = "treeA/tree_test.oct_idx" |
| static const boost::filesystem::path | filename_otreeA_LOD = "treeA_LOD/tree_test.oct_idx" |
| static const boost::filesystem::path | filename_otreeB = "treeB/tree_test.oct_idx" |
| static const boost::filesystem::path | filename_otreeB_LOD = "treeB_LOD/tree_test.oct_idx" |
| AlignedPointTVector | points |
| static const boost::uint32_t | rngseed = 0xAAFF33DD |
| typedef std::vector<PointT, Eigen::aligned_allocator<PointT> > AlignedPointTVector |
Definition at line 99 of file test_outofcore.cpp.
| typedef OutofcoreOctreeBase<OutofcoreOctreeDiskContainer < PointT > , PointT > octree_disk |
Definition at line 93 of file test_outofcore.cpp.
| typedef OutofcoreOctreeBaseNode<OutofcoreOctreeDiskContainer < PointT > , PointT > octree_disk_node |
Definition at line 94 of file test_outofcore.cpp.
| typedef OutofcoreOctreeBase<OutofcoreOctreeRamContainer< PointT> , PointT> octree_ram |
Definition at line 96 of file test_outofcore.cpp.
Definition at line 97 of file test_outofcore.cpp.
| typedef pcl::PointXYZ PointT |
Definition at line 90 of file test_outofcore.cpp.
helper function to compare two points. is there a templated function in pcl to do this for arbitrary point types?
Definition at line 106 of file test_outofcore.cpp.
| int main | ( | int | argc, |
| char ** | argv | ||
| ) |
Definition at line 956 of file test_outofcore.cpp.
| static const uint64_t numPts | ( | 10000 | ) | [static] |
Unit tests for UR out of core octree code which test public interface of OutofcoreOctreeBase.
| static const boost::filesystem::path outofcore_path | ( | "point_cloud_octree/tree_test.oct_idx" | ) | [static] |
| void point_test | ( | octree_disk & | t | ) |
Definition at line 251 of file test_outofcore.cpp.
| TEST | ( | PCL | , |
| Outofcore_Octree_Build | |||
| ) |
Definition at line 114 of file test_outofcore.cpp.
| TEST | ( | PCL | , |
| Outofcore_Octree_Build_LOD | |||
| ) |
Definition at line 167 of file test_outofcore.cpp.
| TEST | ( | PCL | , |
| Outofcore_Bounding_Box | |||
| ) |
Definition at line 216 of file test_outofcore.cpp.
| TEST | ( | PCL | , |
| Outofcore_Point_Query | |||
| ) |
Definition at line 313 of file test_outofcore.cpp.
| TEST_F | ( | OutofcoreTest | , |
| Outofcore_Constructors | |||
| ) |
Thorough test of the constructors, including exceptions and specified behavior.
Definition at line 439 of file test_outofcore.cpp.
| TEST_F | ( | OutofcoreTest | , |
| Outofcore_ConstructorSafety | |||
| ) |
Definition at line 477 of file test_outofcore.cpp.
| TEST_F | ( | OutofcoreTest | , |
| Outofcore_ConstructorBadPaths | |||
| ) |
Definition at line 500 of file test_outofcore.cpp.
| TEST_F | ( | OutofcoreTest | , |
| Outofcore_PointcloudConstructor | |||
| ) |
Definition at line 516 of file test_outofcore.cpp.
| TEST_F | ( | OutofcoreTest | , |
| Outofcore_PointsOnBoundaries | |||
| ) |
Definition at line 553 of file test_outofcore.cpp.
| TEST_F | ( | OutofcoreTest | , |
| Outofcore_MultiplePointClouds | |||
| ) |
Definition at line 596 of file test_outofcore.cpp.
| TEST_F | ( | OutofcoreTest | , |
| Outofcore_PointCloudInput_LOD | |||
| ) |
Definition at line 659 of file test_outofcore.cpp.
| TEST_F | ( | OutofcoreTest | , |
| PointCloud2_Constructors | |||
| ) |
Definition at line 708 of file test_outofcore.cpp.
| TEST_F | ( | OutofcoreTest | , |
| PointCloud2_Insertion | |||
| ) |
Definition at line 747 of file test_outofcore.cpp.
| TEST_F | ( | OutofcoreTest | , |
| PointCloud2_MultiplePointCloud | |||
| ) |
Definition at line 778 of file test_outofcore.cpp.
| TEST_F | ( | OutofcoreTest | , |
| PointCloud2_QueryBoundingBox | |||
| ) |
Definition at line 839 of file test_outofcore.cpp.
| TEST_F | ( | OutofcoreTest | , |
| PointCloud2_Query | |||
| ) |
Definition at line 890 of file test_outofcore.cpp.
const boost::filesystem::path filename_otreeA = "treeA/tree_test.oct_idx" [static] |
Definition at line 81 of file test_outofcore.cpp.
const boost::filesystem::path filename_otreeA_LOD = "treeA_LOD/tree_test.oct_idx" [static] |
Definition at line 84 of file test_outofcore.cpp.
const boost::filesystem::path filename_otreeB = "treeB/tree_test.oct_idx" [static] |
Definition at line 82 of file test_outofcore.cpp.
const boost::filesystem::path filename_otreeB_LOD = "treeB_LOD/tree_test.oct_idx" [static] |
Definition at line 85 of file test_outofcore.cpp.
Definition at line 101 of file test_outofcore.cpp.
const boost::uint32_t rngseed = 0xAAFF33DD [static] |
Definition at line 79 of file test_outofcore.cpp.