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_image_transport/CompressedPublisherConfig.h>
22 #include <compressed_image_transport/CompressedSubscriberConfig.h>
32 class CompressedCodecPrivate;
57 typedef cras::expected<sensor_msgs::CompressedImage, std::string>
EncodeResult;
75 const compressed_image_transport::CompressedPublisherConfig& config)
const;
85 const compressed_image_transport::CompressedSubscriberConfig& config)
const;
98 const dynamic_reconfigure::Config& config)
const override;
101 const dynamic_reconfigure::Config& config)
const override;
114 const sensor_msgs::CompressedImage& compressed,
const std::string& matchFormat)
const;
124 const std_msgs::Header& header)
const;
127 std::unique_ptr<CompressedCodecPrivate>
data;
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[],
175 const char* configFormat,
176 int configJpegQuality,
177 #
if COMPRESSED_HAS_JPEG_OPTIONS == 1
178 bool configJpegProgressive,
179 bool configJpegOptimize,
180 int configJpegRestartInterval,
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,
218 sensor_msgs::Image::_is_bigendian_type& rawIsBigEndian,
219 sensor_msgs::Image::_step_type& rawStep,
221 const char* configMode,
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.
std::string getTransportName() const override
Get the name of the codec/transport (used e.g. as topic suffix).
~CompressedCodec() override
bool compressed_codec_has_extra_jpeg_options()
Whether the extra JPEG encoding options are available (progressive, optimize, restart interval)....
std::unique_ptr< CompressedCodecPrivate > data
Private implementation data.
EncodeResult encode(const sensor_msgs::Image &raw, const compressed_image_transport::CompressedPublisherConfig &config) const
Encode the given raw image using the given publisher config.
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.
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...
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.
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...
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.
Image transport codec corresponding to compressed_image_transport.
::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....
CompressedCodec(const cras::LogHelperPtr &logHelper=std::make_shared< cras::NodeLogHelper >())
Create an instance of the codec.
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)