42 #include <pcl/common/io.h>
45 #include <pcl/outofcore/octree_base_node.h>
46 #include <pcl/outofcore/octree_disk_container.h>
47 #include <pcl/outofcore/octree_ram_container.h>
50 #include <pcl/outofcore/outofcore_iterator_base.h>
51 #include <pcl/outofcore/outofcore_breadth_first_iterator.h>
52 #include <pcl/outofcore/outofcore_depth_first_iterator.h>
53 #include <pcl/outofcore/impl/outofcore_breadth_first_iterator.hpp>
54 #include <pcl/outofcore/impl/outofcore_depth_first_iterator.hpp>
57 #include <pcl/outofcore/metadata.h>
58 #include <pcl/outofcore/outofcore_base_data.h>
60 #include <pcl/filters/filter.h>
61 #include <pcl/filters/random_sample.h>
63 #include <pcl/PCLPointCloud2.h>
65 #include <shared_mutex>
149 template<
typename ContainerT = OutofcoreOctreeDiskContainer<pcl::Po
intXYZ>,
typename Po
intT = pcl::Po
intXYZ>
178 using Ptr = shared_ptr<OutofcoreOctreeBase<ContainerT, PointT> >;
179 using ConstPtr = shared_ptr<const OutofcoreOctreeBase<ContainerT, PointT> >;
219 OutofcoreOctreeBase (
const Eigen::Vector3d& min,
const Eigen::Vector3d& max,
const double resolution_arg,
const boost::filesystem::path &root_node_name,
const std::string &coord_sys);
234 OutofcoreOctreeBase (
const std::uint64_t max_depth,
const Eigen::Vector3d &min,
const Eigen::Vector3d &max,
const boost::filesystem::path &root_node_name,
const std::string &coord_sys);
301 queryFrustum (
const double *planes, std::list<std::string>& file_names)
const;
304 queryFrustum (
const double *planes, std::list<std::string>& file_names,
const std::uint32_t query_depth)
const;
307 queryFrustum (
const double *planes,
const Eigen::Vector3d &eye,
const Eigen::Matrix4d &view_projection_matrix,
308 std::list<std::string>& file_names,
const std::uint32_t query_depth)
const;
323 queryBBIntersects (
const Eigen::Vector3d &min,
const Eigen::Vector3d &max,
const std::uint32_t query_depth, std::list<std::string> &bin_name)
const;
383 queryBoundingBox (
const Eigen::Vector3d &min,
const Eigen::Vector3d &max,
const int query_depth, std::list<std::string> &filenames)
const
399 getBoundingBox (Eigen::Vector3d &min, Eigen::Vector3d &max)
const;
408 return (
metadata_->getLODPoints (depth_index));
426 inline const std::vector<std::uint64_t>&
472 return (
metadata_->getCoordinateSystem ());
512 getOccupiedVoxelCenters(std::vector<Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d> > &voxel_centers, std::size_t query_depth)
const;
559 return (sample_percent_);
567 this->sample_percent_ = std::fabs (sample_percent_arg) > 1.0 ? 1.0 : std::fabs (sample_percent_arg);
572 init (
const std::uint64_t& depth,
const Eigen::Vector3d& min,
const Eigen::Vector3d& max,
const boost::filesystem::path& root_name,
const std::string& coord_sys);
640 const static std::uint64_t
LOAD_COUNT_ =
static_cast<std::uint64_t
>(2e9);
646 enlargeToCube (Eigen::Vector3d &bb_min, Eigen::Vector3d &bb_max);
650 calculateDepth (
const Eigen::Vector3d& min_bb,
const Eigen::Vector3d& max_bb,
const double leaf_resolution);
652 double sample_percent_;
Filter represents the base filter class.
PointCloud represents the base class in PCL for storing collections of 3D points.
shared_ptr< PointCloud< PointT > > Ptr
shared_ptr< const PointCloud< PointT > > ConstPtr
RandomSample applies a random sampling with uniform probability.
Abstract octree iterator class.
This code defines the octree used for point storage at Urban Robotics.
void DeAllocEmptyNodeCache()
Flush empty nodes only.
OutofcoreOctreeBaseMetadata::Ptr metadata_
shared_ptr< pcl::Indices > IndicesPtr
std::uint64_t queryBoundingBoxNumPoints(const Eigen::Vector3d &min, const Eigen::Vector3d &max, const int query_depth, bool load_from_disk=true)
Queries the number of points in a bounding box.
static const int OUTOFCORE_VERSION_
virtual void queryBoundingBox(const Eigen::Vector3d &min, const Eigen::Vector3d &max, const int query_depth, std::list< std::string > &filenames) const
Returns list of pcd files from nodes whose bounding boxes intersect with the input bounding box.
std::uint64_t getNumPointsAtDepth(const std::uint64_t &depth_index) const
Get number of points at specified LOD.
OutofcoreOctreeBase & operator=(OutofcoreOctreeBase &rval)
std::uint64_t addDataToLeaf(const AlignedPointTVector &p)
Recursively add points to the tree.
const std::vector< std::uint64_t > & getNumPointsVector() const
Get number of points at each LOD.
void incrementPointsInLOD(std::uint64_t depth, std::uint64_t inc)
Increment current depths (LOD for branch nodes) point count; called by addDataAtMaxDepth in Outofcore...
void queryFrustum(const double *planes, std::list< std::string > &file_names) const
std::shared_timed_mutex read_write_mutex_
shared mutex for controlling read/write access to disk
void DeAllocEmptyNodeCache(OutofcoreNodeType *current)
flush empty nodes only
std::uint64_t addPointCloud_and_genLOD(pcl::PCLPointCloud2::Ptr &input_cloud)
Recursively add points to the tree.
void convertToXYZ()
Save each .bin file as an XYZ file.
OutofcoreOctreeBase(const boost::filesystem::path &root_node_name, const bool load_all)
Load an existing tree.
void getOccupiedVoxelCenters(AlignedPointTVector &voxel_centers, std::size_t query_depth) const
Returns the voxel centers of all existing voxels at query_depth.
void writeVPythonVisual(const boost::filesystem::path &filename)
Write a python script using the vpython module containing all the bounding boxes.
void buildLOD()
Generate multi-resolution LODs for the tree, which are a uniform random sampling all child leafs belo...
void queryBBIncludes(const Eigen::Vector3d &min, const Eigen::Vector3d &max, const std::uint64_t query_depth, AlignedPointTVector &dst) const
Get Points in BB, only points inside BB.
const std::string & getCoordSystem() const
Get coordinate system tag from the JSON metadata file.
OutofcoreOctreeBaseNode< ContainerT, PointT > BranchNode
typename PointCloud::Ptr PointCloudPtr
void queryBBIntersects(const Eigen::Vector3d &min, const Eigen::Vector3d &max, const std::uint32_t query_depth, std::list< std::string > &bin_name) const
Get a list of file paths at query_depth that intersect with your bounding box specified by min and ma...
std::uint64_t getDepth() const
Get number of LODs, which is the height of the tree.
bool getBoundingBox(Eigen::Vector3d &min, Eigen::Vector3d &max) const
Get the overall bounding box of the outofcore octree; this is the same as the bounding box of the roo...
double getVoxelSideLength() const
Gets the smallest (assumed) cubic voxel side lengths.
void flushToDiskLazy()
Flush all non leaf nodes' cache.
virtual void queryBoundingBox(const Eigen::Vector3d &min, const Eigen::Vector3d &max, const int query_depth, const pcl::PCLPointCloud2::Ptr &dst_blob, double percent=1.0)
Query all points falling within the input bounding box at query_depth and return a PCLPointCloud2 obj...
std::uint64_t getTreeDepth() const
bool checkExtension(const boost::filesystem::path &path_name)
Auxiliary function to validate path_name extension is .octree.
std::uint64_t addDataToLeaf_and_genLOD(AlignedPointTVector &p)
Recursively add points to the tree subsampling LODs on the way.
OutofcoreOctreeBaseNode< ContainerT, PointT > OutofcoreNodeType
bool getBinDimension(double &x, double &y) const
Computes the expected voxel dimensions at the leaves.
shared_ptr< OutofcoreOctreeBase< ContainerT, PointT > > Ptr
std::vector< PointT, Eigen::aligned_allocator< PointT > > AlignedPointTVector
shared_ptr< const OutofcoreOctreeBase< ContainerT, PointT > > ConstPtr
void flushToDisk()
Flush all nodes' cache.
OutofcoreNodeType * getRootNode()
void printBoundingBox() const
Prints size of the bounding boxes to stdou.
void buildLODRecursive(const std::vector< BranchNode * > ¤t_branch)
recursive portion of lod builder
static const std::string TREE_EXTENSION_
defined as ".octree" to append to treepath files
shared_ptr< const pcl::Indices > IndicesConstPtr
OutofcoreNodeType * getBranchChildPtr(const BranchNode &branch_arg, unsigned char childIdx_arg) const
void getOccupiedVoxelCenters(AlignedPointTVector &voxel_centers) const
Gets the voxel centers of all occupied/existing leaves of the tree.
OutofcoreOctreeBase(const OutofcoreOctreeBase &rval)
void queryBBIncludes_subsample(const Eigen::Vector3d &min, const Eigen::Vector3d &max, std::uint64_t query_depth, const double percent, AlignedPointTVector &dst) const
Returns a random subsample of points within the given bounding box at query_depth.
void printBoundingBox(OutofcoreNodeType &node) const
Prints the coordinates of the bounding box of the node to stdout.
std::uint64_t addPointCloud(PointCloudConstPtr point_cloud)
Copies the points from the point_cloud falling within the bounding box of the octree to the out-of-co...
void init(const std::uint64_t &depth, const Eigen::Vector3d &min, const Eigen::Vector3d &max, const boost::filesystem::path &root_name, const std::string &coord_sys)
void setSamplePercent(const double sample_percent_arg)
Sets the sampling percent for constructing LODs.
std::uint64_t addPointCloud(pcl::PCLPointCloud2::Ptr &input_cloud)
void saveToFile()
Write octree definition ".octree" (defined by octree_extension_) to disk.
OutofcoreOctreeBase(OutofcoreOctreeBase &rval)
static const std::uint64_t LOAD_COUNT_
double getSamplePercent() const
Returns the sample_percent_ used when constructing the LOD.
typename PointCloud::ConstPtr PointCloudConstPtr
void setLODFilter(const pcl::Filter< pcl::PCLPointCloud2 >::Ptr &filter_arg)
Sets the filter to use when building the levels of depth.
OutofcoreNodeType * root_node_
Pointer to the root node of the octree data structure.
void getOccupiedVoxelCenters(std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > &voxel_centers) const
Returns the voxel centers of all occupied/existing leaves of the tree.
pcl::Filter< pcl::PCLPointCloud2 >::Ptr getLODFilter()
virtual ~OutofcoreOctreeBase()
OutofcoreOctreeBaseNode Class internally representing nodes of an outofcore octree,...
virtual void queryBBIntersects(const Eigen::Vector3d &min_bb, const Eigen::Vector3d &max_bb, const std::uint32_t query_depth, std::list< std::string > &file_names)
Recursive acquires PCD paths to any node with which the queried bounding box intersects (at query_dep...
shared_ptr< ::pcl::PCLPointCloud2 > Ptr
A point structure representing Euclidean xyz coordinates, and the RGB color.
std::string node_container_extension_
std::string node_container_basename_
std::string node_index_basename_
std::string node_index_extension_