compressed_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_image_transport/CompressedPublisherConfig.h>
22 #include <compressed_image_transport/CompressedSubscriberConfig.h>
23 
24 #include <cras_cpp_common/c_api.h>
28 
30 {
31 
32 class CompressedCodecPrivate;
33 
54 {
55 public:
57  typedef cras::expected<sensor_msgs::CompressedImage, std::string> EncodeResult;
58 
63  explicit CompressedCodec(const cras::LogHelperPtr& logHelper = std::make_shared<cras::NodeLogHelper>());
64 
65  ~CompressedCodec() override;
66 
74  EncodeResult encode(const sensor_msgs::Image& raw,
75  const compressed_image_transport::CompressedPublisherConfig& config) const;
76 
84  ImageTransportCodec::DecodeResult decode(const sensor_msgs::CompressedImage& compressed,
85  const compressed_image_transport::CompressedSubscriberConfig& config) const;
86 
93  ImageTransportCodec::DecodeResult decode(const sensor_msgs::CompressedImage& compressed) const;
94 
95  std::string getTransportName() const override;
96 
97  ImageTransportCodec::EncodeResult encode(const sensor_msgs::Image& raw,
98  const dynamic_reconfigure::Config& config) const override;
99 
101  const dynamic_reconfigure::Config& config) const override;
102 
104  const topic_tools::ShapeShifter& compressed, const std::string& matchFormat) const override;
105 
114  const sensor_msgs::CompressedImage& compressed, const std::string& matchFormat) const;
115 
123  ImageTransportCodec::DecodeResult decompressJPEG(const std::vector<uint8_t>& data, const std::string& source_encoding,
124  const std_msgs::Header& header) const;
125 
126 private:
127  std::unique_ptr<CompressedCodecPrivate> data;
128 };
129 
130 }
131 
132 // ////////
133 // C API //
134 // ////////
135 
165 extern "C" bool compressedCodecEncode(
166  sensor_msgs::Image::_height_type rawHeight,
167  sensor_msgs::Image::_width_type rawWidth,
168  const char* rawEncoding,
169  sensor_msgs::Image::_is_bigendian_type rawIsBigEndian,
170  sensor_msgs::Image::_step_type rawStep,
171  size_t rawDataLength,
172  const uint8_t rawData[],
173  cras::allocator_t compressedFormatAllocator,
174  cras::allocator_t compressedDataAllocator,
175  const char* configFormat,
176  int configJpegQuality,
177 #if COMPRESSED_HAS_JPEG_OPTIONS == 1
178  bool configJpegProgressive,
179  bool configJpegOptimize,
180  int configJpegRestartInterval,
181 #endif
182  int configPngLevel,
183  cras::allocator_t errorStringAllocator,
184  cras::allocator_t logMessagesAllocator
185 );
186 
211 extern "C" bool compressedCodecDecode(
212  const char* compressedFormat,
213  size_t compressedDataLength,
214  const uint8_t compressedData[],
215  sensor_msgs::Image::_height_type& rawHeight,
216  sensor_msgs::Image::_width_type& rawWidth,
217  cras::allocator_t rawEncodingAllocator,
218  sensor_msgs::Image::_is_bigendian_type& rawIsBigEndian,
219  sensor_msgs::Image::_step_type& rawStep,
220  cras::allocator_t rawDataAllocator,
221  const char* configMode,
222  cras::allocator_t errorStringAllocator,
223  cras::allocator_t logMessagesAllocator
224 );
225 
cras::expected< cras::ShapeShifter, std::string > EncodeResult
Result of image encoding. Either a shapeshifter holding the compressed message, or error message...
bool compressedCodecEncode(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, const char *configFormat, int configJpegQuality, int configPngLevel, cras::allocator_t errorStringAllocator, cras::allocator_t logMessagesAllocator)
Encode the given raw image using compressed codec with the given config.
ImageTransportCodec::DecodeResult decompressJPEG(const std::vector< uint8_t > &data, const std::string &source_encoding, const std_msgs::Header &header) const
Fast method to decompress a JPEG image. It does not support PNG images (use decode() if you are not s...
Image transport codec corresponding to compressed_image_transport.
cras::expected< sensor_msgs::CompressedImage, std::string > EncodeResult
Result of image encoding. Either a sensor_msgs::CompressedImage message, or error message...
cras::expected< sensor_msgs::Image, std::string > DecodeResult
Result of image decoding. Either a sensor_msgs::Image holding the raw message, or error message...
std::unique_ptr< CompressedCodecPrivate > data
Private implementation data.
bool compressedCodecDecode(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, const char *configMode, cras::allocator_t errorStringAllocator, cras::allocator_t logMessagesAllocator)
Decode the given compressed image using compressed codec with the given config.
CompressedCodec(const cras::LogHelperPtr &logHelper=std::make_shared< cras::NodeLogHelper >())
Create an instance of the codec.
cras::expected< cras::optional< CompressedImageContent >, std::string > GetCompressedContentResult
Result of getting the actual compressed image data.
Base for all image transport codecs.
Base for all image transport codecs. All codecs have to extend class ImageTransportCodec and implemen...
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_image_transport::CompressedPublisherConfig &config) const
Encode the given raw image using the given publisher config.
void *(* allocator_t)(size_t)
bool compressed_codec_has_extra_jpeg_options()
Whether the extra JPEG encoding options are available (progressive, optimize, restart interval)...
ImageTransportCodec::DecodeResult decode(const sensor_msgs::CompressedImage &compressed, const compressed_image_transport::CompressedSubscriberConfig &config) const
Decode the given compressed image using the given subscriber config.
::cras::LogHelper::Ptr LogHelperPtr
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. the part that can be passed to external decoders or saved to a file). If the codec messages have no such meaning, empty result is returned.


image_transport_codecs
Author(s): Martin Pecka
autogenerated on Sat Jun 17 2023 02:33:19