Octree pointcloud compression class More...
#include <octree_pointcloud_compression.h>

Public Types | |
| typedef OctreeT::BranchNode | BranchNode |
| typedef OctreeT::LeafNode | LeafNode |
| typedef OctreePointCloud < PointT, LeafT, BranchT, OctreeT >::PointCloud | PointCloud |
| typedef OctreePointCloud < PointT, LeafT, BranchT, OctreeT >::PointCloudConstPtr | PointCloudConstPtr |
| typedef OctreePointCloud < PointT, LeafT, BranchT, OctreeT >::PointCloudPtr | PointCloudPtr |
| typedef OctreePointCloudCompression < PointT, LeafT, BranchT, Octree2BufBase< LeafT, BranchT > > | RealTimeStreamCompression |
| typedef OctreePointCloudCompression < PointT, LeafT, BranchT, OctreeBase< LeafT, BranchT > > | SinglePointCloudCompressionLowMemory |
Public Member Functions | |
| virtual void | addPointIdx (const int pointIdx_arg) |
| Add point at index from input pointcloud dataset to octree. | |
| void | decodePointCloud (std::istream &compressed_tree_data_in_arg, PointCloudPtr &cloud_arg) |
| Decode point cloud from input stream. | |
| void | encodePointCloud (const PointCloudConstPtr &cloud_arg, std::ostream &compressed_tree_data_out_arg) |
| Encode point cloud to output stream. | |
| PointCloudPtr | getOutputCloud () const |
| Get a pointer to the output point cloud dataset. | |
| void | initialization () |
| Initialize globals. | |
| OctreePointCloudCompression (compression_Profiles_e compressionProfile_arg=MED_RES_ONLINE_COMPRESSION_WITH_COLOR, bool showStatistics_arg=false, const double pointResolution_arg=0.001, const double octreeResolution_arg=0.01, bool doVoxelGridDownDownSampling_arg=false, const unsigned int iFrameRate_arg=30, bool doColorEncoding_arg=true, const unsigned char colorBitResolution_arg=6) | |
| Constructor. | |
| void | setOutputCloud (const PointCloudPtr &cloud_arg) |
| Provide a pointer to the output data set. | |
| virtual | ~OctreePointCloudCompression () |
| Empty deconstructor. | |
Protected Member Functions | |
| virtual void | deserializeTreeCallback (LeafT &, const OctreeKey &key_arg) |
| Decode leaf nodes information during deserialization. | |
| void | entropyDecoding (std::istream &compressed_tree_data_in_arg) |
| Entropy decoding of input binary stream and output to information vectors. | |
| void | entropyEncoding (std::ostream &compressed_tree_data_out_arg) |
| Apply entropy encoding to encoded information and output to binary stream. | |
| void | readFrameHeader (std::istream &compressed_tree_data_in_arg) |
| Read frame information to output stream. | |
| virtual void | serializeTreeCallback (LeafT &leaf_arg, const OctreeKey &key_arg) |
| Encode leaf node information during serialization. | |
| void | syncToHeader (std::istream &compressed_tree_data_in_arg) |
| Synchronize to frame header. | |
| void | writeFrameHeader (std::ostream &compressed_tree_data_out_arg) |
| Write frame information to output stream. | |
Protected Attributes | |
| bool | b_show_statistics_ |
| std::vector< char > | binary_color_tree_vector_ |
| Interator on binary tree structure vector. | |
| std::vector< char > | binary_tree_data_vector_ |
| Vector for storing binary tree structure. | |
| bool | cloud_with_color_ |
| const unsigned char | color_bit_resolution_ |
| ColorCoding< PointT > | color_coder_ |
| Color coding instance. | |
| uint64_t | compressed_color_data_len_ |
| uint64_t | compressed_point_data_len_ |
| bool | data_with_color_ |
| bool | do_color_encoding_ |
| bool | do_voxel_grid_enDecoding_ |
| StaticRangeCoder | entropy_coder_ |
| Static range coder instance. | |
| uint32_t | frame_ID_ |
| bool | i_frame_ |
| uint32_t | i_frame_counter_ |
| uint32_t | i_frame_rate_ |
| std::size_t | object_count_ |
| const double | octree_resolution_ |
| PointCloudPtr | output_ |
| Pointer to output point cloud dataset. | |
| PointCoding< PointT > | point_coder_ |
| Point coding instance. | |
| unsigned char | point_color_offset_ |
| uint64_t | point_count_ |
| std::vector< unsigned int > | point_count_data_vector_ |
| Vector for storing points per voxel information. | |
| std::vector< unsigned int > ::const_iterator | point_count_data_vector_iterator_ |
| Interator on points per voxel vector. | |
| const double | point_resolution_ |
| const compression_Profiles_e | selected_profile_ |
Static Protected Attributes | |
| static const char * | frame_header_identifier_ = "<PCL-OCT-COMPRESSED>" |
Octree pointcloud compression class
Definition at line 74 of file octree_pointcloud_compression.h.
| typedef OctreeT::BranchNode pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::BranchNode |
Reimplemented from pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >.
Definition at line 84 of file octree_pointcloud_compression.h.
| typedef OctreeT::LeafNode pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::LeafNode |
Reimplemented from pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >.
Definition at line 83 of file octree_pointcloud_compression.h.
| typedef OctreePointCloud<PointT, LeafT, BranchT, OctreeT>::PointCloud pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::PointCloud |
Reimplemented from pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >.
Definition at line 79 of file octree_pointcloud_compression.h.
| typedef OctreePointCloud<PointT, LeafT, BranchT, OctreeT>::PointCloudConstPtr pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::PointCloudConstPtr |
Reimplemented from pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >.
Definition at line 81 of file octree_pointcloud_compression.h.
| typedef OctreePointCloud<PointT, LeafT, BranchT, OctreeT>::PointCloudPtr pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::PointCloudPtr |
Reimplemented from pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >.
Definition at line 80 of file octree_pointcloud_compression.h.
| typedef OctreePointCloudCompression<PointT, LeafT, BranchT, Octree2BufBase<LeafT, BranchT> > pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::RealTimeStreamCompression |
Definition at line 86 of file octree_pointcloud_compression.h.
| typedef OctreePointCloudCompression<PointT, LeafT, BranchT, OctreeBase<LeafT, BranchT> > pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::SinglePointCloudCompressionLowMemory |
Definition at line 87 of file octree_pointcloud_compression.h.
| pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::OctreePointCloudCompression | ( | compression_Profiles_e | compressionProfile_arg = MED_RES_ONLINE_COMPRESSION_WITH_COLOR, |
| bool | showStatistics_arg = false, |
||
| const double | pointResolution_arg = 0.001, |
||
| const double | octreeResolution_arg = 0.01, |
||
| bool | doVoxelGridDownDownSampling_arg = false, |
||
| const unsigned int | iFrameRate_arg = 30, |
||
| bool | doColorEncoding_arg = true, |
||
| const unsigned char | colorBitResolution_arg = 6 |
||
| ) | [inline] |
Constructor.
| compressionProfile_arg,: | define compression profile |
| octreeResolution_arg,: | octree resolution at lowest octree level |
| pointResolution_arg,: | precision of point coordinates |
| doVoxelGridDownDownSampling_arg,: | voxel grid filtering |
| iFrameRate_arg,: | i-frame encoding rate |
| doColorEncoding_arg,: | enable/disable color coding |
| colorBitResolution_arg,: | color bit depth |
| showStatistics_arg,: | output compression statistics |
Definition at line 100 of file octree_pointcloud_compression.h.
| virtual pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::~OctreePointCloudCompression | ( | ) | [inline, virtual] |
Empty deconstructor.
Definition at line 131 of file octree_pointcloud_compression.h.
| virtual void pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::addPointIdx | ( | const int | pointIdx_arg | ) | [inline, virtual] |
Add point at index from input pointcloud dataset to octree.
| [in] | pointIdx_arg | the index representing the point in the dataset given by setInputCloud to be added |
Reimplemented from pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >.
Definition at line 170 of file octree_pointcloud_compression.h.
| void pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::decodePointCloud | ( | std::istream & | compressed_tree_data_in_arg, |
| PointCloudPtr & | cloud_arg | ||
| ) |
Decode point cloud from input stream.
| compressed_tree_data_in_arg,: | binary input stream containing compressed data |
| cloud_arg,: | reference to decoded point cloud |
Definition at line 179 of file octree_pointcloud_compression.hpp.
| void pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::deserializeTreeCallback | ( | LeafT & | , |
| const OctreeKey & | key_arg | ||
| ) | [protected, virtual] |
Decode leaf nodes information during deserialization.
| leaf_arg,: | reference to new leaf node |
| key_arg,: | octree key of new leaf node |
Definition at line 511 of file octree_pointcloud_compression.hpp.
| void pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::encodePointCloud | ( | const PointCloudConstPtr & | cloud_arg, |
| std::ostream & | compressed_tree_data_out_arg | ||
| ) |
Encode point cloud to output stream.
| cloud_arg,: | point cloud to be compressed |
| compressed_tree_data_out_arg,: | binary output stream containing compressed data |
Definition at line 59 of file octree_pointcloud_compression.hpp.
| void pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::entropyDecoding | ( | std::istream & | compressed_tree_data_in_arg | ) | [protected] |
Entropy decoding of input binary stream and output to information vectors.
| compressed_tree_data_in_arg,: | binary input stream |
Definition at line 316 of file octree_pointcloud_compression.hpp.
| void pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::entropyEncoding | ( | std::ostream & | compressed_tree_data_out_arg | ) | [protected] |
Apply entropy encoding to encoded information and output to binary stream.
| compressed_tree_data_out_arg,: | binary output stream |
Definition at line 256 of file octree_pointcloud_compression.hpp.
| PointCloudPtr pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::getOutputCloud | ( | ) | const [inline] |
Get a pointer to the output point cloud dataset.
Definition at line 192 of file octree_pointcloud_compression.h.
| void pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::initialization | ( | ) | [inline] |
Initialize globals.
Definition at line 136 of file octree_pointcloud_compression.h.
| void pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::readFrameHeader | ( | std::istream & | compressed_tree_data_in_arg | ) | [protected] |
Read frame information to output stream.
| compressed_tree_data_in_arg,: | binary input stream |
Definition at line 435 of file octree_pointcloud_compression.hpp.
| void pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::serializeTreeCallback | ( | LeafT & | leaf_arg, |
| const OctreeKey & | key_arg | ||
| ) | [protected, virtual] |
Encode leaf node information during serialization.
| leaf_arg,: | reference to new leaf node |
| key_arg,: | octree key of new leaf node |
Definition at line 476 of file octree_pointcloud_compression.hpp.
| void pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::setOutputCloud | ( | const PointCloudPtr & | cloud_arg | ) | [inline] |
Provide a pointer to the output data set.
| cloud_arg,: | the boost shared pointer to a PointCloud message |
Definition at line 180 of file octree_pointcloud_compression.h.
| void pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::syncToHeader | ( | std::istream & | compressed_tree_data_in_arg | ) | [protected] |
Synchronize to frame header.
| compressed_tree_data_in_arg,: | binary input stream |
Definition at line 420 of file octree_pointcloud_compression.hpp.
| void pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::writeFrameHeader | ( | std::ostream & | compressed_tree_data_out_arg | ) | [protected] |
Write frame information to output stream.
| compressed_tree_data_out_arg,: | binary output stream |
Definition at line 373 of file octree_pointcloud_compression.hpp.
bool pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::b_show_statistics_ [protected] |
Definition at line 295 of file octree_pointcloud_compression.h.
std::vector<char> pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::binary_color_tree_vector_ [protected] |
Interator on binary tree structure vector.
Definition at line 265 of file octree_pointcloud_compression.h.
std::vector<char> pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::binary_tree_data_vector_ [protected] |
Vector for storing binary tree structure.
Definition at line 262 of file octree_pointcloud_compression.h.
bool pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::cloud_with_color_ [protected] |
Definition at line 290 of file octree_pointcloud_compression.h.
const unsigned char pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::color_bit_resolution_ [protected] |
Definition at line 305 of file octree_pointcloud_compression.h.
ColorCoding<PointT> pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::color_coder_ [protected] |
Color coding instance.
Definition at line 274 of file octree_pointcloud_compression.h.
uint64_t pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::compressed_color_data_len_ [protected] |
Definition at line 297 of file octree_pointcloud_compression.h.
uint64_t pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::compressed_point_data_len_ [protected] |
Definition at line 296 of file octree_pointcloud_compression.h.
bool pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::data_with_color_ [protected] |
Definition at line 291 of file octree_pointcloud_compression.h.
bool pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::do_color_encoding_ [protected] |
Definition at line 289 of file octree_pointcloud_compression.h.
bool pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::do_voxel_grid_enDecoding_ [protected] |
Definition at line 282 of file octree_pointcloud_compression.h.
StaticRangeCoder pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::entropy_coder_ [protected] |
Static range coder instance.
Definition at line 280 of file octree_pointcloud_compression.h.
const char * pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::frame_header_identifier_ = "<PCL-OCT-COMPRESSED>" [static, protected] |
Definition at line 300 of file octree_pointcloud_compression.h.
uint32_t pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::frame_ID_ [protected] |
Definition at line 285 of file octree_pointcloud_compression.h.
bool pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::i_frame_ [protected] |
Definition at line 287 of file octree_pointcloud_compression.h.
uint32_t pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::i_frame_counter_ [protected] |
Definition at line 284 of file octree_pointcloud_compression.h.
uint32_t pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::i_frame_rate_ [protected] |
Definition at line 283 of file octree_pointcloud_compression.h.
std::size_t pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::object_count_ [protected] |
Definition at line 307 of file octree_pointcloud_compression.h.
const double pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::octree_resolution_ [protected] |
Definition at line 304 of file octree_pointcloud_compression.h.
PointCloudPtr pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::output_ [protected] |
Pointer to output point cloud dataset.
Definition at line 259 of file octree_pointcloud_compression.h.
PointCoding<PointT> pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::point_coder_ [protected] |
Point coding instance.
Definition at line 277 of file octree_pointcloud_compression.h.
unsigned char pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::point_color_offset_ [protected] |
Definition at line 292 of file octree_pointcloud_compression.h.
uint64_t pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::point_count_ [protected] |
Definition at line 286 of file octree_pointcloud_compression.h.
std::vector<unsigned int> pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::point_count_data_vector_ [protected] |
Vector for storing points per voxel information.
Definition at line 268 of file octree_pointcloud_compression.h.
std::vector<unsigned int>::const_iterator pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::point_count_data_vector_iterator_ [protected] |
Interator on points per voxel vector.
Definition at line 271 of file octree_pointcloud_compression.h.
const double pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::point_resolution_ [protected] |
Definition at line 303 of file octree_pointcloud_compression.h.
const compression_Profiles_e pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >::selected_profile_ [protected] |
Definition at line 302 of file octree_pointcloud_compression.h.