Classes | Enumerations | Functions
image_transport_codecs Namespace Reference

Classes

class  CompressedCodec
 Image transport codec corresponding to compressed_image_transport. More...
 
class  CompressedDepthCodec
 Image transport codec corresponding to compressed_depth_image_transport. More...
 
struct  CompressedDepthTransportFormat
 Decoded meaning of field sensor_msgs::CompressedImage::format for compressedDepth transport. More...
 
struct  CompressedImageContent
 The part of a compressed message that represents the actual image data (i.e. data that can be passed to an external decoder). More...
 
struct  CompressedTransportFormat
 Decoded meaning of field sensor_msgs::CompressedImage::format for compressed transport. More...
 
class  ImageTransportCodec
 Base for all image transport codecs. All codecs have to extend class ImageTransportCodec and implement the pure virtual methods std::string getTransportName() const, encode(const sensor_msgs::Image&, const dynamic_reconfigure::Config&) const and decode(const topic_tools::ShapeShifter&, const dynamic_reconfigure::Config&) const. There are other convenience methods provided, but all of them are based on these implementations. More...
 
class  ImageTransportCodecPlugin
 Basic interface of an image transport codec plugin. More...
 
class  ImageTransportCodecPluginBase
 Convenience class for implementing image transport codec plugins, which just relays the whole API to a Codec library. More...
 
class  ImageTransportCodecs
 Plugin-based interface for compressing and decompressing images using codec plugins. More...
 

Enumerations

enum  CompressedDepthTransportCompressionFormat { CompressedDepthTransportCompressionFormat::PNG, CompressedDepthTransportCompressionFormat::RVL }
 Compression format of compressedDepth codec (PNG/RVL). RVL is only usable in Noetic. More...
 
enum  CompressedTransportCompressionFormat { CompressedTransportCompressionFormat::JPEG, CompressedTransportCompressionFormat::PNG }
 Compression format of compressed codec (JPEG/PNG). More...
 

Functions

CompressedDepthTransportFormat extractCompressedDepthTransportFormat (const std::string &imageEncoding, const CompressedDepthTransportCompressionFormat &compressionFormat)
 Create the CompressedDepthTransportFormat structure for the given raw image compressed with the given method. More...
 
CompressedDepthTransportFormat extractCompressedDepthTransportFormat (const sensor_msgs::Image &image, const CompressedDepthTransportCompressionFormat &compressionFormat)
 Create the CompressedDepthTransportFormat structure for the given raw image compressed with the given method. More...
 
cras::expected< CompressedDepthTransportFormat, std::string > extractCompressedDepthTransportFormat (const std::string &imageEncoding, const std::string &compressionFormat)
 Create the CompressedDepthTransportFormat structure for the given raw image compressed with the given method. More...
 
cras::expected< CompressedDepthTransportFormat, std::string > extractCompressedDepthTransportFormat (const sensor_msgs::Image &image, const std::string &compressionFormat)
 Create the CompressedDepthTransportFormat structure for the given raw image compressed with the given method. More...
 
CompressedTransportFormat extractCompressedTransportFormat (const std::string &imageEncoding, const CompressedTransportCompressionFormat &compressionFormat)
 Create the CompressedTransportFormat structure for the given raw image compressed with the given method. More...
 
CompressedTransportFormat extractCompressedTransportFormat (const sensor_msgs::Image &image, const CompressedTransportCompressionFormat &compressionFormat)
 Create the CompressedTransportFormat structure for the given raw image compressed with the given method. More...
 
cras::expected< CompressedTransportFormat, std::string > extractCompressedTransportFormat (const std::string &imageEncoding, const std::string &compressionFormat)
 Create the CompressedTransportFormat structure for the given raw image compressed with the given method. More...
 
cras::expected< CompressedTransportFormat, std::string > extractCompressedTransportFormat (const sensor_msgs::Image &image, const std::string &compressionFormat)
 Create the CompressedTransportFormat structure for the given raw image compressed with the given method. More...
 
cras::expected< std::pair< cras::optional< CompressedTransportFormat >, cras::optional< CompressedDepthTransportFormat > >, std::string > guessAnyCompressedImageTransportFormat (const sensor_msgs::CompressedImage &image)
 Parse the string from field sensor_msgs::CompressedImage::format using either compressed or compressedDepth transport. Selection between the two formats is done automatically and it might peek into the first 64 bytes of the compressed byte stream in the image. More...
 
std::string makeCompressedDepthTransportFormat (const CompressedDepthTransportFormat &format)
 Convert the CompressedDepthTransportFormat structure into a string to be filled in field sensor_msgs::CompressedImage::format using compressedDepth transport. More...
 
std::string makeCompressedTransportFormat (const CompressedTransportFormat &format)
 Convert the CompressedTransportFormat structure into a string to be filled in field sensor_msgs::CompressedImage::format of compressed transport image. More...
 
cras::expected< CompressedDepthTransportFormat, std::string > parseCompressedDepthTransportFormat (const std::string &format)
 Parse the string from field sensor_msgs::CompressedImage::format using compressedDepth transport into CompressedDepthTransportFormat structure. More...
 
cras::expected< CompressedTransportFormat, std::string > parseCompressedTransportFormat (const std::string &format)
 Parse the string from field sensor_msgs::CompressedImage::format using compressed transport into CompressedTransportFormat structure. More...
 

Enumeration Type Documentation

◆ CompressedDepthTransportCompressionFormat

Compression format of compressedDepth codec (PNG/RVL). RVL is only usable in Noetic.

Enumerator
PNG 

PNG compression format.

RVL 

RVL compression format (only usable in Noetic).

Definition at line 107 of file parse_compressed_format.h.

◆ CompressedTransportCompressionFormat

Compression format of compressed codec (JPEG/PNG).

Enumerator
JPEG 

JPEG compression format.

PNG 

PNG compression format.

Definition at line 28 of file parse_compressed_format.h.

Function Documentation

◆ extractCompressedDepthTransportFormat() [1/4]

CompressedDepthTransportFormat image_transport_codecs::extractCompressedDepthTransportFormat ( const std::string &  imageEncoding,
const CompressedDepthTransportCompressionFormat compressionFormat 
)

Create the CompressedDepthTransportFormat structure for the given raw image compressed with the given method.

Parameters
[in]imageEncodingencoding field of the raw image.
[in]compressionFormatThe target compression method.
Returns
The CompressedDepthTransportFormat structure corresponding to the given image and compression method.

◆ extractCompressedDepthTransportFormat() [2/4]

CompressedDepthTransportFormat image_transport_codecs::extractCompressedDepthTransportFormat ( const sensor_msgs::Image &  image,
const CompressedDepthTransportCompressionFormat compressionFormat 
)

Create the CompressedDepthTransportFormat structure for the given raw image compressed with the given method.

Parameters
[in]imageThe raw image.
[in]compressionFormatThe target compression method.
Returns
The CompressedDepthTransportFormat structure corresponding to the given image and compression method.

◆ extractCompressedDepthTransportFormat() [3/4]

cras::expected<CompressedDepthTransportFormat, std::string> image_transport_codecs::extractCompressedDepthTransportFormat ( const std::string &  imageEncoding,
const std::string &  compressionFormat 
)

Create the CompressedDepthTransportFormat structure for the given raw image compressed with the given method.

Parameters
[in]imageEncodingencoding field of the raw image.
[in]compressionFormatThe string version of target compression method (either "png" or "rvl" (only on Noetic)).
Returns
The CompressedDepthTransportFormat structure corresponding to the given image and compression method, or error string if format is invalid.

◆ extractCompressedDepthTransportFormat() [4/4]

cras::expected<CompressedDepthTransportFormat, std::string> image_transport_codecs::extractCompressedDepthTransportFormat ( const sensor_msgs::Image &  image,
const std::string &  compressionFormat 
)

Create the CompressedDepthTransportFormat structure for the given raw image compressed with the given method.

Parameters
[in]imageThe raw image.
[in]compressionFormatThe string version of target compression method (either "png" or "rvl" (only on Noetic)).
Returns
The CompressedDepthTransportFormat structure corresponding to the given image and compression method, or error string if format is invalid.

◆ extractCompressedTransportFormat() [1/4]

CompressedTransportFormat image_transport_codecs::extractCompressedTransportFormat ( const std::string &  imageEncoding,
const CompressedTransportCompressionFormat compressionFormat 
)

Create the CompressedTransportFormat structure for the given raw image compressed with the given method.

Parameters
[in]imageEncodingencoding field of the raw image.
[in]compressionFormatThe target compression method.
Returns
The CompressedTransportFormat structure corresponding to the given image and compression method.

◆ extractCompressedTransportFormat() [2/4]

CompressedTransportFormat image_transport_codecs::extractCompressedTransportFormat ( const sensor_msgs::Image &  image,
const CompressedTransportCompressionFormat compressionFormat 
)

Create the CompressedTransportFormat structure for the given raw image compressed with the given method.

Parameters
[in]imageThe raw image.
[in]compressionFormatThe target compression method.
Returns
The CompressedTransportFormat structure corresponding to the given image and compression method.

◆ extractCompressedTransportFormat() [3/4]

cras::expected<CompressedTransportFormat, std::string> image_transport_codecs::extractCompressedTransportFormat ( const std::string &  imageEncoding,
const std::string &  compressionFormat 
)

Create the CompressedTransportFormat structure for the given raw image compressed with the given method.

Parameters
[in]imageEncodingencoding field of the raw image.
[in]compressionFormatThe string version of target compression method (either "jpeg" or "png").
Returns
The CompressedTransportFormat structure corresponding to the given image and compression method, or error string if format is invalid.

◆ extractCompressedTransportFormat() [4/4]

cras::expected<CompressedTransportFormat, std::string> image_transport_codecs::extractCompressedTransportFormat ( const sensor_msgs::Image &  image,
const std::string &  compressionFormat 
)

Create the CompressedTransportFormat structure for the given raw image compressed with the given method.

Parameters
[in]imageThe raw image.
[in]compressionFormatThe string version of target compression method (either "jpeg" or "png").
Returns
The CompressedTransportFormat structure corresponding to the given image and compression method, or error string if format is invalid.

◆ guessAnyCompressedImageTransportFormat()

cras::expected< std::pair<cras::optional<CompressedTransportFormat>, cras::optional<CompressedDepthTransportFormat> >, std::string> image_transport_codecs::guessAnyCompressedImageTransportFormat ( const sensor_msgs::CompressedImage &  image)

Parse the string from field sensor_msgs::CompressedImage::format using either compressed or compressedDepth transport. Selection between the two formats is done automatically and it might peek into the first 64 bytes of the compressed byte stream in the image.

Parameters
[in]imageThe image whose transport format should be parsed.
Returns
The parsed CompressedTransportFormat or CompressedDepthTransportFormat (exactly one of these two will be valid on success) or error string.

◆ makeCompressedDepthTransportFormat()

std::string image_transport_codecs::makeCompressedDepthTransportFormat ( const CompressedDepthTransportFormat format)

Convert the CompressedDepthTransportFormat structure into a string to be filled in field sensor_msgs::CompressedImage::format using compressedDepth transport.

Parameters
[in]formatThe format to convert.
Returns
The string for the format field.

◆ makeCompressedTransportFormat()

std::string image_transport_codecs::makeCompressedTransportFormat ( const CompressedTransportFormat format)

Convert the CompressedTransportFormat structure into a string to be filled in field sensor_msgs::CompressedImage::format of compressed transport image.

Parameters
[in]formatThe format to convert.
Returns
The string for the format field.

◆ parseCompressedDepthTransportFormat()

cras::expected<CompressedDepthTransportFormat, std::string> image_transport_codecs::parseCompressedDepthTransportFormat ( const std::string &  format)

Parse the string from field sensor_msgs::CompressedImage::format using compressedDepth transport into CompressedDepthTransportFormat structure.

Parameters
[in]formatThe format field text.
Returns
The parsed CompressedDepthTransportFormat structure or error string.

◆ parseCompressedTransportFormat()

cras::expected<CompressedTransportFormat, std::string> image_transport_codecs::parseCompressedTransportFormat ( const std::string &  format)

Parse the string from field sensor_msgs::CompressedImage::format using compressed transport into CompressedTransportFormat structure.

Parameters
[in]formatThe format field text.
Returns
The parsed structure or error string.


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