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 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 sensor_msgs::Image &image, const std::string &compressionFormat) |
Create the CompressedDepthTransportFormat structure for the given raw image compressed with the given method. More... | |
CompressedDepthTransportFormat | extractCompressedDepthTransportFormat (const std::string &imageEncoding, 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... | |
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 sensor_msgs::Image &image, const std::string &compressionFormat) |
Create the CompressedTransportFormat 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... | |
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< 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... | |
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.
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.
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.
[in] | image | The raw image. |
[in] | compressionFormat | The target compression method. |
CompressedDepthTransportFormat
structure corresponding to the given image and compression method. 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.
[in] | image | The raw image. |
[in] | compressionFormat | The string version of target compression method (either "png" or "rvl" (only on Noetic)). |
CompressedDepthTransportFormat
structure corresponding to the given image and compression method, or error string if format
is invalid. 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.
[in] | imageEncoding | encoding field of the raw image. |
[in] | compressionFormat | The target compression method. |
CompressedDepthTransportFormat
structure corresponding to the given image and compression method. 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.
[in] | imageEncoding | encoding field of the raw image. |
[in] | compressionFormat | The string version of target compression method (either "png" or "rvl" (only on Noetic)). |
CompressedDepthTransportFormat
structure corresponding to the given image and compression method, or error string if format
is invalid. 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.
[in] | image | The raw image. |
[in] | compressionFormat | The target compression method. |
CompressedTransportFormat
structure corresponding to the given image and compression method. 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.
[in] | image | The raw image. |
[in] | compressionFormat | The string version of target compression method (either "jpeg" or "png"). |
CompressedTransportFormat
structure corresponding to the given image and compression method, or error string if format
is invalid. 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.
[in] | imageEncoding | encoding field of the raw image. |
[in] | compressionFormat | The target compression method. |
CompressedTransportFormat
structure corresponding to the given image and compression method. 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.
[in] | imageEncoding | encoding field of the raw image. |
[in] | compressionFormat | The string version of target compression method (either "jpeg" or "png"). |
CompressedTransportFormat
structure corresponding to the given image and compression method, or error string if format
is invalid. 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.
[in] | image | The image whose transport format should be parsed. |
CompressedTransportFormat
or CompressedDepthTransportFormat
(exactly one of these two will be valid on success) or error string. 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.
[in] | format | The format to convert. |
format
field. 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.
[in] | format | The format to convert. |
format
field. 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.
[in] | format | The format field text. |
CompressedDepthTransportFormat
structure or error string. 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.
[in] | format | The format field text. |