Commit 4d0d1e66 authored by Xiang Zhang's avatar Xiang Zhang Committed by David Flynn
Browse files

geom/m49232: octree node geometry quantisation

This introduces a quantization scheme into the octree coding process,
enables adaptive geometry quantization for different regions of the
point cloud.  This in-loop scheme is independent of the any quantisation
performed in non-normative pre-processing at the input to the encoder.

At a particular depth of the octree, the remaining (uncoded) position
bits of each point are quantised according to a per-node (or rather,
per-subtree) QP.  The QP itself is signalled as an offset to a base QP.

The following configuration parameters are added:
  positionQuantisationEnabled
  positionBaseQp
  positionQuantisationOctreeDepth
parent 6b18730b
......@@ -214,6 +214,22 @@ Controls the entropy coding method used for equi-probable (bypass) bins:
Geometry coding
---------------
### `--positionQuantisationEnabled=0|1`
Enables in-loop quantisation and reconstruction of geometry positions.
NB: All in-loop quantisation is independent (and happens after) any
position scaling due to `positionQuantizationScale`.
### `--positionBaseQp=INT-VALUE`
The quantisation parameter used to quantise geometry positions. The
effective QP may be varied according to `positionQuantisationOctreeDepth`.
A QP equal to 4 results in a scale factor of 1.
### `--positionQuantisationOctreeDepth=INT-VALUE`
The depth in the octree at which per-node QP offsets are signalled.
A non-normative encoder process determines the QP offset based upon
the local density of the octree.
### `--bitwiseOccupancyCoding=0|1`
In octree geometry coding, there are both byte-wise and bit-wise tools to
encode the occupancy data. This option selects between the two methods.
......
......@@ -254,6 +254,7 @@ public:
swap(withColors, other.withColors);
swap(withReflectances, other.withReflectances);
swap(withFrameIndex, other.withFrameIndex);
swap(positionsReconstructed, other.positionsReconstructed);
}
Vec3<double> operator[](const size_t index) const
......@@ -296,6 +297,22 @@ public:
assert(index < reflectances.size() && withReflectances);
reflectances[index] = reflectance;
}
Vec3<double> getPositionReconstructed(const size_t index) const
{
assert(index < positionsReconstructed.size());
return positionsReconstructed[index];
}
Vec3<double>& getPositionReconstructed(const size_t index)
{
assert(index < positionsReconstructed.size());
return positionsReconstructed[index];
}
void setPositionReconstructed(const size_t index, const Vec3<double> pos)
{
assert(index < positionsReconstructed.size());
positionsReconstructed[index] = pos;
}
void copyPositions() { positionsReconstructed = positions; }
bool hasReflectances() const { return withReflectances; }
void addReflectances()
......@@ -368,6 +385,7 @@ public:
void resize(const size_t size)
{
positions.resize(size);
positionsReconstructed.resize(size);
if (hasColors()) {
colors.resize(size);
}
......@@ -382,6 +400,8 @@ public:
void reserve(const size_t size)
{
positions.reserve(size);
positionsReconstructed.reserve(size);
if (hasColors()) {
colors.reserve(size);
}
......@@ -398,6 +418,7 @@ public:
colors.clear();
reflectances.clear();
frameidx.clear();
positionsReconstructed.clear();
}
size_t removeDuplicatePointInQuantizedPoint(int minGeomNodeSizeLog2)
......@@ -429,6 +450,9 @@ public:
std::copy(
src.positions.begin(), src.positions.end(),
std::next(positions.begin(), dstEnd));
std::copy(
src.positionsReconstructed.begin(), src.positionsReconstructed.end(),
std::next(positionsReconstructed.begin(), dstEnd));
if (hasColors() && src.hasColors())
std::copy(
......@@ -452,6 +476,8 @@ public:
if (hasReflectances()) {
std::swap(getReflectance(index1), getReflectance(index2));
}
std::swap(
getPositionReconstructed(index1), getPositionReconstructed(index2));
}
Box3<double> computeBoundingBox() const
......@@ -502,6 +528,10 @@ public:
private:
std::vector<Vec3<double>> positions;
// todo(df): remove this
std::vector<Vec3<double>> positionsReconstructed;
std::vector<Vec3<attr_t>> colors;
std::vector<attr_t> reflectances;
std::vector<uint8_t> frameidx;
......
......@@ -61,6 +61,7 @@ struct EncoderAttributeParams {
struct EncoderParams {
SequenceParameterSet sps;
GeometryParameterSet gps;
GeometryBrickHeader gbh;
// NB: information about attributes is split between the SPS and the APS.
// => The SPS enumerates the attributes, the APS controls coding params.
......@@ -108,7 +109,7 @@ public:
private:
void appendReconstructedPoints(PCCPointSet3* reconstructedCloud);
void encodeGeometryBrick(PayloadBuffer* buf);
void encodeGeometryBrick(const EncoderParams*, PayloadBuffer* buf);
PCCPointSet3 quantization(const PCCPointSet3& inputPointCloud);
......
......@@ -543,6 +543,18 @@ ParseParameters(int argc, char* argv[], Parameters& params)
"Size of nodes for surface triangulation.\n"
" 0: disabled\n")
("positionQuantisationEnabled",
params.encoder.gps.geom_scaling_enabled_flag, false,
"Enable in-loop quantisation of positions")
("positionBaseQp",
params.encoder.gps.geom_base_qp, 4,
"Base QP used in position quantisation")
("positionQuantisationOctreeDepth",
params.encoder.gbh.geom_octree_qp_offset_depth, 3,
"Octree depth used for signalling position QP offsets\n")
(po::Section("Attributes"))
// attribute processing
......
......@@ -352,7 +352,7 @@ PCCTMC3Encoder3::compressPartition(
pcc::chrono::Stopwatch<pcc::chrono::utime_inc_children_clock> clock_user;
clock_user.start();
encodeGeometryBrick(&payload);
encodeGeometryBrick(params, &payload);
clock_user.stop();
......@@ -444,7 +444,8 @@ PCCTMC3Encoder3::compressPartition(
//----------------------------------------------------------------------------
void
PCCTMC3Encoder3::encodeGeometryBrick(PayloadBuffer* buf)
PCCTMC3Encoder3::encodeGeometryBrick(
const EncoderParams* params, PayloadBuffer* buf)
{
// todo(df): confirm minimum of 1 isn't needed
int32_t maxBB =
......@@ -462,6 +463,8 @@ PCCTMC3Encoder3::encodeGeometryBrick(PayloadBuffer* buf)
gbh.geom_box_log2_scale = 0;
gbh.geom_max_node_size_log2 = nodeSizeLog2;
gbh.geom_num_points = int(pointCloud.getPointCount());
gbh.geom_octree_qp_offset_enabled_flag = _gps->geom_scaling_enabled_flag;
gbh.geom_octree_qp_offset_depth = params->gbh.geom_octree_qp_offset_depth;
write(*_sps, *_gps, gbh, buf);
// todo(df): remove estimate when arithmetic codec is replaced
......
......@@ -77,6 +77,10 @@ struct PCCOctree3Node {
// The occupancy map used describing the current node and its siblings.
uint8_t siblingOccupancy;
int qp;
Vec3<uint32_t> pos_quant;
Vec3<uint32_t> pos_base;
};
//---------------------------------------------------------------------------
......
......@@ -41,6 +41,7 @@
#include "geometry_intra_pred.h"
#include "io_hls.h"
#include "tables.h"
#include "quantization.h"
namespace pcc {
......@@ -90,6 +91,8 @@ public:
Vec3<uint32_t> decodePointPosition(int nodeSizeLog2);
int decodeQpOffset();
template<class OutputIt>
int decodeDirectPosition(
int nodeSizeLog2, const PCCOctree3Node& node, OutputIt outputPoints);
......@@ -107,6 +110,9 @@ private:
AdaptiveBitModel _ctxPointCountPerBlock;
AdaptiveBitModel _ctxBlockSkipTh;
AdaptiveBitModel _ctxNumIdcmPointsEq1;
AdaptiveBitModel _ctxQpOffsetIsZero;
AdaptiveBitModel _ctxQpOffsetSign;
AdaptiveBitModel _ctxQpOffsetAbsEgl;
// For bitwise occupancy coding
CtxModelOctreeOccupancy _ctxOccupancy;
......@@ -372,6 +378,20 @@ GeometryOctreeDecoder::decodePointPosition(int nodeSizeLog2)
return delta;
}
int
GeometryOctreeDecoder::decodeQpOffset()
{
int dqp = 0;
if (!_arithmeticDecoder->decode(_ctxQpOffsetIsZero)) {
int dqp_sign = _arithmeticDecoder->decode(_ctxQpOffsetSign);
dqp =
_arithmeticDecoder->decodeExpGolomb(0, _ctxEquiProb, _ctxQpOffsetAbsEgl)
+ 1;
dqp = dqp_sign ? dqp : -dqp;
}
return dqp;
}
//-------------------------------------------------------------------------
// Direct coding of position of points in node (early tree termination).
// Decoded points are written to @outputPoints
......@@ -391,10 +411,14 @@ GeometryOctreeDecoder::decodeDirectPosition(
if (_arithmeticDecoder->decode(_ctxNumIdcmPointsEq1))
numPoints++;
QuantizerGeom quantizer(node.qp);
for (int i = 0; i < numPoints; i++) {
// convert node-relative position to world position
Vec3<uint32_t> pos = node.pos + decodePointPosition(nodeSizeLog2);
*(outputPoints++) = {double(pos[0]), double(pos[1]), double(pos[2])};
Vec3<uint32_t> pos = decodePointPosition(nodeSizeLog2);
*(outputPoints++) = {
double(quantizer.scale(node.pos_quant[0] + pos[0]) + node.pos_base[0]),
double(quantizer.scale(node.pos_quant[1] + pos[1]) + node.pos_base[1]),
double(quantizer.scale(node.pos_quant[2] + pos[2]) + node.pos_base[2])};
}
return numPoints;
......@@ -430,6 +454,7 @@ decodeGeometryOctree(
node00.neighPattern = 0;
node00.numSiblingsPlus1 = 8;
node00.siblingOccupancy = 0;
node00.qp = 4;
size_t processedPointCount = 0;
std::vector<uint32_t> values;
......@@ -447,6 +472,10 @@ decodeGeometryOctree(
occupancyAtlas.clear();
}
int numLvlsUntilQpOffset = -1;
if (gbh.geom_octree_qp_offset_enabled_flag)
numLvlsUntilQpOffset = gbh.geom_octree_qp_offset_depth;
for (; !fifo.empty(); fifo.pop_front()) {
if (fifo.begin() == fifoCurrLvlEnd) {
// transition to the next level
......@@ -464,10 +493,22 @@ decodeGeometryOctree(
// allow partial tree decoding
if (nodeSizeLog2 == minNodeSizeLog2)
break;
numLvlsUntilQpOffset--;
}
PCCOctree3Node& node0 = fifo.front();
if (numLvlsUntilQpOffset == 0) {
node0.qp = decoder.decodeQpOffset() + gps.geom_base_qp;
node0.pos_base = node0.pos;
node0.pos_quant = {0, 0, 0};
}
int shiftBits = (node0.qp - 4) / 6;
int effectiveNodeSizeLog2 = nodeSizeLog2 - shiftBits;
int effectiveChildSizeLog2 = effectiveNodeSizeLog2 - 1;
int occupancyAdjacencyGt0 = 0;
int occupancyAdjacencyGt1 = 0;
int occupancyAdjacencyUnocc = 0;
......@@ -491,16 +532,18 @@ decodeGeometryOctree(
int occupancyPrediction = 0;
// generate intra prediction
if (nodeSizeLog2 < gps.intra_pred_max_node_size_log2) {
if (effectiveNodeSizeLog2 < gps.intra_pred_max_node_size_log2) {
predictGeometryOccupancyIntra(
occupancyAtlas, node0.pos, nodeSizeLog2, &occupancyIsPredicted,
&occupancyPrediction);
}
// decode occupancy pattern
uint8_t occupancy = decoder.decodeOccupancy(
node0.neighPattern, occupancyIsPredicted, occupancyPrediction,
occupancyAdjacencyGt0, occupancyAdjacencyGt1, occupancyAdjacencyUnocc);
uint8_t occupancy = 1;
if (effectiveNodeSizeLog2 > 0) {
occupancy = decoder.decodeOccupancy(
node0.neighPattern, occupancyIsPredicted, occupancyPrediction,
occupancyAdjacencyGt0, occupancyAdjacencyGt1, occupancyAdjacencyUnocc);
}
assert(occupancy > 0);
......@@ -529,17 +572,18 @@ decodeGeometryOctree(
// point counts for leaf nodes are coded immediately upon
// encountering the leaf node.
if (childSizeLog2 == 0) {
if (effectiveChildSizeLog2 <= 0) {
int numPoints = 1;
if (!gps.geom_unique_points_flag) {
numPoints = decoder.decodePositionLeafNumPoints();
}
QuantizerGeom quantizer(node0.qp);
const Vec3<double> point(
node0.pos[0] + (x << childSizeLog2),
node0.pos[1] + (y << childSizeLog2),
node0.pos[2] + (z << childSizeLog2));
quantizer.scale(node0.pos_quant[0] + x) + node0.pos_base[0],
quantizer.scale(node0.pos_quant[1] + y) + node0.pos_base[1],
quantizer.scale(node0.pos_quant[2] + z) + node0.pos_base[2]);
for (int i = 0; i < numPoints; ++i)
pointCloud[processedPointCount++] = point;
......@@ -552,6 +596,12 @@ decodeGeometryOctree(
fifo.emplace_back();
auto& child = fifo.back();
child.qp = node0.qp;
child.pos_quant[0] = node0.pos_quant[0] + (x << effectiveChildSizeLog2);
child.pos_quant[1] = node0.pos_quant[1] + (y << effectiveChildSizeLog2);
child.pos_quant[2] = node0.pos_quant[2] + (z << effectiveChildSizeLog2);
child.pos_base = node0.pos_base;
child.pos[0] = node0.pos[0] + (x << childSizeLog2);
child.pos[1] = node0.pos[1] + (y << childSizeLog2);
child.pos[2] = node0.pos[2] + (z << childSizeLog2);
......@@ -559,9 +609,10 @@ decodeGeometryOctree(
child.siblingOccupancy = occupancy;
bool idcmEnabled = gps.inferred_direct_coding_mode_enabled_flag;
if (isDirectModeEligible(idcmEnabled, nodeSizeLog2, node0, child)) {
if (isDirectModeEligible(
idcmEnabled, effectiveNodeSizeLog2, node0, child)) {
int numPoints = decoder.decodeDirectPosition(
childSizeLog2, child, &pointCloud[processedPointCount]);
effectiveChildSizeLog2, child, &pointCloud[processedPointCount]);
processedPointCount += numPoints;
if (numPoints > 0) {
......@@ -584,11 +635,13 @@ decodeGeometryOctree(
}
}
if (minNodeSizeLog2 > 0) {
pointCloud.resize(processedPointCount);
}
// NB: the point cloud needs to be resized if partially decoded
// OR: if geometry quantisation has changed the number of points
// todo(df): this breaks the current definition of geom_num_points
pointCloud.resize(processedPointCount);
// return partial coding result
// todo(df): node.pos is still in quantised form -- this is probably wrong
if (nodesRemaining) {
*nodesRemaining = std::move(fifo);
}
......
......@@ -41,6 +41,9 @@
#include "geometry_intra_pred.h"
#include "io_hls.h"
#include "tables.h"
#include "quantization.h"
#include <set>
namespace pcc {
......@@ -94,6 +97,8 @@ public:
void encodePointPosition(int nodeSizeLog2, const Vec3<uint32_t>& pos);
void encodeQpOffset(int dqp);
bool encodeDirectPosition(
int nodeSizeLog2,
const PCCOctree3Node& node,
......@@ -113,6 +118,10 @@ private:
AdaptiveBitModel _ctxBlockSkipTh;
AdaptiveBitModel _ctxNumIdcmPointsEq1;
AdaptiveBitModel _ctxQpOffsetIsZero;
AdaptiveBitModel _ctxQpOffsetSign;
AdaptiveBitModel _ctxQpOffsetAbsEgl;
// For bitwise occupancy coding
CtxModelOctreeOccupancy _ctxOccupancy;
CtxMapOctreeOccupancy _ctxIdxMaps[18];
......@@ -373,6 +382,108 @@ GeometryOctreeEncoder::encodePointPosition(
//-------------------------------------------------------------------------
// Direct coding of position of points in node (early tree termination).
void
GeometryOctreeEncoder::encodeQpOffset(int dqp)
{
_arithmeticEncoder->encode(dqp == 0, _ctxQpOffsetIsZero);
if (dqp == 0) {
return;
}
_arithmeticEncoder->encode(dqp > 0, _ctxQpOffsetSign);
_arithmeticEncoder->encodeExpGolomb(
abs(dqp) - 1, 0, _ctxEquiProb, _ctxQpOffsetAbsEgl);
}
//-------------------------------------------------------------------------
template<typename It>
void
calculateNodeQps(int baseQp, It nodesBegin, It nodesEnd)
{
// determine delta qp for each node based on the point density
int lowQp = baseQp - 4 >= 4 ? baseQp - 4 : 4;
int mediumQp = baseQp;
int highQp = baseQp + 6;
std::vector<int> numPointsInNode;
std::vector<double> cum_prob;
int32_t numPointsInLvl = 0;
for (auto it = nodesBegin; it != nodesEnd; ++it) {
numPointsInNode.push_back(it->end - it->start);
numPointsInLvl += it->end - it->start;
}
std::sort(numPointsInNode.begin(), numPointsInNode.end());
double cc = 0;
for (auto num : numPointsInNode) {
cc += num;
cum_prob.push_back(cc / numPointsInLvl);
}
int th1 = -1, th2 = -1;
for (int i = 0; i < cum_prob.size(); i++) {
if (th1 == -1 && cum_prob[i] > 0.05) {
th1 = numPointsInNode[i];
} else if (th2 == -1 && cum_prob[i] > 0.6)
th2 = numPointsInNode[i];
}
for (auto it = nodesBegin; it != nodesEnd; ++it) {
if (it->end - it->start < th1) {
it->qp = highQp;
} else if (it->end - it->start < th2)
it->qp = mediumQp;
else
it->qp = lowQp;
}
}
//-------------------------------------------------------------------------
void
geometryQuantization(
PCCPointSet3& pointCloud, PCCOctree3Node& node, int nodeSizeLog2)
{
QuantizerGeom quantizer = QuantizerGeom(node.qp);
int qpShift = (node.qp - 4) / 6;
Vec3<uint32_t> start_pos = node.pos;
Vec3<uint32_t> start_pos_quant = 0;
Vec3<uint32_t> end_pos_quant = (1 << nodeSizeLog2) >> qpShift;
for (int i = node.start; i < node.end; i++) {
Vec3<double> reconPoint, quantizedPoint;
for (int k = 0; k < 3; k++) {
int64_t k_pos = pointCloud[i][k] - start_pos[k];
k_pos = quantizer.quantize(k_pos);
k_pos = PCCClip(k_pos, start_pos_quant[k], end_pos_quant[k] - 1);
pointCloud[i][k] = k_pos;
reconPoint[k] = quantizer.scale(k_pos) + start_pos[k];
}
pointCloud.setPositionReconstructed(i, reconPoint);
}
}
//-------------------------------------------------------------------------
void
checkDuplicatePoints(
PCCPointSet3& pointCloud,
PCCOctree3Node& node,
std::vector<int>& pointIdxToDmIdx)
{
auto first = PCCPointSet3::iterator(&pointCloud, node.start);
auto last = PCCPointSet3::iterator(&pointCloud, node.end);
std::set<Vec3<double>> uniquePointsSet;
for (auto i = first; i != last;) {
if (uniquePointsSet.find(**i) == uniquePointsSet.end()) {
uniquePointsSet.insert(**i);
i++;
} else {
std::iter_swap(i, last - 1);
last--;
pointIdxToDmIdx[--node.end] = -2; // mark as duplicate
}
}
}
//-------------------------------------------------------------------------
bool
GeometryOctreeEncoder::encodeDirectPosition(
......@@ -388,12 +499,11 @@ GeometryOctreeEncoder::encodeDirectPosition(
_arithmeticEncoder->encode(numPoints > 1, _ctxNumIdcmPointsEq1);
for (auto idx = node.start; idx < node.end; idx++) {
// determine the point position relative to box edge
encodePointPosition(
nodeSizeLog2,
Vec3<uint32_t>{int(pointCloud[idx][0]) - node.pos[0],
int(pointCloud[idx][1]) - node.pos[1],
int(pointCloud[idx][2]) - node.pos[2]});
Vec3<uint32_t>{uint32_t(pointCloud[idx][0]),
uint32_t(pointCloud[idx][1]),
uint32_t(pointCloud[idx][2])});
}
return true;
......@@ -425,6 +535,7 @@ encodeGeometryOctree(
node00.neighPattern = 0;
node00.numSiblingsPlus1 = 8;
node00.siblingOccupancy = 0;
node00.qp = 4;
// map of pointCloud idx to DM idx, used to reorder the points
// after coding.
......@@ -450,6 +561,17 @@ encodeGeometryOctree(
}
Vec3<uint32_t> occupancyAtlasOrigin(0xffffffff);
int numLvlsUntilQpOffset = -1;
if (gbh.geom_octree_qp_offset_enabled_flag)
numLvlsUntilQpOffset = gbh.geom_octree_qp_offset_depth;
// applied to the root node, just set the node qp
if (numLvlsUntilQpOffset == 0)
node00.qp = gps.geom_base_qp;
if (gbh.geom_octree_qp_offset_enabled_flag)
pointCloud.copyPositions();
for (; !fifo.empty(); fifo.pop_front()) {
if (fifo.begin() == fifoCurrLvlEnd) {
// transition to the next level
......@@ -463,24 +585,49 @@ encodeGeometryOctree(
// allow partial tree encoding using trisoup
if (nodeSizeLog2 == gps.trisoup_node_size_log2)
break;
// determing a per node QP at the appropriate level
// NB: this has no effect here if geom_octree_qp_offset_depth=0
if (--numLvlsUntilQpOffset == 0)
calculateNodeQps(gps.geom_base_qp, fifo.begin(), fifoCurrLvlEnd);
}
PCCOctree3Node& node0 = fifo.front();
// encode delta qp for each octree block
if (numLvlsUntilQpOffset == 0)
encoder.encodeQpOffset(node0.qp - gps.geom_base_qp);
int shiftBits = (node0.qp - 4) / 6;
int effectiveNodeSizeLog2 = nodeSizeLog2 - shiftBits;
int effectiveChildSizeLog2 = effectiveNodeSizeLog2 - 1;
if (numLvlsUntilQpOffset == 0) {
geometryQuantization(pointCloud, node0, nodeSizeLog2);
if (gps.geom_unique_points_flag)
checkDuplicatePoints(pointCloud, node0, pointIdxToDmIdx);
}
// split the current node into 8 children
// - perform an 8-way counting sort of the current node's points
// - (later) map to child nodes
int childSizeLog2 = nodeSizeLog2 - 1;
std::array<int, 8> childCounts = {};
countingSort(
PCCPointSet3::iterator(&pointCloud, node0.start),
PCCPointSet3::iterator(&pointCloud, node0.end), childCounts,
[=](const PCCPointSet3::Proxy& proxy) {
const auto& point = *proxy;
int bitpos = 1 << childSizeLog2;
return !!(int(point[2]) & bitpos) | (!!(int(point[1]) & bitpos) << 1)
| (!!(int(point[0]) & bitpos) << 2);
});
if (effectiveChildSizeLog2 < 0) {
// quantization step size is larger than the node,
// all points end up in the first child.
childCounts[0] = node0.end - node0.start;
} else {
countingSort(
PCCPointSet3::iterator(&pointCloud, node0.start),
PCCPointSet3::iterator(&pointCloud, node0.end), childCounts,
[=](const PCCPointSet3::Proxy& proxy) {
const auto& point = *proxy;
int bitpos = (1 << childSizeLog2) >> shiftBits;