Point Cloud Compression

Point clouds consist of huge data sets describing three dimensional points associated with additional information such as distance, color, normals, etc. Additionally, they can be created at high rate and therefore occupy a significant amount of memory resources. Once point clouds have to be stored or transmitted over rate-limited communication channels, methods for compressing this kind of data become highly interesting. The Point Cloud Library provides point cloud compression functionality. It allows for encoding all kinds of point clouds including “unorganized” point clouds that are characterized by non-existing point references, varying point size, resolution, density and/or point ordering. Furthermore, the underlying octree data structure enables to efficiently merge point cloud data from several sources.

octreeCompression

In the following, we explain how single point clouds as well as streams of points clouds can be efficiently compressed. In the presented example, we capture point clouds with the OpenNIGrabber to be compressed using the PCL point cloud compression techniques.

The code:

First, create a file, let’s say, point_cloud_compression.cpp and place the following inside it:

 1#include <pcl/point_cloud.h>
 2#include <pcl/point_types.h>
 3#include <pcl/io/openni_grabber.h>
 4#include <pcl/visualization/cloud_viewer.h>
 5
 6#include <pcl/compression/octree_pointcloud_compression.h>
 7
 8#include <stdio.h>
 9#include <sstream>
10#include <stdlib.h>
11
12#ifdef WIN32
13# define sleep(x) Sleep((x)*1000)
14#endif
15
16class SimpleOpenNIViewer
17{
18public:
19  SimpleOpenNIViewer () :
20    viewer (" Point Cloud Compression Example")
21  {
22  }
23
24  void
25  cloud_cb_ (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr &cloud)
26  {
27    if (!viewer.wasStopped ())
28    {
29      // stringstream to store compressed point cloud
30      std::stringstream compressedData;
31      // output pointcloud
32      pcl::PointCloud<pcl::PointXYZRGBA>::Ptr cloudOut (new pcl::PointCloud<pcl::PointXYZRGBA> ());
33
34      // compress point cloud
35      PointCloudEncoder->encodePointCloud (cloud, compressedData);
36
37      // decompress point cloud
38      PointCloudDecoder->decodePointCloud (compressedData, cloudOut);
39
40
41      // show decompressed point cloud
42      viewer.showCloud (cloudOut);
43    }
44  }
45
46  void
47  run ()
48  {
49
50    bool showStatistics = true;
51
52    // for a full list of profiles see: /io/include/pcl/compression/compression_profiles.h
53    pcl::io::compression_Profiles_e compressionProfile = pcl::io::MED_RES_ONLINE_COMPRESSION_WITH_COLOR;
54
55    // instantiate point cloud compression for encoding and decoding
56    PointCloudEncoder = new pcl::io::OctreePointCloudCompression<pcl::PointXYZRGBA> (compressionProfile, showStatistics);
57    PointCloudDecoder = new pcl::io::OctreePointCloudCompression<pcl::PointXYZRGBA> ();
58
59    // create a new grabber for OpenNI devices
60    pcl::Grabber* interface = new pcl::OpenNIGrabber ();
61
62    // make callback function from member function
63    std::function<void(const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr&)> f =
64      [this] (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr& cloud) { cloud_cb_ (cloud); };
65
66    // connect callback function for desired signal. In this case its a point cloud with color values
67    boost::signals2::connection c = interface->registerCallback (f);
68
69    // start receiving point clouds
70    interface->start ();
71
72    while (!viewer.wasStopped ())
73    {
74      sleep (1);
75    }
76
77    interface->stop ();
78
79    // delete point cloud compression instances
80    delete (PointCloudEncoder);
81    delete (PointCloudDecoder);
82
83  }
84
85  pcl::visualization::CloudViewer viewer;
86
87  pcl::io::OctreePointCloudCompression<pcl::PointXYZRGBA>* PointCloudEncoder;
88  pcl::io::OctreePointCloudCompression<pcl::PointXYZRGBA>* PointCloudDecoder;
89
90};
91
92int
93main ()
94{
95  SimpleOpenNIViewer v;
96  v.run ();
97
98  return (0);
99}

The explanation

Now, let’s discuss the code in detail. Let’s start at the main() function: First we create a new SimpleOpenNIViewer instance and call its run() method.

int
main ()
{
  SimpleOpenNIViewer v;
  v.run ();

  return (0);
}

In the run() function, we create instances of the OctreePointCloudCompression class for encoding and decoding. They can take compression profiles as an arguments for configuring the compression algorithm. The provided compression profiles predefine common parameter sets for point clouds captured by openNI devices. In this example, we use the MED_RES_ONLINE_COMPRESSION_WITH_COLOR profile which applies a coordinate encoding precision of 5 cubic millimeter and enables color component encoding. It is further optimized for fast online compression. A full list of compression profiles including their configuration can be found in the file “/io/include/pcl/compression/compression_profiles.h”. A full parametrization of the compression algorithm is also possible in the OctreePointCloudCompression constructor using the MANUAL_CONFIGURATION profile. For further details on advanced parametrization, please have a look at section “Advanced Parametrization”.

    bool showStatistics = true;

    // for a full list of profiles see: /io/include/pcl/compression/compression_profiles.h
    pcl::io::compression_Profiles_e compressionProfile = pcl::io::MED_RES_ONLINE_COMPRESSION_WITH_COLOR;

    // instantiate point cloud compression for encoding and decoding
    PointCloudEncoder = new pcl::io::OctreePointCloudCompression<pcl::PointXYZRGBA> (compressionProfile, showStatistics);
    PointCloudDecoder = new pcl::io::OctreePointCloudCompression<pcl::PointXYZRGBA> ();

The following code instantiates a new grabber for an OpenNI device and starts the interface callback loop.

    // create a new grabber for OpenNI devices
    pcl::Grabber* interface = new pcl::OpenNIGrabber ();

    // make callback function from member function
    std::function<void(const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr&)> f =
      [this] (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr& cloud) { cloud_cb_ (cloud); };

    // connect callback function for desired signal. In this case its a point cloud with color values
    boost::signals2::connection c = interface->registerCallback (f);

    // start receiving point clouds
    interface->start ();

    while (!viewer.wasStopped ())
    {
      sleep (1);
    }

    interface->stop ();

In the callback function executed by the OpenNIGrabber capture loop, we first compress the captured point cloud into a stringstream buffer. That follows a decompression step, which decodes the compressed binary data into a new point cloud object. The decoded point cloud is then sent to the point cloud viewer.

  void
  cloud_cb_ (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr &cloud)
  {
    if (!viewer.wasStopped ())
    {
      // stringstream to store compressed point cloud
      std::stringstream compressedData;
      // output pointcloud
      pcl::PointCloud<pcl::PointXYZRGBA>::Ptr cloudOut (new pcl::PointCloud<pcl::PointXYZRGBA> ());

      // compress point cloud
      PointCloudEncoder->encodePointCloud (cloud, compressedData);

      // decompress point cloud
      PointCloudDecoder->decodePointCloud (compressedData, cloudOut);


      // show decompressed point cloud
      viewer.showCloud (cloudOut);
    }
  }

Compiling and running the program

Add the following lines to your CMakeLists.txt file:

 1cmake_minimum_required(VERSION 3.5 FATAL_ERROR)
 2
 3project(point_cloud_compression)
 4
 5find_package(PCL 1.2 REQUIRED)
 6
 7include_directories(${PCL_INCLUDE_DIRS})
 8link_directories(${PCL_LIBRARY_DIRS})
 9add_definitions(${PCL_DEFINITIONS})
10
11add_executable (point_cloud_compression point_cloud_compression.cpp)
12target_link_libraries (point_cloud_compression ${PCL_LIBRARIES})

After you have made the executable, you can run it. Simply do:

$ ./point_cloud_compression

You will see something similar to:

[OpenNIGrabber] Number devices connected: 1
[OpenNIGrabber] 1. device on bus 002:17 is a Xbox NUI Camera (2ae) from Microsoft (45e) with serial id 'B00364707960044B'
[OpenNIGrabber] device_id is not set or has unknown format: ! Using first device.
[OpenNIGrabber] Opened 'Xbox NUI Camera' on bus 2:17 with serial number 'B00364707960044B'
streams alive:  image,  depth_image
*** POINTCLOUD ENCODING ***
Frame ID: 1
Encoding Frame: Intra frame
Number of encoded points: 192721
XYZ compression percentage: 3.91049%
XYZ bytes per point: 0.469259 bytes
Color compression percentage: 15.4717%
Color bytes per point: 0.618869 bytes
Size of uncompressed point cloud: 3011.27 kBytes
Size of compressed point cloud: 204 kBytes
Total bytes per point: 1.08813 bytes
Total compression percentage: 6.8008%
Compression ratio: 14.7042

*** POINTCLOUD ENCODING ***
Frame ID: 2
Encoding Frame: Prediction frame
Number of encoded points: 192721
XYZ compression percentage: 3.8132%
XYZ bytes per point: 0.457584 bytes
Color compression percentage: 15.5448%
Color bytes per point: 0.62179 bytes
Size of uncompressed point cloud: 3011.27 kBytes
Size of compressed point cloud: 203 kBytes
Total bytes per point: 1.07937 bytes
Total compression percentage: 6.74609%
Compression ratio: 14.8234

*** POINTCLOUD ENCODING ***
Frame ID: 3
Encoding Frame: Prediction frame
Number of encoded points: 192721
XYZ compression percentage: 3.79962%
XYZ bytes per point: 0.455954 bytes
Color compression percentage: 15.2121%
Color bytes per point: 0.608486 bytes
Size of uncompressed point cloud: 3011.27 kBytes
Size of compressed point cloud: 200 kBytes
Total bytes per point: 1.06444 bytes
Total compression percentage: 6.65275%
Compression ratio: 15.0314

...

Compression Profiles:

Compression profiles define parameter sets for the PCL point cloud encoder. They are optimized for compression of common point clouds retrieved from the OpenNI grabber. Please note, that the decoder does not need to be parametrized as it detects and adopts the configuration used during encoding. The following compression profiles are available:

  • LOW_RES_ONLINE_COMPRESSION_WITHOUT_COLOR 1 cubic centimeter resolution, no color, fast online encoding

  • LOW_RES_ONLINE_COMPRESSION_WITH_COLOR 1 cubic centimeter resolution, color, fast online encoding

  • MED_RES_ONLINE_COMPRESSION_WITHOUT_COLOR 5 cubic millimeter resolution, no color, fast online encoding

  • MED_RES_ONLINE_COMPRESSION_WITH_COLOR 5 cubic millimeter resolution, color, fast online encoding

  • HIGH_RES_ONLINE_COMPRESSION_WITHOUT_COLOR 1 cubic millimeter resolution, no color, fast online encoding

  • HIGH_RES_ONLINE_COMPRESSION_WITH_COLOR 1 cubic millimeter resolution, color, fast online encoding

  • LOW_RES_OFFLINE_COMPRESSION_WITHOUT_COLOR 1 cubic centimeter resolution, no color, efficient offline encoding

  • LOW_RES_OFFLINE_COMPRESSION_WITH_COLOR 1 cubic centimeter resolution, color, efficient offline encoding

  • MED_RES_OFFLINE_COMPRESSION_WITHOUT_COLOR 5 cubic millimeter resolution, no color, efficient offline encoding

  • MED_RES_OFFLINE_COMPRESSION_WITH_COLOR 5 cubic millimeter resolution, color, efficient offline encoding

  • HIGH_RES_OFFLINE_COMPRESSION_WITHOUT_COLOR 1 cubic millimeter resolution, no color, efficient offline encoding

  • HIGH_RES_OFFLINE_COMPRESSION_WITH_COLOR 1 cubic millimeter resolution, color, efficient offline encoding

  • MANUAL_CONFIGURATION enables manual configuration for advanced parametrization

Advanced parametrization:

In order to have full access to all compression related parameters, the constructor of the OctreePointCloudCompression class can initialized with additional compression parameters. Please note, that for enabling advanced parametrization, the compressionProfile_arg argument needs to be set to MANUAL_CONFIGURATION.

OctreePointCloudCompression (compression_Profiles_e compressionProfile_arg,
                             bool showStatistics_arg,
                             const double pointResolution_arg,
                             const double octreeResolution_arg,
                             bool doVoxelGridDownDownSampling_arg,
                             const unsigned int iFrameRate_arg,
                             bool doColorEncoding_arg,
                             const unsigned char colorBitResolution_arg
                            )

The advanced parametrization is explained in the following:

  • compressionProfile_arg: This parameter should be set to MANUAL_CONFIGURATION for enabling advanced parametrization.

  • showStatistics_arg: Print compression related statistics to stdout.

  • pointResolution_arg: Define coding precision for point coordinates. This parameter should be set to a value below the sensor noise.

  • octreeResolution_arg: This parameter defines the voxel size of the deployed octree. A lower voxel resolution enables faster compression at, however, decreased compression performance. This enables a trade-off between high frame/update rates and compression efficiency.

  • doVoxelGridDownDownSampling_arg: If activated, only the hierarchical octree data structure is encoded. The decoder generated points at the voxel centers. In this way, the point cloud becomes downsampled during compression while achieving high compression performance.

  • iFrameRate_arg: The point cloud compression scheme differentially encodes point clouds. In this way, differences between the incoming point cloud and the previously encoded pointcloud is encoded in order to achieve maximum compression performance. The iFrameRate_arg allows to specify the rate of frames in the stream at which incoming point clouds are not differentially encoded (similar to I/P-frames in video coding).

  • doColorEncoding_arg: This option enables color component encoding.

  • colorBitResolution_arg: This parameter defines the amount of bits per color component to be encoded.

Command line tool for PCL point cloud stream compression

The pcl apps component contains a command line tool for point cloud compression and streaming: Simply execute “./pcl_openni_octree_compression -?” to see a full list of options (note: the output on screen may differ):

PCL point cloud stream compression

usage: ./pcl_openni_octree_compression [mode] [profile] [parameters]

I/O:
    -f file  : file name

file compression mode:
    -x: encode point cloud stream to file
    -d: decode from file and display point cloud stream

network streaming mode:
    -s       : start server on localhost
    -c host  : connect to server and display decoded cloud stream

optional compression profile:
    -p profile : select compression profile:
                   -"lowC"  Low resolution with color
                   -"lowNC" Low resolution without color
                   -"medC" Medium resolution with color
                   -"medNC" Medium resolution without color
                   -"highC" High resolution with color
                   -"highNC" High resolution without color

optional compression parameters:
    -r prec  : point precision
    -o prec  : octree voxel size
    -v       : enable voxel-grid downsampling
    -a       : enable color coding
    -i rate  : i-frame rate
    -b bits  : bits/color component
    -t       : output statistics
    -e       : show input cloud during encoding

example:
    ./pcl_openni_octree_compression -x -p highC -t -f pc_compressed.pcc

In order to stream compressed point cloud via TCP/IP, you can start the server with:

$ ./pcl_openni_octree_compression -s

It will listen on port 6666 for incoming connections. Now start the client with:

$ ./pcl_openni_octree_compression -c SERVER_NAME

and remotely captured point clouds will be locally shown in the point cloud viewer.

Conclusion

This PCL point cloud compression enables to efficiently compress point clouds of any type and point cloud streams.