compressed_depth_codec.h
Go to the documentation of this file.
1 #pragma once
2 
3 // SPDX-License-Identifier: BSD-3-Clause
4 // SPDX-FileCopyrightText: Czech Technical University in Prague
5 
13 #include <memory>
14 #include <string>
15 #include <vector>
16 
17 #include <dynamic_reconfigure/Config.h>
18 #include <sensor_msgs/CompressedImage.h>
19 #include <sensor_msgs/Image.h>
20 
21 #include <compressed_depth_image_transport/CompressedDepthPublisherConfig.h>
23 
24 #include <cras_cpp_common/c_api.h>
28 #include <cras_cpp_common/span.hpp>
30 
31 namespace cv
32 {
33 class Mat;
34 }
35 
36 namespace image_transport_codecs
37 {
38 
59 {
60 public:
62  typedef cras::expected<sensor_msgs::CompressedImage, std::string> EncodeResult;
63 
68  explicit CompressedDepthCodec(const cras::LogHelperPtr& logHelper = std::make_shared<cras::NodeLogHelper>());
69 
70  ~CompressedDepthCodec() override;
71 
79  EncodeResult encode(const sensor_msgs::Image& raw,
80  const compressed_depth_image_transport::CompressedDepthPublisherConfig& config) const;
81 
88  ImageTransportCodec::DecodeResult decode(const sensor_msgs::CompressedImage& compressed) const;
89 
90  std::string getTransportName() const override;
91 
92  ImageTransportCodec::EncodeResult encode(const sensor_msgs::Image& raw,
93  const dynamic_reconfigure::Config& config) const override;
94 
96  const dynamic_reconfigure::Config& config) const override;
97 
99  const topic_tools::ShapeShifter& compressed, const std::string& matchFormat) const override;
100 
109  const sensor_msgs::CompressedImage& compressed, const std::string& matchFormat) const;
110 
118  const sensor_msgs::CompressedImage& compressed) const;
119 
125  ImageTransportCodec::DecodeResult decodeCompressedDepthImage(const sensor_msgs::CompressedImage& compressed) const;
126 
136  EncodeResult encodeCompressedDepthImage(const sensor_msgs::Image& raw, const std::string& compression_format,
137  double depth_max, double depth_quantization, int png_level) const;
138 
144  cv::Mat decodeRVL(const std::vector<uint8_t>& compressed) const;
145 
151  void encodeRVL(const cv::Mat& depthImg16UC1, std::vector<uint8_t>& compressed) const;
152 
159  cv::Mat fromInvDepth(const cv::Mat& invDepthImg,
160  const compressed_depth_image_transport::ConfigHeader& compressionConfig) const;
161 
171  cv::Mat toInvDepth(const cv::Mat& depthImg, double depth_max, double depth_quantization,
172  compressed_depth_image_transport::ConfigHeader& compressionConfig) const;
173 };
174 
175 }
176 
177 // //////////
178 // C API ///
179 // //////////
180 
208 extern "C" bool compressedDepthCodecEncode(
209  sensor_msgs::Image::_height_type rawHeight,
210  sensor_msgs::Image::_width_type rawWidth,
211  const char* rawEncoding,
212  sensor_msgs::Image::_is_bigendian_type rawIsBigEndian,
213  sensor_msgs::Image::_step_type rawStep,
214  size_t rawDataLength,
215  const uint8_t rawData[],
216  cras::allocator_t compressedFormatAllocator,
217  cras::allocator_t compressedDataAllocator,
218 #if COMPRESSED_DEPTH_HAS_RVL == 1
219  const char* configFormat,
220 #endif
221  double configDepthMax,
222  double configDepthQuantization,
223  int configPngLevel,
224  cras::allocator_t errorStringAllocator,
225  cras::allocator_t logMessagesAllocator
226 );
227 
251 extern "C" bool compressedDepthCodecDecode(
252  const char* compressedFormat,
253  size_t compressedDataLength,
254  const uint8_t compressedData[],
255  sensor_msgs::Image::_height_type& rawHeight,
256  sensor_msgs::Image::_width_type& rawWidth,
257  cras::allocator_t rawEncodingAllocator,
258  sensor_msgs::Image::_is_bigendian_type& rawIsBigEndian,
259  sensor_msgs::Image::_step_type& rawStep,
260  cras::allocator_t rawDataAllocator,
261  cras::allocator_t errorStringAllocator,
262  cras::allocator_t logMessagesAllocator
263 );
264 
269 extern "C" bool compressed_depth_codec_has_rvl();
image_transport_codecs::CompressedDepthCodec::toInvDepth
cv::Mat toInvDepth(const cv::Mat &depthImg, double depth_max, double depth_quantization, compressed_depth_image_transport::ConfigHeader &compressionConfig) const
Convert a float direct-coded image to 16UC1 inverse-depth-coded image.
optional.hpp
image_transport_codecs::CompressedDepthCodec::getTransportName
std::string getTransportName() const override
Get the name of the codec/transport (used e.g. as topic suffix).
c_api.h
compression_common.h
image_transport_codecs::CompressedDepthCodec::encode
EncodeResult encode(const sensor_msgs::Image &raw, const compressed_depth_image_transport::CompressedDepthPublisherConfig &config) const
Encode the given raw image using the given publisher config.
image_transport_codecs::CompressedDepthCodec::fromInvDepth
cv::Mat fromInvDepth(const cv::Mat &invDepthImg, const compressed_depth_image_transport::ConfigHeader &compressionConfig) const
Convert a 16UC1 inverse-depth-coded image into a float direct-coded image.
image_transport_codecs::CompressedDepthCodec::encodeRVL
void encodeRVL(const cv::Mat &depthImg16UC1, std::vector< uint8_t > &compressed) const
Encode the given 16UC1 image (i.e. transformed to inverse depth) using RVL.
image_transport_codecs::CompressedDepthCodec::getCompressionConfig
compressed_depth_image_transport::ConfigHeader getCompressionConfig(const sensor_msgs::CompressedImage &compressed) const
Get the depth quantization parameters used by compression.
image_transport_codecs::CompressedDepthCodec::getCompressedImageContent
ImageTransportCodec::GetCompressedContentResult getCompressedImageContent(const topic_tools::ShapeShifter &compressed, const std::string &matchFormat) const override
Return the part of the encoded message that represents the actual image data (i.e....
image_transport_codecs::ImageTransportCodec::DecodeResult
cras::expected< sensor_msgs::Image, std::string > DecodeResult
Result of image decoding. Either a sensor_msgs::Image holding the raw message, or error message.
Definition: image_transport_codec.h:95
compressedDepthCodecDecode
bool compressedDepthCodecDecode(const char *compressedFormat, size_t compressedDataLength, const uint8_t compressedData[], sensor_msgs::Image::_height_type &rawHeight, sensor_msgs::Image::_width_type &rawWidth, cras::allocator_t rawEncodingAllocator, sensor_msgs::Image::_is_bigendian_type &rawIsBigEndian, sensor_msgs::Image::_step_type &rawStep, cras::allocator_t rawDataAllocator, cras::allocator_t errorStringAllocator, cras::allocator_t logMessagesAllocator)
Decode the given compressed image using compressedDepth codec.
compressedDepthCodecEncode
bool compressedDepthCodecEncode(sensor_msgs::Image::_height_type rawHeight, sensor_msgs::Image::_width_type rawWidth, const char *rawEncoding, sensor_msgs::Image::_is_bigendian_type rawIsBigEndian, sensor_msgs::Image::_step_type rawStep, size_t rawDataLength, const uint8_t rawData[], cras::allocator_t compressedFormatAllocator, cras::allocator_t compressedDataAllocator, double configDepthMax, double configDepthQuantization, int configPngLevel, cras::allocator_t errorStringAllocator, cras::allocator_t logMessagesAllocator)
Encode the given raw image using compressedDepth codec with the given config.
image_transport_codecs::CompressedDepthCodec::~CompressedDepthCodec
~CompressedDepthCodec() override
image_transport_codecs::ImageTransportCodec::GetCompressedContentResult
cras::expected< cras::optional< CompressedImageContent >, std::string > GetCompressedContentResult
Result of getting the actual compressed image data.
Definition: image_transport_codec.h:98
log_utils.h
image_transport_codecs::CompressedDepthCodec
Image transport codec corresponding to compressed_depth_image_transport.
Definition: compressed_depth_codec.h:58
image_transport_codecs::CompressedDepthCodec::decodeCompressedDepthImage
ImageTransportCodec::DecodeResult decodeCompressedDepthImage(const sensor_msgs::CompressedImage &compressed) const
Decode the given compressed image.
image_transport_codec.h
Base for all image transport codecs.
image_transport_codecs::CompressedDepthCodec::decode
ImageTransportCodec::DecodeResult decode(const sensor_msgs::CompressedImage &compressed) const
Decode the given compressed image.
image_transport_codecs::ImageTransportCodec
Base for all image transport codecs. All codecs have to extend class ImageTransportCodec and implemen...
Definition: image_transport_codec.h:81
compressed_depth_image_transport::ConfigHeader
span.hpp
image_transport_codecs::CompressedDepthCodec::CompressedDepthCodec
CompressedDepthCodec(const cras::LogHelperPtr &logHelper=std::make_shared< cras::NodeLogHelper >())
Create an instance of the codec.
image_transport_codecs::CompressedDepthCodec::EncodeResult
cras::expected< sensor_msgs::CompressedImage, std::string > EncodeResult
Result of image encoding. Either a sensor_msgs::CompressedImage message, or error message.
Definition: compressed_depth_codec.h:62
cras::LogHelperPtr
::cras::LogHelper::Ptr LogHelperPtr
image_transport_codecs
Definition: compressed_codec.h:29
node.h
compressed_depth_codec_has_rvl
bool compressed_depth_codec_has_rvl()
Whether the RVL encoding is available. This should be false on Melodic and true on Noetic.
image_transport_codecs::CompressedDepthCodec::decodeRVL
cv::Mat decodeRVL(const std::vector< uint8_t > &compressed) const
Decode a RVL-encoded image into a 16UC1 cv::Mat.
cv
Definition: compressed_depth_codec.h:31
image_transport_codecs::CompressedDepthCodec::encodeCompressedDepthImage
EncodeResult encodeCompressedDepthImage(const sensor_msgs::Image &raw, const std::string &compression_format, double depth_max, double depth_quantization, int png_level) const
Encode the given raw image using the given quantization and compression config.
topic_tools::ShapeShifter
image_transport_codecs::ImageTransportCodec::EncodeResult
cras::expected< cras::ShapeShifter, std::string > EncodeResult
Result of image encoding. Either a shapeshifter holding the compressed message, or error message.
Definition: image_transport_codec.h:92
cras::allocator_t
void *(* allocator_t)(size_t)


image_transport_codecs
Author(s): Martin Pecka
autogenerated on Mon Jun 17 2024 02:49:15