Skip to content

Commit

Permalink
Merge branch 'depth_rvl_compression' of https://github.com/borongyuan…
Browse files Browse the repository at this point in the history
…/rtabmap into borongyuan-depth_rvl_compression
  • Loading branch information
matlabbe committed Dec 15, 2024
2 parents 97c5636 + 07db741 commit d38f4c2
Show file tree
Hide file tree
Showing 10 changed files with 254 additions and 32 deletions.
1 change: 1 addition & 0 deletions corelib/include/rtabmap/core/Compression.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

#include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines

#include <rtabmap/core/rvl_codec.h>
#include <rtabmap/utilite/UThread.h>
#include <opencv2/opencv.hpp>

Expand Down
1 change: 1 addition & 0 deletions corelib/include/rtabmap/core/Memory.h
Original file line number Diff line number Diff line change
Expand Up @@ -303,6 +303,7 @@ class RTABMAP_CORE_EXPORT Memory
bool _notLinkedNodesKeptInDb;
bool _saveIntermediateNodeData;
std::string _rgbCompressionFormat;
std::string _depthCompressionFormat;
bool _incrementalMemory;
bool _localizationDataSaved;
bool _reduceGraph;
Expand Down
1 change: 1 addition & 0 deletions corelib/include/rtabmap/core/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -209,6 +209,7 @@ class RTABMAP_CORE_EXPORT Parameters
RTABMAP_PARAM(Mem, NotLinkedNodesKept, bool, true, "Keep not linked nodes in db (rehearsed nodes and deleted nodes).");
RTABMAP_PARAM(Mem, IntermediateNodeDataKept, bool, false, "Keep intermediate node data in db.");
RTABMAP_PARAM_STR(Mem, ImageCompressionFormat, ".jpg", "RGB image compression format. It should be \".jpg\" or \".png\".");
RTABMAP_PARAM_STR(Mem, DepthCompressionFormat, ".rvl", "Depth image compression format. It should be \".png\" or \".rvl\".");
RTABMAP_PARAM(Mem, STMSize, unsigned int, 10, "Short-term memory size.");
RTABMAP_PARAM(Mem, IncrementalMemory, bool, true, "SLAM mode, otherwise it is Localization mode.");
RTABMAP_PARAM(Mem, LocalizationDataSaved, bool, false, uFormat("Save localization data during localization session (when %s=false). When enabled, the database will then also grow in localization mode. This mode would be used only for debugging purpose.", kMemIncrementalMemory().c_str()).c_str());
Expand Down
37 changes: 37 additions & 0 deletions corelib/include/rtabmap/core/rvl_codec.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
// The following code is a C++ wrapper of the code presented by
// Andrew D. Wilson in "Fast Lossless Depth Image Compression" at SIGCHI'17.
// The original code is licensed under the MIT License.

#ifndef RVL_CODEC_H_
#define RVL_CODEC_H_

#include <cstdint>
#include "rtabmap/core/rtabmap_core_export.h"

namespace rtabmap
{

class RTABMAP_CORE_EXPORT RvlCodec {
public:
RvlCodec();
// Compress input data into output. The size of output can be equal to (1.5 * numPixels + 4) in the worst case.
int CompressRVL(const uint16_t * input, unsigned char * output, int numPixels);
// Decompress input data into output. The size of output must be equal to numPixels.
void DecompressRVL(const unsigned char * input, uint16_t * output, int numPixels);

private:
RvlCodec(const RvlCodec &);
RvlCodec & operator=(const RvlCodec &);

void EncodeVLE(int value);
int DecodeVLE();

int *buffer_;
int *pBuffer_;
int word_;
int nibblesWritten_;
};

} // namespace rtabmap

#endif // RVL_CODEC_H_
2 changes: 2 additions & 0 deletions corelib/src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,8 @@ SET(SRC_FILES
util3d_correspondences.cpp
util3d_motion_estimation.cpp

rvl_codec.cpp

SensorData.cpp
Graph.cpp
Compression.cpp
Expand Down
84 changes: 64 additions & 20 deletions corelib/src/Compression.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,14 +34,14 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

namespace rtabmap {

// format : ".png" ".jpg" "" (empty is general)
// format : ".jpg" ".png" ".rvl" "" (empty is general)
CompressionThread::CompressionThread(const cv::Mat & mat, const std::string & format) :
uncompressedData_(mat),
format_(format),
image_(!format.empty()),
compressMode_(true)
{
UASSERT(format.empty() || format.compare(".png") == 0 || format.compare(".jpg") == 0);
UASSERT(format.empty() || format.compare(".jpg") == 0 || format.compare(".png") == 0 || format.compare(".rvl") == 0);
}
// assume image
CompressionThread::CompressionThread(const cv::Mat & bytes, bool isImage) :
Expand Down Expand Up @@ -96,7 +96,7 @@ void CompressionThread::mainLoop()
this->kill();
}

// ".png" or ".jpg"
// ".jpg" or ".png" or ".rvl"
std::vector<unsigned char> compressImage(const cv::Mat & image, const std::string & format)
{
std::vector<unsigned char> bytes;
Expand All @@ -108,6 +108,20 @@ std::vector<unsigned char> compressImage(const cv::Mat & image, const std::strin
cv::Mat bgra(image.size(), CV_8UC4, image.data);
cv::imencode(format, bgra, bytes);
}
else if(format == ".rvl")
{
bytes = {'D', 'E', 'P', 'T', 'H', 'R', 'V', 'L'};
int numPixels = image.rows * image.cols;
// In the worst case, RVL compression results in ~1.5x larger data.
bytes.resize(3 * numPixels + 20);
uint32_t cols = image.cols;
uint32_t rows = image.rows;
memcpy(&bytes[8], &cols, 4);
memcpy(&bytes[12], &rows, 4);
RvlCodec rvl;
int compressedSize = rvl.CompressRVL(image.ptr<uint16_t>(), &bytes[16], numPixels);
bytes.resize(16 + compressedSize);
}
else
{
cv::imencode(format, image, bytes);
Expand All @@ -116,7 +130,7 @@ std::vector<unsigned char> compressImage(const cv::Mat & image, const std::strin
return bytes;
}

// ".png" or ".jpg"
// ".jpg" or ".png" or ".rvl"
cv::Mat compressImage2(const cv::Mat & image, const std::string & format)
{
std::vector<unsigned char> bytes = compressImage(image, format);
Expand All @@ -129,39 +143,69 @@ cv::Mat compressImage2(const cv::Mat & image, const std::string & format)

cv::Mat uncompressImage(const cv::Mat & bytes)
{
cv::Mat image;
cv::Mat image;
if(!bytes.empty())
{
size_t maxlen = std::min(bytes.rows * bytes.cols * bytes.elemSize(), size_t(8));
std::vector<unsigned char> signature(maxlen);
memcpy(&signature[0], bytes.data, maxlen);
if (std::string(signature.begin(), signature.end()) == "DEPTHRVL")
{
uint32_t cols, rows;
memcpy(&cols, &bytes.data[8], 4);
memcpy(&rows, &bytes.data[12], 4);
image = cv::Mat(rows, cols, CV_16UC1);
RvlCodec rvl;
rvl.DecompressRVL(&bytes.data[16], image.ptr<uint16_t>(), cols * rows);
}
else
{
#if CV_MAJOR_VERSION>2 || (CV_MAJOR_VERSION >=2 && CV_MINOR_VERSION >=4)
image = cv::imdecode(bytes, cv::IMREAD_UNCHANGED);
image = cv::imdecode(bytes, cv::IMREAD_UNCHANGED);
#else
image = cv::imdecode(bytes, -1);
image = cv::imdecode(bytes, -1);
#endif
if(image.type() == CV_8UC4)
{
// Using clone() or copyTo() caused a memory leak !?!?
// image = cv::Mat(image.size(), CV_32FC1, image.data).clone();
cv::Mat depth(image.size(), CV_32FC1);
memcpy(depth.data, image.data, image.total()*image.elemSize());
image = depth;
if(image.type() == CV_8UC4)
{
// Using clone() or copyTo() caused a memory leak !?!?
// image = cv::Mat(image.size(), CV_32FC1, image.data).clone();
cv::Mat depth(image.size(), CV_32FC1);
memcpy(depth.data, image.data, image.total()*image.elemSize());
image = depth;
}
}
}
return image;
}

cv::Mat uncompressImage(const std::vector<unsigned char> & bytes)
{
cv::Mat image;
cv::Mat image;
if(bytes.size())
{
size_t maxlen = std::min(bytes.size(), size_t(8));
std::vector<unsigned char> signature(maxlen);
memcpy(&signature[0], &bytes, maxlen);
if (std::string(signature.begin(), signature.end()) == "DEPTHRVL")
{
uint32_t cols, rows;
memcpy(&cols, &bytes[8], 4);
memcpy(&rows, &bytes[12], 4);
image = cv::Mat(rows, cols, CV_16UC1);
RvlCodec rvl;
rvl.DecompressRVL(&bytes[16], image.ptr<uint16_t>(), cols * rows);
}
else
{
#if CV_MAJOR_VERSION>2 || (CV_MAJOR_VERSION >=2 && CV_MINOR_VERSION >=4)
image = cv::imdecode(bytes, cv::IMREAD_UNCHANGED);
image = cv::imdecode(bytes, cv::IMREAD_UNCHANGED);
#else
image = cv::imdecode(bytes, -1);
image = cv::imdecode(bytes, -1);
#endif
if(image.type() == CV_8UC4)
{
image = cv::Mat(image.size(), CV_32FC1, image.data).clone();
if(image.type() == CV_8UC4)
{
image = cv::Mat(image.size(), CV_32FC1, image.data).clone();
}
}
}
return image;
Expand Down
23 changes: 20 additions & 3 deletions corelib/src/Memory.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,6 +80,7 @@ Memory::Memory(const ParametersMap & parameters) :
_notLinkedNodesKeptInDb(Parameters::defaultMemNotLinkedNodesKept()),
_saveIntermediateNodeData(Parameters::defaultMemIntermediateNodeDataKept()),
_rgbCompressionFormat(Parameters::defaultMemImageCompressionFormat()),
_depthCompressionFormat(Parameters::defaultMemDepthCompressionFormat()),
_incrementalMemory(Parameters::defaultMemIncrementalMemory()),
_localizationDataSaved(Parameters::defaultMemLocalizationDataSaved()),
_reduceGraph(Parameters::defaultMemReduceGraph()),
Expand Down Expand Up @@ -568,6 +569,7 @@ void Memory::parseParameters(const ParametersMap & parameters)
Parameters::parse(params, Parameters::kMemNotLinkedNodesKept(), _notLinkedNodesKeptInDb);
Parameters::parse(params, Parameters::kMemIntermediateNodeDataKept(), _saveIntermediateNodeData);
Parameters::parse(params, Parameters::kMemImageCompressionFormat(), _rgbCompressionFormat);
Parameters::parse(params, Parameters::kMemDepthCompressionFormat(), _depthCompressionFormat);
Parameters::parse(params, Parameters::kMemRehearsalIdUpdatedToNewOne(), _idUpdatedToNewOneRehearsal);
Parameters::parse(params, Parameters::kMemGenerateIds(), _generateIds);
Parameters::parse(params, Parameters::kMemBadSignaturesIgnored(), _badSignaturesIgnored);
Expand Down Expand Up @@ -828,6 +830,16 @@ void Memory::parseParameters(const ParametersMap & parameters)
uInsert(parameters_, ParametersPair(Parameters::kMemUseOdomFeatures(), "false"));
}
}

if(!_saveDepth16Format && _depthCompressionFormat == ".rvl")
{
UWARN("%s is disabled, but %s=.rvl only supports 16 bits depth format. Enabling %s...",
Parameters::kMemSaveDepth16Format().c_str(),
Parameters::kMemDepthCompressionFormat().c_str(),
Parameters::kMemSaveDepth16Format().c_str());
_saveDepth16Format = true;
uInsert(parameters_, ParametersPair(Parameters::kMemSaveDepth16Format(), "true"));
}
}

void Memory::preUpdate()
Expand Down Expand Up @@ -5810,7 +5822,12 @@ Signature * Memory::createSignature(const SensorData & inputData, const Transfor

if(_saveDepth16Format && !depthOrRightImage.empty() && depthOrRightImage.type() == CV_32FC1)
{
UWARN("Save depth data to 16 bits format: depth type detected is 32FC1, use 16UC1 depth format to avoid this conversion (or set parameter \"Mem/SaveDepth16Format\"=false to use 32bits format).");
static bool warned = false;
if(!warned)
{
UWARN("Save depth data to 16 bits format: depth type detected is 32FC1, use 16UC1 depth format to avoid this conversion (or set parameter \"Mem/SaveDepth16Format\"=false to use 32bits format).");
warned = true;
}
depthOrRightImage = util2d::cvtDepthFromFloat(depthOrRightImage);
}

Expand All @@ -5821,7 +5838,7 @@ Signature * Memory::createSignature(const SensorData & inputData, const Transfor
if(_compressionParallelized)
{
rtabmap::CompressionThread ctImage(image, _rgbCompressionFormat);
rtabmap::CompressionThread ctDepth(depthOrRightImage, depthOrRightImage.type() == CV_32FC1 || depthOrRightImage.type() == CV_16UC1?std::string(".png"):_rgbCompressionFormat);
rtabmap::CompressionThread ctDepth(depthOrRightImage, depthOrRightImage.type() == CV_32FC1 || depthOrRightImage.type() == CV_16UC1?_depthCompressionFormat:_rgbCompressionFormat);
rtabmap::CompressionThread ctLaserScan(laserScan.data());
rtabmap::CompressionThread ctUserData(data.userDataRaw());
if(!image.empty())
Expand Down Expand Up @@ -5853,7 +5870,7 @@ Signature * Memory::createSignature(const SensorData & inputData, const Transfor
else
{
compressedImage = compressImage2(image, _rgbCompressionFormat);
compressedDepth = compressImage2(depthOrRightImage, depthOrRightImage.type() == CV_32FC1 || depthOrRightImage.type() == CV_16UC1?std::string(".png"):_rgbCompressionFormat);
compressedDepth = compressImage2(depthOrRightImage, depthOrRightImage.type() == CV_32FC1 || depthOrRightImage.type() == CV_16UC1?_depthCompressionFormat:_rgbCompressionFormat);
compressedScan = compressData2(laserScan.data());
compressedUserData = compressData2(data.userDataRaw());
}
Expand Down
102 changes: 102 additions & 0 deletions corelib/src/rvl_codec.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,102 @@
// The following code is a C++ wrapper of the code presented by
// Andrew D. Wilson in "Fast Lossless Depth Image Compression" at SIGCHI'17.
// The original code is licensed under the MIT License.

#include <rtabmap/core/rvl_codec.h>

namespace rtabmap
{

RvlCodec::RvlCodec() {}

void RvlCodec::EncodeVLE(int value)
{
do
{
int nibble = value & 0x7; // lower 3 bits
if (value >>= 3)
nibble |= 0x8; // more to come
word_ <<= 4;
word_ |= nibble;
if (++nibblesWritten_ == 8) // output word
{
*pBuffer_++ = word_;
nibblesWritten_ = 0;
word_ = 0;
}
} while (value);
}

int RvlCodec::DecodeVLE()
{
unsigned int nibble;
int value = 0, bits = 29;
do
{
if (!nibblesWritten_)
{
word_ = *pBuffer_++; // load word
nibblesWritten_ = 8;
}
nibble = word_ & 0xf0000000;
value |= (nibble << 1) >> bits;
word_ <<= 4;
nibblesWritten_--;
bits -= 3;
} while (nibble & 0x80000000);
return value;
}

int RvlCodec::CompressRVL(const uint16_t * input, unsigned char * output, int numPixels)
{
buffer_ = pBuffer_ = reinterpret_cast<int *>(output);
nibblesWritten_ = 0;
const uint16_t * end = input + numPixels;
uint16_t previous = 0;
while (input != end)
{
int zeros = 0, nonzeros = 0;
for (; (input != end) && !*input; input++, zeros++) {}
EncodeVLE(zeros); // number of zeros
for (const uint16_t * p = input; (p != end) && *p++; nonzeros++) {}
EncodeVLE(nonzeros); // number of nonzeros
for (int i = 0; i < nonzeros; i++)
{
uint16_t current = *input++;
int delta = current - previous;
int positive = (delta << 1) ^ (delta >> 31);
EncodeVLE(positive); // nonzero value
previous = current;
}
}
if (nibblesWritten_) // last few values
*pBuffer_++ = word_ << 4 * (8 - nibblesWritten_);
return static_cast<int>((unsigned char *)pBuffer_ - (unsigned char *)buffer_); // num bytes
}

void RvlCodec::DecompressRVL(const unsigned char * input, uint16_t * output, int numPixels)
{
buffer_ = pBuffer_ = const_cast<int *>(reinterpret_cast<const int *>(input));
nibblesWritten_ = 0;
uint16_t current, previous = 0;
int numPixelsToDecode = numPixels;
while (numPixelsToDecode)
{
int zeros = DecodeVLE(); // number of zeros
numPixelsToDecode -= zeros;
for (; zeros; zeros--)
*output++ = 0;
int nonzeros = DecodeVLE(); // number of nonzeros
numPixelsToDecode -= nonzeros;
for (; nonzeros; nonzeros--)
{
int positive = DecodeVLE(); // nonzero value
int delta = (positive >> 1) ^ -(positive & 1);
current = previous + delta;
*output++ = current;
previous = current;
}
}
}

} // namespace rtabmap
1 change: 1 addition & 0 deletions guilib/src/PreferencesDialog.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -995,6 +995,7 @@ PreferencesDialog::PreferencesDialog(QWidget * parent) :
_ui->general_checkBox_keepBinaryData->setObjectName(Parameters::kMemBinDataKept().c_str());
_ui->general_checkBox_saveIntermediateNodeData->setObjectName(Parameters::kMemIntermediateNodeDataKept().c_str());
_ui->lineEdit_rgbCompressionFormat->setObjectName(Parameters::kMemImageCompressionFormat().c_str());
_ui->lineEdit_depthCompressionFormat->setObjectName(Parameters::kMemDepthCompressionFormat().c_str());
_ui->general_checkBox_keepDescriptors->setObjectName(Parameters::kMemRawDescriptorsKept().c_str());
_ui->general_checkBox_saveDepth16bits->setObjectName(Parameters::kMemSaveDepth16Format().c_str());
_ui->general_checkBox_compressionParallelized->setObjectName(Parameters::kMemCompressionParallelized().c_str());
Expand Down
Loading

0 comments on commit d38f4c2

Please sign in to comment.