Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Friends
pcl::outofcore::OutofcoreOctreeNodeMetadata Class Reference

Encapsulated class to read JSON metadata into memory, and write the JSON metadata for each node. More...

#include <outofcore_node_data.h>

List of all members.

Public Types

typedef boost::shared_ptr
< const
OutofcoreOctreeNodeMetadata
ConstPtr
typedef boost::shared_ptr
< OutofcoreOctreeNodeMetadata
Ptr

Public Member Functions

void getBoundingBox (Eigen::Vector3d &min_bb, Eigen::Vector3d &max_bb) const
 Get the lower and upper corners of the bounding box enclosing this node.
const Eigen::Vector3d & getBoundingBoxMax () const
 Get the upper bounding box corner.
const Eigen::Vector3d & getBoundingBoxMin () const
 Get the lower bounding box corner.
const boost::filesystem::path & getDirectoryPathname () const
 Get the directory path name; this is the parent_path of.
const boost::filesystem::path & getMetadataFilename () const
 Sets the name of the JSON file.
int getOutofcoreVersion () const
 et the outofcore version read from the "version" field of the JSON object
const boost::filesystem::path & getPCDFilename () const
 Get the path to the PCD file.
const Eigen::Vector3d & getVoxelCenter () const
 Get the midpoint of this node's bounding box.
int loadMetadataFromDisk ()
 Loads the data from a JSON file located at metadata_filename_.
int loadMetadataFromDisk (const boost::filesystem::path &path_to_metadata)
 Loads the data from a JSON file located at metadata_filename_.
 OutofcoreOctreeNodeMetadata ()
 Empty constructor.
 OutofcoreOctreeNodeMetadata (const OutofcoreOctreeNodeMetadata &orig)
 Copy constructor.
void serializeMetadataToDisk ()
 Writes the data to a JSON file located at metadata_filename_.
void setBoundingBox (const Eigen::Vector3d &min_bb, const Eigen::Vector3d &max_bb)
 Set the lower and upper corners of the bounding box.
void setBoundingBoxMax (const Eigen::Vector3d &max_bb)
 Set the upper bounding box corner.
void setBoundingBoxMin (const Eigen::Vector3d &min_bb)
 Set the lower bounding box corner.
void setDirectoryPathname (const boost::filesystem::path &directory_pathname)
 Set the directory path name.
void setMetadataFilename (const boost::filesystem::path &path_to_metadata)
 Gets the name of the JSON file.
void setOutofcoreVersion (const int version)
 Set the outofcore version stored in the "version" field of the JSON object.
void setPCDFilename (const boost::filesystem::path &point_filename)
 Set the point filename; extension .pcd.
 ~OutofcoreOctreeNodeMetadata ()

Protected Member Functions

void updateVoxelCenter ()
 Computes the midpoint; used when bounding box is changed.

Protected Attributes

boost::filesystem::path binary_point_filename_
 Path to PCD file (i.e. "bin"ary point data)
boost::filesystem::path directory_
 Directory this metadata belongs in.
Eigen::Vector3d max_bb_
 The X,Y,Z axes-aligned maximum corner for the bounding box.
boost::filesystem::path metadata_filename_
 Metadata (JSON) file pathname (oct_idx extension JSON file)
Eigen::Vector3d midpoint_xyz_
 Voxel center; not stored on disk.
Eigen::Vector3d min_bb_
 The X,Y,Z axes-aligned minimum corner for the bounding box.
int outofcore_version_
 Outofcore library version identifier.

Friends

std::ostream & operator<< (std::ostream &os, const OutofcoreOctreeNodeMetadata &metadata_arg)

Detailed Description

Encapsulated class to read JSON metadata into memory, and write the JSON metadata for each node.

This class encapsulates the outofcore node metadata serialization/deserialization. At the time it was written, this depended on cJSON to write JSON objects to disk. This class can be extended to have arbitrary ascii metadata fields saved to the metadata object file on disk.

The JSON file is formatted in the following way:

     {
       "version": 3,
       "bb_min":  [xxx,yyy,zzz],
       "bb_max":  [xxx,yyy,zzz],
       "bin":     "path_to_data.pcd"
     }
     

Any properties not stored in the metadata file are computed when the file is loaded (e.g. midpoint_xyz_). By convention, the JSON files are stored on disk with .oct_idx extension.

Author:
Stephen Fox (foxstephend@gmail.com)

Definition at line 83 of file outofcore_node_data.h.


Member Typedef Documentation

Definition at line 89 of file outofcore_node_data.h.

Definition at line 88 of file outofcore_node_data.h.


Constructor & Destructor Documentation

Empty constructor.

Definition at line 56 of file outofcore_node_data.cpp.

Definition at line 69 of file outofcore_node_data.cpp.

Copy constructor.

Definition at line 75 of file outofcore_node_data.cpp.


Member Function Documentation

void pcl::outofcore::OutofcoreOctreeNodeMetadata::getBoundingBox ( Eigen::Vector3d &  min_bb,
Eigen::Vector3d &  max_bb 
) const

Get the lower and upper corners of the bounding box enclosing this node.

Definition at line 125 of file outofcore_node_data.cpp.

Get the upper bounding box corner.

Definition at line 108 of file outofcore_node_data.cpp.

Get the lower bounding box corner.

Definition at line 91 of file outofcore_node_data.cpp.

const boost::filesystem::path & pcl::outofcore::OutofcoreOctreeNodeMetadata::getDirectoryPathname ( ) const

Get the directory path name; this is the parent_path of.

Definition at line 144 of file outofcore_node_data.cpp.

const boost::filesystem::path & pcl::outofcore::OutofcoreOctreeNodeMetadata::getMetadataFilename ( ) const

Sets the name of the JSON file.

Definition at line 192 of file outofcore_node_data.cpp.

et the outofcore version read from the "version" field of the JSON object

Definition at line 176 of file outofcore_node_data.cpp.

const boost::filesystem::path & pcl::outofcore::OutofcoreOctreeNodeMetadata::getPCDFilename ( ) const

Get the path to the PCD file.

Definition at line 159 of file outofcore_node_data.cpp.

Get the midpoint of this node's bounding box.

Definition at line 209 of file outofcore_node_data.cpp.

Loads the data from a JSON file located at metadata_filename_.

Definition at line 255 of file outofcore_node_data.cpp.

int pcl::outofcore::OutofcoreOctreeNodeMetadata::loadMetadataFromDisk ( const boost::filesystem::path &  path_to_metadata)

Loads the data from a JSON file located at metadata_filename_.

Definition at line 336 of file outofcore_node_data.cpp.

Writes the data to a JSON file located at metadata_filename_.

Definition at line 217 of file outofcore_node_data.cpp.

void pcl::outofcore::OutofcoreOctreeNodeMetadata::setBoundingBox ( const Eigen::Vector3d &  min_bb,
const Eigen::Vector3d &  max_bb 
)

Set the lower and upper corners of the bounding box.

Definition at line 134 of file outofcore_node_data.cpp.

void pcl::outofcore::OutofcoreOctreeNodeMetadata::setBoundingBoxMax ( const Eigen::Vector3d &  max_bb)

Set the upper bounding box corner.

Definition at line 116 of file outofcore_node_data.cpp.

void pcl::outofcore::OutofcoreOctreeNodeMetadata::setBoundingBoxMin ( const Eigen::Vector3d &  min_bb)

Set the lower bounding box corner.

Definition at line 99 of file outofcore_node_data.cpp.

void pcl::outofcore::OutofcoreOctreeNodeMetadata::setDirectoryPathname ( const boost::filesystem::path &  directory_pathname)

Set the directory path name.

Definition at line 151 of file outofcore_node_data.cpp.

void pcl::outofcore::OutofcoreOctreeNodeMetadata::setMetadataFilename ( const boost::filesystem::path &  path_to_metadata)

Gets the name of the JSON file.

Definition at line 200 of file outofcore_node_data.cpp.

Set the outofcore version stored in the "version" field of the JSON object.

Definition at line 184 of file outofcore_node_data.cpp.

void pcl::outofcore::OutofcoreOctreeNodeMetadata::setPCDFilename ( const boost::filesystem::path &  point_filename)

Set the point filename; extension .pcd.

Definition at line 167 of file outofcore_node_data.cpp.

Computes the midpoint; used when bounding box is changed.

Definition at line 182 of file outofcore_node_data.h.


Friends And Related Function Documentation

std::ostream& operator<< ( std::ostream &  os,
const OutofcoreOctreeNodeMetadata metadata_arg 
) [friend]

Definition at line 346 of file outofcore_node_data.cpp.


Member Data Documentation

Path to PCD file (i.e. "bin"ary point data)

Definition at line 170 of file outofcore_node_data.h.

boost::filesystem::path pcl::outofcore::OutofcoreOctreeNodeMetadata::directory_ [protected]

Directory this metadata belongs in.

Definition at line 174 of file outofcore_node_data.h.

The X,Y,Z axes-aligned maximum corner for the bounding box.

Definition at line 168 of file outofcore_node_data.h.

Metadata (JSON) file pathname (oct_idx extension JSON file)

Definition at line 176 of file outofcore_node_data.h.

Voxel center; not stored on disk.

Definition at line 172 of file outofcore_node_data.h.

The X,Y,Z axes-aligned minimum corner for the bounding box.

Definition at line 166 of file outofcore_node_data.h.

Outofcore library version identifier.

Definition at line 178 of file outofcore_node_data.h.


The documentation for this class was generated from the following files:


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:44:32