Go to the documentation of this file.
17 #include <dynamic_reconfigure/Config.h>
18 #include <sensor_msgs/CompressedImage.h>
19 #include <sensor_msgs/Image.h>
21 #include <compressed_depth_image_transport/CompressedDepthPublisherConfig.h>
62 typedef cras::expected<sensor_msgs::CompressedImage, std::string>
EncodeResult;
80 const compressed_depth_image_transport::CompressedDepthPublisherConfig& config)
const;
93 const dynamic_reconfigure::Config& config)
const override;
96 const dynamic_reconfigure::Config& config)
const override;
109 const sensor_msgs::CompressedImage& compressed,
const std::string& matchFormat)
const;
118 const sensor_msgs::CompressedImage& compressed)
const;
137 double depth_max,
double depth_quantization,
int png_level)
const;
144 cv::Mat
decodeRVL(
const std::vector<uint8_t>& compressed)
const;
151 void encodeRVL(
const cv::Mat& depthImg16UC1, std::vector<uint8_t>& compressed)
const;
171 cv::Mat
toInvDepth(
const cv::Mat& depthImg,
double depth_max,
double depth_quantization,
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[],
218 #
if COMPRESSED_DEPTH_HAS_RVL == 1
219 const char* configFormat,
221 double configDepthMax,
222 double configDepthQuantization,
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,
258 sensor_msgs::Image::_is_bigendian_type& rawIsBigEndian,
259 sensor_msgs::Image::_step_type& rawStep,
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.
std::string getTransportName() const override
Get the name of the codec/transport (used e.g. as topic suffix).
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.
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.
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.
compressed_depth_image_transport::ConfigHeader getCompressionConfig(const sensor_msgs::CompressedImage &compressed) const
Get the depth quantization parameters used by compression.
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....
cras::expected< sensor_msgs::Image, std::string > DecodeResult
Result of image decoding. Either a sensor_msgs::Image holding the raw message, or error message.
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.
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.
~CompressedDepthCodec() override
cras::expected< cras::optional< CompressedImageContent >, std::string > GetCompressedContentResult
Result of getting the actual compressed image data.
Image transport codec corresponding to compressed_depth_image_transport.
ImageTransportCodec::DecodeResult decodeCompressedDepthImage(const sensor_msgs::CompressedImage &compressed) const
Decode the given compressed image.
Base for all image transport codecs.
ImageTransportCodec::DecodeResult decode(const sensor_msgs::CompressedImage &compressed) const
Decode the given compressed image.
Base for all image transport codecs. All codecs have to extend class ImageTransportCodec and implemen...
CompressedDepthCodec(const cras::LogHelperPtr &logHelper=std::make_shared< cras::NodeLogHelper >())
Create an instance of the codec.
cras::expected< sensor_msgs::CompressedImage, std::string > EncodeResult
Result of image encoding. Either a sensor_msgs::CompressedImage message, or error message.
::cras::LogHelper::Ptr LogHelperPtr
bool compressed_depth_codec_has_rvl()
Whether the RVL encoding is available. This should be false on Melodic and true on Noetic.
cv::Mat decodeRVL(const std::vector< uint8_t > &compressed) const
Decode a RVL-encoded image into a 16UC1 cv::Mat.
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.
cras::expected< cras::ShapeShifter, std::string > EncodeResult
Result of image encoding. Either a shapeshifter holding the compressed message, or error message.
void *(* allocator_t)(size_t)