Commit ca4ac3f9 authored by David Flynn's avatar David Flynn
Browse files

m42238/geometry: neighbour contextualised coding of occupancy

This commit provides an implementation of m42238 to code occupancy:

 - a node's child occupancy is contextualised based on the adjacent
   neighbours of the parent node.

 - when an isolated node is occupied by only a single child, the
   sub-node address [0,7] is directly coded instead of the 8-bit
   occupancy word.

 - collection of neighbour occupancy is performed using a scatter/
   gather operation upon the insertion of each child node into the
   fifo queue.

 - the feature may be controlled via the command line / config file
   using the --neighbourContextualisation=1|0 option
parent 63b7fab9
......@@ -40,6 +40,8 @@
#include <math.h>
#include <string.h>
#include "PCCMisc.h"
namespace pcc {
/// Vector dim 3
template <typename T>
......@@ -254,6 +256,20 @@ template <typename T>
bool PCCApproximatelyEqual(T a, T b, T epsilon = std::numeric_limits<double>::epsilon()) {
return fabs(a - b) <= ((fabs(a) < fabs(b) ? fabs(b) : fabs(a)) * epsilon);
}
//---------------------------------------------------------------------------
// Convert a vector position (divided by 2^depth) to morton order address.
template <typename T>
uint64_t mortonAddr(const PCCVector3<T>& vec, int depth) {
uint64_t addr = interleave3b0(uint64_t(vec.z()) >> depth);
addr |= interleave3b0(uint64_t(vec.y()) >> depth) << 1;
addr |= interleave3b0(uint64_t(vec.x()) >> depth) << 2;
return addr;
}
//---------------------------------------------------------------------------
} /* namespace pcc */
#endif /* PCCMath_h */
......@@ -124,6 +124,14 @@ static int popcnt(uint32_t x) {
return ((x + (x >> 4) & 0xF0F0F0Fu) * 0x1010101u) >> 24;
}
//---------------------------------------------------------------------------
// Test if population count is greater than 1.
// Returns non-zero if true.
//
static uint32_t popcntGt1(uint32_t x) {
return x & (x - 1);
}
//---------------------------------------------------------------------------
// Round @x up to next power of two.
//
......@@ -154,6 +162,29 @@ static int ceillog2(uint32_t x) {
return ilog2(x-1) + 1;
}
//-------------------------------------------------------------------------
// Shuffle bits of x so as to interleave 0b00 between each pair.
// NB: x must be in the range [0, 2**21 - 1].
//
static int64_t interleave3b0(uint64_t x)
{
x = ((x << 32) | x) & 0x00ff00000000ffffllu;
x = ((x << 16) | x) & 0x00ff0000ff0000ffllu;
x = ((x << 8) | x) & 0xf00f00f00f00f00fllu;
x = ((x << 4) | x) & 0x30c30c30c30c30c3llu;
x = ((x << 2) | x) & 0x9249249249249249llu;
return x;
}
//---------------------------------------------------------------------------
// Decrement the @axis-th dimension of 3D morton code @x.
//
static uint64_t morton3dAxisDec(uint64_t val, int axis)
{
const uint64_t mask0 = 0x9249249249249249llu << axis;
return ((val & mask0) - 1 & mask0) | (val & ~mask0);
}
//---------------------------------------------------------------------------
// Sort the elements in range [@first, @last) using a counting sort.
//
......
......@@ -54,6 +54,17 @@ struct PCCOctree3Node {
// Range of point indexes spanned by node
uint32_t start;
uint32_t end;
// address of the current node in 3D morton order.
uint64_t mortonIdx;
// pattern denoting occupied neighbour nodes.
// 32 8 (y)
// |/
// 2--n--1 (x)
// /|
// 4 16 (z)
uint8_t neighPattern = 0;
};
struct PCCNeighborInfo {
......@@ -207,6 +218,89 @@ inline void PCCBuildPredictors(const PCCPointSet3 &pointCloud,
prevIndexesSize = indexes.size();
}
}
//---------------------------------------------------------------------------
// Update the neighbour pattern flags for a node and the 'left' neighbour on
// each axis. This update should be applied to each newly inserted node.
void
updateGeometryNeighState(
const ringbuf<PCCOctree3Node>::iterator& bufEnd,
int64_t numNodesNextLvl, int childSizeLog2,
PCCOctree3Node& child, int childIdx, uint8_t neighPattern,
uint8_t parantOccupancy
) {
uint64_t midx = child.mortonIdx = mortonAddr(child.pos, childSizeLog2);
static const struct {
int childIdxBitPos;
int axis;
int patternFlagUs;
int patternFlagThem;
} neighParamMap[] = {
{4, 2, 1<<1, 1<<0}, // x
{2, 1, 1<<2, 1<<3}, // y
{1, 0, 1<<4, 1<<5}, // z
};
for (const auto& param : neighParamMap) {
// skip expensive check if parent's flags indicate adjacent neighbour
// is not present.
if ((childIdx & param.childIdxBitPos) == 0) {
// $axis co-ordinate = 0
if (parantOccupancy & (1<<(childIdx + param.childIdxBitPos)))
child.neighPattern |= param.patternFlagThem;
if (!(neighPattern & param.patternFlagUs))
continue;
}
else {
if (parantOccupancy & (1<<(childIdx - param.childIdxBitPos)))
child.neighPattern |= param.patternFlagUs;
// no external search is required for $axis co-ordinate = 1
continue;
}
// calculate the morton address of the 'left' neighbour,
// the delta is then used as the starting position for a search
int64_t mortonIdxNeigh =
morton3dAxisDec(midx, param.axis) & ~0x8000000000000000ull;
int64_t mortonDelta = midx - mortonIdxNeigh;
if (mortonDelta < 0) {
// no neighbour due to being in zero-th col/row/plane
continue;
}
// NB: fifo already contains current node, no point searching it
auto posEnd = bufEnd;
std::advance(posEnd, -1);
auto posStart = bufEnd;
std::advance(posStart, -std::min(numNodesNextLvl, mortonDelta+2));
auto found = std::lower_bound(posStart, posEnd, mortonIdxNeigh,
[](const PCCOctree3Node& node, uint64_t mortonIdx) {
return node.mortonIdx < mortonIdx;
}
);
// NB: found is always valid (see posEnd) => can skip check.
if (found->mortonIdx != mortonIdxNeigh) {
// neighbour isn't present => must have been empty
continue;
}
// update both node's neighbour pattern
// NB: neighours being present implies occupancy
child.neighPattern |= param.patternFlagUs;
found->neighPattern |= param.patternFlagThem;
}
}
//---------------------------------------------------------------------------
}
#endif /* PCCTMC3Common_h */
......@@ -46,6 +46,8 @@
#include "PCCTMC3Common.h"
#include "ArithmeticCodec.h"
#include "tables.h"
namespace pcc {
class PCCTMC3Decoder3 {
......@@ -416,6 +418,9 @@ class PCCTMC3Decoder3 {
PCCReadFromBuffer<uint8_t>(bitstream.buffer, u8value, bitstream.size);
geometryPointsAreUnique = bool(u8value);
PCCReadFromBuffer<uint8_t>(bitstream.buffer, u8value, bitstream.size);
neighbourContextsEnabled = bool(u8value);
if (hasColors) {
pointCloud.addColors();
} else {
......@@ -463,6 +468,78 @@ class PCCTMC3Decoder3 {
return count;
}
//-------------------------------------------------------------------------
// map the @occupancy pattern bits to take into account symmetries in the
// neighbour configuration @neighPattern.
//
uint8_t
mapGeometryOccupancyInv(uint8_t occupancy, uint8_t neighPattern)
{
switch (kOccMapRotateXIdFromPattern[neighPattern]) {
case 1: occupancy = kOccMapRotateX270[occupancy]; break;
case 2: occupancy = kOccMapRotateX270Y180[occupancy]; break;
case 3: occupancy = kOccMapRotateX090Y180[occupancy]; break;
}
if (kOccMapRotateYIdFromPattern[neighPattern]) {
occupancy = kOccMapRotateY090[occupancy];
}
bool flag_ud = (neighPattern & 16) && !(neighPattern & 32);
if (flag_ud) {
occupancy = kOccMapMirrorXY[occupancy];
}
switch (kOccMapRotateZIdFromPatternXY[neighPattern & 15]) {
case 1: occupancy = kOccMapRotateZ270[occupancy]; break;
case 2: occupancy = kOccMapRotateZ180[occupancy]; break;
case 3: occupancy = kOccMapRotateZ090[occupancy]; break;
}
return occupancy;
}
//-------------------------------------------------------------------------
// decode node occupancy bits
//
uint32_t decodeGeometryOccupancy(
bool neighbourContextsEnabled,
o3dgc::Arithmetic_Codec* arithmeticDecoder,
o3dgc::Adaptive_Bit_Model& ctxSingleChild,
o3dgc::Static_Bit_Model& ctxEquiProb,
o3dgc::Adaptive_Data_Model (&ctxOccupancy)[10],
const PCCOctree3Node& node0
) {
if (!neighbourContextsEnabled) {
return arithmeticDecoder->decode(ctxOccupancy[0]);
}
// neighbouring configuration with reduction from 64 to 10
int neighPattern = node0.neighPattern;
int neighPattern10 = kNeighPattern64to10[neighPattern];
// decode occupancy pattern
uint32_t occupancy;
if (neighPattern10 == 0) {
// neighbour empty and only one point => decode index, not pattern
if (arithmeticDecoder->decode(ctxSingleChild)) {
uint32_t cnt = arithmeticDecoder->decode(ctxEquiProb);
cnt |= arithmeticDecoder->decode(ctxEquiProb) << 1;
cnt |= arithmeticDecoder->decode(ctxEquiProb) << 2;
occupancy = 1 << cnt;
}
else {
occupancy = arithmeticDecoder->decode(ctxOccupancy[0]);
}
}
else {
occupancy = arithmeticDecoder->decode(ctxOccupancy[neighPattern10]);
occupancy = mapGeometryOccupancyInv(occupancy, neighPattern);
}
return occupancy;
}
//-------------------------------------------------------------------------
int decodePositions(PCCBitstream &bitstream, PCCPointSet3 &pointCloud) {
......@@ -472,11 +549,19 @@ class PCCTMC3Decoder3 {
arithmeticDecoder.set_buffer(uint32_t(bitstream.capacity - bitstream.size),
bitstream.buffer + bitstream.size);
arithmeticDecoder.start_decoder();
o3dgc::Adaptive_Data_Model multiSymbolOccupancyModel0(257);
o3dgc::Static_Bit_Model ctxEquiProb;
o3dgc::Adaptive_Bit_Model ctxSingleChild;
o3dgc::Adaptive_Bit_Model ctxSinglePointPerBlock;
o3dgc::Adaptive_Bit_Model ctxPointCountPerBlock;
// pattern model using ten 6-neighbour configurations
o3dgc::Adaptive_Data_Model ctxOccupancy[10];
for (int i = 0; i < 10; i++) {
ctxOccupancy[i].set_alphabet(256);
if (neighbourContextsEnabled)
ctxOccupancy[i].reset(kInitCtxOccupancy + 256 * i, true);
}
// init main fifo
// -- worst case size is the last level containing every input poit
......@@ -496,6 +581,7 @@ class PCCTMC3Decoder3 {
node00.start = uint32_t(0);
node00.end = uint32_t(pointCloud.getPointCount());
node00.pos = uint32_t(0);
node00.neighPattern = 0;
fifo.push_back(node00);
size_t processedPointCount = 0;
......@@ -503,16 +589,24 @@ class PCCTMC3Decoder3 {
auto fifoCurrLvlEnd = fifo.end();
// this counter represents fifo.end() - fifoCurrLvlEnd().
// ie, the number of nodes added to the next level of the tree
int numNodesNextLvl = 0;
for (; !fifo.empty(); fifo.pop_front()) {
if (fifo.begin() == fifoCurrLvlEnd) {
// transition to the next level
fifoCurrLvlEnd = fifo.end();
nodeSizeLog2--;
numNodesNextLvl = 0;
}
PCCOctree3Node& node0 = fifo.front();
// split the current node based on occupancy.
const uint32_t occupancy = arithmeticDecoder.decode(multiSymbolOccupancyModel0);
// decode occupancy pattern
uint8_t occupancy = decodeGeometryOccupancy(
neighbourContextsEnabled, &arithmeticDecoder, ctxSingleChild,
ctxEquiProb, ctxOccupancy, node0
);
assert(occupancy > 0);
// split the current node
......@@ -561,6 +655,15 @@ class PCCTMC3Decoder3 {
child.pos[0] = node0.pos[0] + (x << childSizeLog2);
child.pos[1] = node0.pos[1] + (y << childSizeLog2);
child.pos[2] = node0.pos[2] + (z << childSizeLog2);
// NB: there is no need to update the neighbour state for leaf nodes
numNodesNextLvl++;
if (neighbourContextsEnabled) {
updateGeometryNeighState(
fifo.end(), numNodesNextLvl, childSizeLog2, child, i,
node0.neighPattern, occupancy
);
}
}
}
......@@ -603,6 +706,10 @@ class PCCTMC3Decoder3 {
// When not equal to zero, indicates that a count of points is present in
// each geometry octree leaf node.
bool geometryPointsAreUnique;
// Controls the use of neighbour based contextualisation of octree
// occupancy during geometry coding.
bool neighbourContextsEnabled;
};
}
......
......@@ -50,6 +50,7 @@
#include "PCCTMC3Common.h"
#include "ArithmeticCodec.h"
#include "tables.h"
namespace pcc {
struct PCCAttributeEncodeParamaters {
......@@ -64,6 +65,11 @@ struct PCCAttributeEncodeParamaters {
struct PCCTMC3Encoder3Parameters {
double positionQuantizationScale;
bool mergeDuplicatedPoints;
// Controls the use of neighbour based contextualisation of octree
// occupancy during geometry coding.
bool neighbourContextsEnabled;
std::map<std::string, PCCAttributeEncodeParamaters> attributeEncodeParameters;
};
......@@ -615,6 +621,78 @@ class PCCTMC3Encoder3 {
return count;
}
//-------------------------------------------------------------------------
// map the @occupancy pattern bits to take into account symmetries in the
// neighbour configuration @neighPattern.
//
uint8_t
mapGeometryOccupancy(uint8_t occupancy, uint8_t neighPattern)
{
switch (kOccMapRotateZIdFromPatternXY[neighPattern & 15]) {
case 1: occupancy = kOccMapRotateZ090[occupancy]; break;
case 2: occupancy = kOccMapRotateZ180[occupancy]; break;
case 3: occupancy = kOccMapRotateZ270[occupancy]; break;
}
bool flag_ud = (neighPattern & 16) && !(neighPattern & 32);
if (flag_ud) {
occupancy = kOccMapMirrorXY[occupancy];
}
if (kOccMapRotateYIdFromPattern[neighPattern]) {
occupancy = kOccMapRotateY270[occupancy];
}
switch (kOccMapRotateXIdFromPattern[neighPattern]) {
case 1: occupancy = kOccMapRotateX090[occupancy]; break;
case 2: occupancy = kOccMapRotateX270Y180[occupancy]; break;
case 3: occupancy = kOccMapRotateX090Y180[occupancy]; break;
}
return occupancy;
}
//-------------------------------------------------------------------------
// enecode a node's occupancy bits
//
void encodeGeometryOccupancy(
bool neighbourContextsEnabled,
o3dgc::Arithmetic_Codec* arithmeticEncoder,
o3dgc::Adaptive_Bit_Model& ctxSingleChild,
o3dgc::Static_Bit_Model& ctxEquiProb,
o3dgc::Adaptive_Data_Model (&ctxOccupancy)[10],
const PCCOctree3Node& node0,
int occupancy
) {
if (!neighbourContextsEnabled) {
arithmeticEncoder->encode(occupancy, ctxOccupancy[0]);
return;
}
// code occupancy using the neighbour configuration context
// with reduction from 64 states to 10.
int neighPattern = node0.neighPattern;
int neighPattern10 = kNeighPattern64to10[neighPattern];
if (neighPattern10 == 0) {
bool singleChild = !popcntGt1(occupancy);
arithmeticEncoder->encode(singleChild, ctxSingleChild);
if (singleChild) {
// no siblings => encode index = (z,y,x) not 8bit pattern
arithmeticEncoder->encode(!!(occupancy & 0xaa), ctxEquiProb); // z
arithmeticEncoder->encode(!!(occupancy & 0xcc), ctxEquiProb); // y
arithmeticEncoder->encode(!!(occupancy & 0xf0), ctxEquiProb); // x
} else {
arithmeticEncoder->encode(occupancy, ctxOccupancy[0]);
}
}
else {
uint32_t mappedOccupancy = mapGeometryOccupancy(occupancy, neighPattern);
arithmeticEncoder->encode(mappedOccupancy, ctxOccupancy[neighPattern10]);
}
}
//-------------------------------------------------------------------------
int encodePositions(
......@@ -627,11 +705,18 @@ class PCCTMC3Encoder3 {
arithmeticEncoder.set_buffer(uint32_t(bitstream.capacity - bitstream.size),
bitstream.buffer + bitstream.size);
arithmeticEncoder.start_encoder();
o3dgc::Adaptive_Data_Model multiSymbolOccupancyModel0(257);
o3dgc::Static_Bit_Model ctxEquiProb;
o3dgc::Adaptive_Bit_Model ctxSingleChild;
o3dgc::Adaptive_Bit_Model ctxSinglePointPerBlock;
o3dgc::Adaptive_Bit_Model ctxPointCountPerBlock;
// occupancy map model using ten 6-neighbour configurations
o3dgc::Adaptive_Data_Model ctxOccupancy[10];
for (int i = 0; i < 10; i++) {
ctxOccupancy[i].set_alphabet(256);
if (params.neighbourContextsEnabled)
ctxOccupancy[i].reset(kInitCtxOccupancy + 256 * i, true);
}
// init main fifo
// -- worst case size is the last level containing every input poit
......@@ -651,6 +736,7 @@ class PCCTMC3Encoder3 {
node00.start = uint32_t(0);
node00.end = uint32_t(pointCloud.getPointCount());
node00.pos = uint32_t(0);
node00.neighPattern = 0;
fifo.push_back(node00);
size_t processedPointCount = 0;
......@@ -658,10 +744,15 @@ class PCCTMC3Encoder3 {
auto fifoCurrLvlEnd = fifo.end();
// this counter represents fifo.end() - fifoCurrLvlEnd().
// ie, the number of nodes added to the next level of the tree
int numNodesNextLvl = 0;
for (; !fifo.empty(); fifo.pop_front()) {
if (fifo.begin() == fifoCurrLvlEnd) {
// transition to the next level
fifoCurrLvlEnd = fifo.end();
numNodesNextLvl = 0;
nodeSizeLog2--;
}
......@@ -694,7 +785,10 @@ class PCCTMC3Encoder3 {
}
assert(occupancy > 0);
arithmeticEncoder.encode(occupancy, multiSymbolOccupancyModel0);
encodeGeometryOccupancy(
params.neighbourContextsEnabled, &arithmeticEncoder, ctxSingleChild,
ctxEquiProb, ctxOccupancy, node0, occupancy
);
// when nodeSizeLog2 == 1, children are indivisible (ie leaf nodes)
// and are immediately coded. No further splitting occurs.
......@@ -722,7 +816,8 @@ class PCCTMC3Encoder3 {
continue;
}
// nodeSizeLog2 > 1: insert split children into fifo
// nodeSizeLog2 > 1: insert split children into fifo while updating
// neighbour state
int childPointsStartIdx = node0.start;
for (int i = 0; i < 8; i++) {
if (!childCounts[i]) {
......@@ -745,6 +840,15 @@ class PCCTMC3Encoder3 {
child.start = childPointsStartIdx;
childPointsStartIdx += childCounts[i];
child.end = childPointsStartIdx;
// NB: there is no need to update the neighbour state for leaf nodes
numNodesNextLvl++;
if (params.neighbourContextsEnabled) {
updateGeometryNeighState(
fifo.end(), numNodesNextLvl, childSizeLog2, child, i,
node0.neighPattern, occupancy
);
}
}
}
......@@ -766,6 +870,9 @@ class PCCTMC3Encoder3 {
PCCWriteToBuffer<uint8_t>(
uint8_t(params.mergeDuplicatedPoints), bitstream.buffer, bitstream.size);
PCCWriteToBuffer<uint8_t>(
uint8_t(params.neighbourContextsEnabled), bitstream.buffer, bitstream.size);
for (int k = 0; k < 3; ++k) {
PCCWriteToBuffer<double>(minPositions[k], bitstream.buffer, bitstream.size);
}
......
......@@ -165,6 +165,11 @@ bool ParseParameters(int argc, char *argv[], Parameters &params) {
params.roundOutputPositions, false,
"todo(kmammou)")
// tools
("neighbourContextualisation",
params.encodeParameters.neighbourContextsEnabled, true,
"Contextualise geometry octree occupancy based on neighbour patterns")
// attribute processing
// NB: Attribute options are special in the way they are applied (see above)
("attribute",
......@@ -273,6 +278,8 @@ bool ParseParameters(int argc, char *argv[], Parameters &params) {
<< endl;
cout << "\t positionQuantizationScale " << params.encodeParameters.positionQuantizationScale
<< endl;
cout << "\t neighbourContextualisation " << params.encodeParameters.neighbourContextsEnabled
<< endl;
for (const auto & attributeEncodeParameters : params.encodeParameters.attributeEncodeParameters) {
cout << "\t " << attributeEncodeParameters.first << endl;
cout << "\t\t numberOfNearestNeighborsInPrediction "
......
This diff is collapsed.
/* The copyright in this software is being made available under the BSD
* Licence, included below. This software may be subject to other third
* party and contributor rights, including patent rights, and no such
* rights are granted under this licence.
*
* Copyright (c) 2017-2018, ISO/IEC
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
*
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* * Neither the name of the ISO/IEC nor the names of its contributors
* may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#pragma once
#include <cstdint>
namespace pcc {
// Symmetry reduction of 64 neighbour pattern to 10
extern const uint8_t kNeighPattern64to10[64];
// Identifies the X-Y rotation to be performed given a neighbour pattern
// 0 => none
// 1 => X 90° ACW (encoder) [kOccMapRotateX090]
// 1 => X 270° ACW (decoder) [kOccMapRotateX270]
// 2 => X 270° ACW, Y 180° [kOccMapRotateX270Y180]
// 3 => X 90° ACW, Y 180° [kOccMapRotateX090Y180]