Commit 32137071 authored by Philip A. Chou's avatar Philip A. Chou Committed by David Flynn
Browse files

trisoup/m43786: initial import of c++ version of trisoup

This commit integrates a c++ trisoup codec, replacing the previous matlab
implementation.

The provided code has been reworked to avoid duplicating code, dead code,
and operate with the current HLS.
parent 780b950b
......@@ -73,6 +73,7 @@ file(GLOB PROJECT_INC_FILES
"constants.h"
"geometry.h"
"geometry_octree.h"
"geometry_trisoup.h"
"hls.h"
"io_hls.h"
"io_tlv.h"
......@@ -98,6 +99,8 @@ file(GLOB PROJECT_CPP_FILES
"geometry_octree.cpp"
"geometry_octree_decoder.cpp"
"geometry_octree_encoder.cpp"
"geometry_trisoup_decoder.cpp"
"geometry_trisoup_encoder.cpp"
"io_hls.cpp"
"io_tlv.cpp"
"osspecific.cpp"
......
......@@ -48,8 +48,8 @@ namespace pcc {
//============================================================================
// Quantise the geometry of a point cloud, retaining unique points only.
// Points in the @src point cloud are translated by @offset, then quantised
// by a multiplicitive @scaleFactor with rounding.
// Points in the @src point cloud are translated by @offset, quantised by a
// multiplicitive @scaleFactor with rounding, then clamped to @clamp.
//
// The destination and source point clouds may be the same object.
//
......@@ -59,6 +59,7 @@ inline void
quantizePositionsUniq(
const float scaleFactor,
const PCCVector3D offset,
const PCCBox3<int32_t> clamp,
const PCCPointSet3& src,
PCCPointSet3* dst)
{
......@@ -70,9 +71,10 @@ quantizePositionsUniq(
const PCCVector3D point = (src[i] + offset) * scaleFactor;
PCCVector3<int32_t> quantizedPoint;
quantizedPoint[0] = int64_t(std::round(point[0]));
quantizedPoint[1] = int64_t(std::round(point[1]));
quantizedPoint[2] = int64_t(std::round(point[2]));
for (int k = 0; k < 3; k++) {
quantizedPoint[k] =
PCCClip(int32_t(std::round(point[k])), clamp.min[k], clamp.max[k]);
}
uniquePoints.insert(quantizedPoint);
}
......@@ -106,6 +108,7 @@ inline void
quantizePositions(
const float scaleFactor,
const PCCVector3D offset,
const PCCBox3<int32_t> clamp,
const PCCPointSet3& src,
PCCPointSet3* dst)
{
......@@ -118,11 +121,17 @@ quantizePositions(
dst->resize(numSrcPoints);
}
PCCBox3D clampD{
{double(clamp.min[0]), double(clamp.min[1]), double(clamp.min[2])},
{double(clamp.max[0]), double(clamp.max[1]), double(clamp.max[2])},
};
for (int i = 0; i < numSrcPoints; ++i) {
const PCCVector3D point = (src[i] + offset) * scaleFactor;
auto& dstPoint = (*dst)[i];
for (int k = 0; k < 3; ++k)
dstPoint[k] = std::round(point[k]);
dstPoint[k] =
PCCClip(std::round(point[k]), clampD.min[k], clampD.max[k]);
}
// don't copy attributes if dst already has them
......@@ -140,6 +149,21 @@ quantizePositions(
}
}
//============================================================================
// Clamp point co-ordinates in @cloud to @bbox, preserving attributes.
inline void
clampVolume(PCCBox3D bbox, PCCPointSet3* cloud)
{
int numSrcPoints = cloud->getPointCount();
for (int i = 0; i < numSrcPoints; ++i) {
auto& point = (*cloud)[i];
for (int k = 0; k < 3; ++k)
point[k] = PCCClip(point[k], bbox.min[k], bbox.max[k]);
}
}
//============================================================================
// Determine colour attribute values from a reference/source point cloud.
// Each point in @target is coloured by:
......
......@@ -78,7 +78,6 @@ public:
private:
int decodeGeometryBrick(const PayloadBuffer& buf);
void decodeAttributeBrick(const PayloadBuffer& buf);
int decodeTrisoup(const PayloadBuffer& buf, PCCPointSet3& pointCloud);
//==========================================================================
......
......@@ -84,8 +84,6 @@ private:
void encodeGeometryBrick(PayloadBuffer* buf);
int encodeTrisoup(bool hasColor, bool hasReflectance, PayloadBuffer* buf);
void computeMinPositions(const PCCPointSet3& inputPointCloud);
void quantization(const PCCPointSet3& inputPointCloud);
......
......@@ -176,8 +176,7 @@ PCCTMC3Decoder3::decodeGeometryBrick(const PayloadBuffer& buf)
decodeGeometryOctree(*_gps, gbh, _currentPointCloud, &arithmeticDecoder);
}
if (_gps->geom_codec_type == GeometryCodecType::kTriSoup) {
if (decodeTrisoup(buf, _currentPointCloud))
return -1;
decodeGeometryTrisoup(*_gps, gbh, _currentPointCloud, &arithmeticDecoder);
}
arithmeticDecoder.stop_decoder();
......@@ -234,71 +233,6 @@ PCCTMC3Decoder3::decodeAttributeBrick(const PayloadBuffer& buf)
std::cout << std::endl;
}
//--------------------------------------------------------------------------
int
PCCTMC3Decoder3::decodeTrisoup(
const PayloadBuffer& buf, PCCPointSet3& pointCloud)
{
assert(buf.type == PayloadType::kGeometryBrick);
// Write out TMC1 geometry bitstream from the converged TMC13 bitstream.
std::ofstream fout("outbin/outbin_0000.bin", std::ios::binary);
if (!fout.is_open()) {
// maybe because directory does not exist; try again...
pcc::mkdir("outbin");
fout.open("outbin/outbin_0000.bin", std::ios::binary);
if (!fout.is_open())
return -1;
}
fout.write(buf.data(), buf.size());
if (!fout) {
return -1;
}
fout.close();
// Decompress geometry with TMC1.
std::string cmd;
cmd = "7z e -aoa -bso0 -ooutbin outbin/outbin_0000.bin";
if (int err = system(cmd.c_str())) {
std::cerr << "Failed (" << err << ") to run :" << cmd << '\n';
return -1;
}
cmd =
"TMC1_geometryDecode"
" -inbin outbin/outbin"
" -outref refinedVerticesDecoded.ply"
" -depth "
+ std::to_string(_gps->trisoup_depth) + " -level "
+ std::to_string(_gps->trisoup_triangle_level)
+ " -format binary_little_endian";
if (int err = system(cmd.c_str())) {
std::cerr << "Failed (" << err << ") to run :" << cmd << '\n';
return -1;
}
cmd =
"TMC1_voxelize"
" -inref refinedVerticesDecoded.ply"
" -outvox quantizedPointCloudDecoded.ply"
" -depth "
+ std::to_string(_gps->trisoup_depth) + " -format binary_little_endian";
if (int err = system(cmd.c_str())) {
std::cerr << "Failed (" << err << ") to run :" << cmd << '\n';
return -1;
}
bool hasColors = pointCloud.hasColors();
bool hasReflectances = pointCloud.hasReflectances();
if (!pointCloud.read("quantizedPointCloudDecoded.ply")) {
std::cerr << "Failed to read quantizedPointCloudDecoded.ply\n";
return -1;
}
pointCloud.addRemoveAttributes(hasColors, hasReflectances);
return 0;
}
//==========================================================================
void
......
......@@ -126,46 +126,17 @@ PCCTMC3Encoder3::compress(
// - encode geometry
// - recolour
if (_gps->geom_codec_type == GeometryCodecType::kOctree) {
quantization(inputPointCloud);
}
if (_gps->geom_codec_type == GeometryCodecType::kTriSoup) {
// todo(?): this ought to be replaced with quantization(...)
if (!inputPointCloud.write("verticesInWorldCoords.ply", true)) {
std::cerr << "Failed to write verticesInWorldCoords.ply\n";
return -1;
}
std::string cmd =
"TMC1_coordinateTransform"
" -inworld verticesInWorldCoords.ply"
" -outframe verticesInFrameCoords.ply"
" -depth "
+ std::to_string(_gps->trisoup_depth) + " -scale "
+ std::to_string(_sps->donotuse_trisoup_int_to_orig_scale)
+ " -format binary_little_endian";
if (int err = system(cmd.c_str())) {
std::cerr << "Failed (" << err << ") to run :" << cmd << '\n';
return -1;
}
}
// The quantization process will determine the bounding box
quantization(inputPointCloud);
// geometry encoding
if (1) {
PayloadBuffer payload(PayloadType::kGeometryBrick);
pcc::chrono::Stopwatch<pcc::chrono::utime_inc_children_clock> clock_user;
clock_user.start();
if (_gps->geom_codec_type == GeometryCodecType::kOctree) {
encodeGeometryBrick(&payload);
}
if (_gps->geom_codec_type == GeometryCodecType::kTriSoup) {
bool hasColor = inputPointCloud.hasColors();
bool hasReflectance = inputPointCloud.hasReflectances();
if (encodeTrisoup(hasColor, hasReflectance, &payload))
return -1;
}
encodeGeometryBrick(&payload);
clock_user.stop();
......@@ -256,6 +227,10 @@ PCCTMC3Encoder3::encodeGeometryBrick(PayloadBuffer* buf)
// the current node dimension (log2) encompasing maxBB
int nodeSizeLog2 = ceillog2(maxBB + 1);
// todo(df): consider removal of trisoup_depth
if (_gps->geom_codec_type == GeometryCodecType::kTriSoup)
nodeSizeLog2 = _gps->trisoup_depth;
GeometryBrickHeader gbh;
gbh.geom_geom_parameter_set_id = _gps->gps_geom_parameter_set_id;
gbh.geomBoxOrigin.x() = int(minPositions.x());
......@@ -274,7 +249,9 @@ PCCTMC3Encoder3::encodeGeometryBrick(PayloadBuffer* buf)
if (_gps->geom_codec_type == GeometryCodecType::kOctree) {
encodeGeometryOctree(*_gps, gbh, pointCloud, &arithmeticEncoder);
}
// todo(df): move trisoup coding here
if (_gps->geom_codec_type == GeometryCodecType::kTriSoup) {
encodeGeometryTrisoup(*_gps, gbh, pointCloud, &arithmeticEncoder);
}
uint32_t dataLen = arithmeticEncoder.stop_encoder();
std::copy_n(arithmeticEncoder.buffer(), dataLen, std::back_inserter(*buf));
......@@ -316,62 +293,6 @@ PCCTMC3Encoder3::reconstructedPointCloud(PCCPointSet3* reconstructedCloud)
//----------------------------------------------------------------------------
int
PCCTMC3Encoder3::encodeTrisoup(
bool hasColor, bool hasReflectance, PayloadBuffer* buf)
{
// todo(?): port TMC1 geometry encoder
// todo(?): fix TMC1 to output where it is told not requiring an extra
// level of guesswork to find the output file.
pcc::mkdir("outbin");
std::string cmd =
"TMC1_geometryEncode"
" -inframe verticesInFrameCoords.ply"
" -outbin outbin"
" -outref refinedVertices.ply"
" -depth "
+ std::to_string(_gps->trisoup_depth) + " -level "
+ std::to_string(_gps->trisoup_triangle_level)
+ " -format binary_little_endian";
if (int err = system(cmd.c_str())) {
std::cerr << "Failed (" << err << ") to run :" << cmd << '\n';
return -1;
}
// todo(?): port interpolator
cmd =
"TMC1_voxelize"
" -inref refinedVertices.ply"
" -outvox voxelizedVertices.ply"
" -depth "
+ std::to_string(_gps->trisoup_depth) + " -format binary_little_endian";
if (int err = system(cmd.c_str())) {
std::cerr << "Failed (" << err << ") to run :" << cmd << '\n';
return -1;
}
// Read in quantizedPointCloud file.
if (!pointCloud.read("voxelizedVertices.ply")) {
std::cerr << "Failed to open voxelizedVertices.ply\n";
return -1;
}
pointCloud.addRemoveAttributes(hasColor, hasReflectance);
// encapsulate the TMC1 "bitstream"
std::ifstream fin("outbin/outbin_0000.bin", std::ios::binary);
if (!fin.is_open()) {
std::cerr << "failed to open tmc1 bitstream\n";
return -1;
}
std::copy(
std::istreambuf_iterator<char>(fin), std::istreambuf_iterator<char>(),
std::back_inserter(*buf));
return 0;
}
//----------------------------------------------------------------------------
void
PCCTMC3Encoder3::computeMinPositions(const PCCPointSet3& inputPointCloud)
{
......@@ -398,14 +319,25 @@ PCCTMC3Encoder3::quantization(const PCCPointSet3& inputPointCloud)
if (_gps->geom_codec_type == GeometryCodecType::kOctree)
computeMinPositions(inputPointCloud);
PCCBox3<int32_t> clampBox{{0, 0, 0}, {INT32_MAX, INT32_MAX, INT32_MAX}};
if (_gps->geom_codec_type == GeometryCodecType::kTriSoup) {
// NB: Since trisoup forces the octree root node size, and the
// quantiser above rounds half away from zero it is possible that
// an input ranged [0,2**n) becomes [0,2**m], requiring an octree
// root node size of 2**(m+1).
// todo(??): consider truncation towards zero in quantisation.
int32_t maxval = (1 << _gps->trisoup_depth) - 1;
clampBox = PCCBox3<int32_t>{{0, 0, 0}, {maxval, maxval, maxval}};
}
if (_gps->geom_unique_points_flag) {
quantizePositionsUniq(
_sps->seq_source_geom_scale_factor, -minPositions, inputPointCloud,
&pointCloud);
_sps->seq_source_geom_scale_factor, -minPositions, clampBox,
inputPointCloud, &pointCloud);
} else {
quantizePositions(
_sps->seq_source_geom_scale_factor, -minPositions, inputPointCloud,
&pointCloud);
_sps->seq_source_geom_scale_factor, -minPositions, clampBox,
inputPointCloud, &pointCloud);
}
const size_t pointCount = pointCloud.getPointCount();
......
......@@ -55,6 +55,20 @@ void decodeGeometryOctree(
PCCPointSet3& pointCloud,
o3dgc::Arithmetic_Codec* arithmeticDecoder);
//----------------------------------------------------------------------------
void encodeGeometryTrisoup(
const GeometryParameterSet& gps,
const GeometryBrickHeader& gbh,
PCCPointSet3& pointCloud,
o3dgc::Arithmetic_Codec* arithmeticEncoder);
void decodeGeometryTrisoup(
const GeometryParameterSet& gps,
const GeometryBrickHeader& gbh,
PCCPointSet3& pointCloud,
o3dgc::Arithmetic_Codec* arithmeticDecoder);
//============================================================================
} // namespace pcc
......@@ -39,6 +39,8 @@
#include "ArithmeticCodec.h"
#include "PCCMath.h"
#include "PCCPointSet.h"
#include "hls.h"
#include "ringbuf.h"
namespace pcc {
......@@ -91,6 +93,23 @@ void updateGeometryNeighState(
uint8_t neighPattern,
uint8_t parentOccupancy);
//---------------------------------------------------------------------------
// :: octree encoder exposing internal ringbuffer
void encodeGeometryOctree(
const GeometryParameterSet& gps,
const GeometryBrickHeader& gbh,
PCCPointSet3& pointCloud,
o3dgc::Arithmetic_Codec* arithmeticEncoder,
pcc::ringbuf<PCCOctree3Node>* nodesRemaining);
void decodeGeometryOctree(
const GeometryParameterSet& gps,
const GeometryBrickHeader& gbh,
PCCPointSet3& pointCloud,
o3dgc::Arithmetic_Codec* arithmeticDecoder,
pcc::ringbuf<PCCOctree3Node>* nodesRemaining);
//---------------------------------------------------------------------------
// Determine if direct coding is permitted.
// If tool is enabled:
......
......@@ -254,7 +254,8 @@ decodeGeometryOctree(
const GeometryParameterSet& gps,
const GeometryBrickHeader& gbh,
PCCPointSet3& pointCloud,
o3dgc::Arithmetic_Codec* arithmeticDecoder)
o3dgc::Arithmetic_Codec* arithmeticDecoder,
pcc::ringbuf<PCCOctree3Node>* nodesRemaining)
{
GeometryOctreeDecoder decoder(arithmeticDecoder);
......@@ -266,6 +267,11 @@ decodeGeometryOctree(
// the current node dimension (log2)
int nodeSizeLog2 = gbh.geom_max_node_size_log2;
// termination for trisoup
int terminalNodeSizeLog2 = 0;
if (gps.geom_codec_type == GeometryCodecType::kTriSoup)
terminalNodeSizeLog2 = gps.trisoup_depth - gps.trisoup_triangle_level;
// push the first node
fifo.emplace_back();
PCCOctree3Node& node00 = fifo.back();
......@@ -299,7 +305,12 @@ decodeGeometryOctree(
nodeSizeLog2--;
numNodesNextLvl = 0;
occupancyAtlasOrigin = 0xffffffff;
// allow partial tree encoding using trisoup
if (nodeSizeLog2 == terminalNodeSizeLog2)
break;
}
PCCOctree3Node& node0 = fifo.front();
if (gps.neighbour_avail_boundary_log2) {
......@@ -389,6 +400,23 @@ decodeGeometryOctree(
}
}
}
// return partial coding result
if (nodesRemaining) {
*nodesRemaining = std::move(fifo);
}
}
//-------------------------------------------------------------------------
void
decodeGeometryOctree(
const GeometryParameterSet& gps,
const GeometryBrickHeader& gbh,
PCCPointSet3& pointCloud,
o3dgc::Arithmetic_Codec* arithmeticDecoder)
{
decodeGeometryOctree(gps, gbh, pointCloud, arithmeticDecoder, nullptr);
}
//============================================================================
......
......@@ -250,7 +250,8 @@ encodeGeometryOctree(
const GeometryParameterSet& gps,
const GeometryBrickHeader& gbh,
PCCPointSet3& pointCloud,
o3dgc::Arithmetic_Codec* arithmeticEncoder)
o3dgc::Arithmetic_Codec* arithmeticEncoder,
pcc::ringbuf<PCCOctree3Node>* nodesRemaining)
{
GeometryOctreeEncoder encoder(arithmeticEncoder);
......@@ -282,6 +283,11 @@ encodeGeometryOctree(
// the initial node size is the root node's
int nodeSizeLog2 = gbh.geom_max_node_size_log2;
// termination for trisoup
int terminalNodeSizeLog2 = 0;
if (gps.geom_codec_type == GeometryCodecType::kTriSoup)
terminalNodeSizeLog2 = gps.trisoup_depth - gps.trisoup_triangle_level;
// this counter represents fifo.end() - fifoCurrLvlEnd().
// ie, the number of nodes added to the next level of the tree
int numNodesNextLvl = 0;
......@@ -300,6 +306,10 @@ encodeGeometryOctree(
numNodesNextLvl = 0;
occupancyAtlasOrigin = 0xffffffff;
nodeSizeLog2--;
// allow partial tree encoding using trisoup
if (nodeSizeLog2 == terminalNodeSizeLog2)
break;
}
PCCOctree3Node& node0 = fifo.front();
......@@ -428,6 +438,12 @@ encodeGeometryOctree(
}
}
// return partial coding result
if (nodesRemaining) {
*nodesRemaining = std::move(fifo);
return;
}
////
// The following is to re-order the points according in the decoding
// order since IDCM causes leaves to be coded earlier than they
......@@ -457,4 +473,16 @@ encodeGeometryOctree(
//============================================================================
void
encodeGeometryOctree(
const GeometryParameterSet& gps,
const GeometryBrickHeader& gbh,
PCCPointSet3& pointCloud,
o3dgc::Arithmetic_Codec* arithmeticEncoder)
{
encodeGeometryOctree(gps, gbh, pointCloud, arithmeticEncoder, nullptr);
}
//============================================================================
} // namespace pcc
/* 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>
#include <vector>
#include "PCCPointSet.h"
#include "geometry_octree.h"
#include "ringbuf.h"
namespace pcc {
//============================================================================
void determineTrisoupVertices(
const ringbuf<PCCOctree3Node>& leaves,
std::vector<bool>& segind,
std::vector<uint8_t>& vertices,
const PCCPointSet3& pointCloud,
const int defaultBlockWidth);
void decodeTrisoupCommon(
const ringbuf<PCCOctree3Node>& leaves,
const std::vector<bool>& segind,
const std::vector<uint8_t>& vertices,
PCCPointSet3& pointCloud,
const int defaultBlockWidth);
//============================================================================
struct TrisoupSegment {
PCCVector3<uint32_t> startpos; // start point of edge segment
PCCVector3<uint32_t> endpos; // end point of edge segment
int index; // index of segment, to reorder after sorting
int uniqueIndex; // index of uniqueSegment
int vertex; // distance along segment for intersection (else -1)
};
struct TrisoupSegmentEnc : public TrisoupSegment {
TrisoupSegmentEnc(
const PCCVector3<uint32_t>& startpos,
const PCCVector3<uint32_t>& endpos,
int index,
int uniqueIndex,
int vertex,
int count,