Classes | Namespaces | Enumerations | Functions
parse_compressed_format.h File Reference

Methods for parsing the values of field sensor_msgs::CompressedImage::format for compressed and compressedDepth codecs. More...

#include <string>
#include <utility>
#include <sensor_msgs/Image.h>
#include <cras_cpp_common/c_api.h>
#include <cras_cpp_common/expected.hpp>
#include <cras_cpp_common/optional.hpp>
Include dependency graph for parse_compressed_format.h:

Go to the source code of this file.

Classes

struct  image_transport_codecs::CompressedDepthTransportFormat
 Decoded meaning of field sensor_msgs::CompressedImage::format for compressedDepth transport. More...
 
struct  image_transport_codecs::CompressedTransportFormat
 Decoded meaning of field sensor_msgs::CompressedImage::format for compressed transport. More...
 

Namespaces

 image_transport_codecs
 

Enumerations

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

Functions

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. More...
 
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. More...
 
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. More...
 
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. More...
 
bool extractCompressedDepthTransportFormat (const char *imageEncoding, const char *compressionFormat, int &bitDepth, cras::allocator_t errorStringAllocator)
 Create the compressedDepth transport parameters for the given raw image compressed with the given method. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
bool extractCompressedTransportFormat (const char *imageEncoding, const char *compressionFormat, cras::allocator_t compressedEncodingAllocator, int &numChannels, int &bitDepth, bool &isColor, cras::allocator_t errorStringAllocator)
 Create the compressed transport parameters for the given raw image compressed with the given method. More...
 
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. More...
 
bool guessAnyCompressedImageTransportFormat (const char *format, const uint8_t imageHeader[64], bool &isCompressedDepth, cras::allocator_t compressionFormatAllocator, cras::allocator_t rawEncodingAllocator, cras::allocator_t compressedEncodingAllocator, int &numChannels, int &bitDepth, bool &isColor, cras::allocator_t errorStringAllocator)
 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 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. More...
 
bool makeCompressedDepthTransportFormat (const char *compressionFormat, const char *rawEncoding, int bitDepth, cras::allocator_t formatAllocator, cras::allocator_t errorStringAllocator)
 Convert the compressedDepth transport parameters into a string to be filled in field sensor_msgs::CompressedImage::format. More...
 
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. More...
 
bool makeCompressedTransportFormat (const char *compressionFormat, const char *rawEncoding, const char *compressedEncoding, int numChannels, int bitDepth, bool isColor, cras::allocator_t formatAllocator, cras::allocator_t errorStringAllocator)
 Convert the compressed transport parameters into a string to be filled in field sensor_msgs::CompressedImage::format. More...
 
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. More...
 
bool parseCompressedDepthTransportFormat (const char *format, cras::allocator_t compressionFormatAllocator, cras::allocator_t rawEncodingAllocator, int &bitDepth, cras::allocator_t errorStringAllocator)
 Parse the string from field sensor_msgs::CompressedImage::format using compressedDepth transport into individual components. More...
 
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. More...
 
bool parseCompressedTransportFormat (const char *format, cras::allocator_t compressionFormatAllocator, cras::allocator_t rawEncodingAllocator, cras::allocator_t compressedEncodingAllocator, int &numChannels, int &bitDepth, bool &isColor, cras::allocator_t errorStringAllocator)
 C API ///. More...
 

Detailed Description

Methods for parsing the values of field sensor_msgs::CompressedImage::format for compressed and compressedDepth codecs.

Author
Martin Pecka

Definition in file parse_compressed_format.h.

Function Documentation

◆ extractCompressedDepthTransportFormat()

bool extractCompressedDepthTransportFormat ( const char *  imageEncoding,
const char *  compressionFormat,
int bitDepth,
cras::allocator_t  errorStringAllocator 
)

Create the compressedDepth transport parameters for the given raw image compressed with the given method.

Parameters
[in]imageEncodingencoding field of the raw image.
[in]compressionFormatThe compression format ("png" or "rvl").
[out]bitDepthNumber of bits used for encoding one raw channel value.
[in,out]errorStringAllocatorAllocator for explanation why the parsing failed (used only in case of failure).
Returns
Whether the extraction succeeded. If not, the output parameters are not valid, and the buffer created using errorStringAllocator contains the explanation why the extraction failed.

◆ extractCompressedTransportFormat()

bool extractCompressedTransportFormat ( const char *  imageEncoding,
const char *  compressionFormat,
cras::allocator_t  compressedEncodingAllocator,
int numChannels,
int bitDepth,
bool &  isColor,
cras::allocator_t  errorStringAllocator 
)

Create the compressed transport parameters for the given raw image compressed with the given method.

Parameters
[in]imageEncodingencoding field of the raw image.
[in]compressionFormatThe compression format ("jpeg" or "png").
[in,out]compressedEncodingAllocatorAllocator for encoding of the compressed image (i.e. bgr8 for JPEG).
[out]numChannelsNumber of channels of the raw image data (1 for mono/depth images, 3-4 for color).
[out]bitDepthNumber of bits used for encoding one raw channel value.
[out]isColorWhether the image is a color image or not.
[in,out]errorStringAllocatorAllocator for explanation why the parsing failed (used only in case of failure).
Returns
Whether the extraction succeeded. If not, the output parameters are not valid, and the buffer created using errorStringAllocator contains the explanation why the extraction failed.

◆ guessAnyCompressedImageTransportFormat()

bool guessAnyCompressedImageTransportFormat ( const char *  format,
const uint8_t  imageHeader[64],
bool &  isCompressedDepth,
cras::allocator_t  compressionFormatAllocator,
cras::allocator_t  rawEncodingAllocator,
cras::allocator_t  compressedEncodingAllocator,
int numChannels,
int bitDepth,
bool &  isColor,
cras::allocator_t  errorStringAllocator 
)

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.
Parameters
[in]formatThe format field text.
[in]imageHeaderFirst 64 bytes of the image's data field.
[out]isCompressedDepthTrue if the image should be decoded using compressedDepth transport.
[in,out]compressionFormatAllocatorAllocator for the compression format ("jpeg", "png" or "rvl").
[in,out]rawEncodingAllocatorAllocator for encoding of the raw image (before compression).
[in,out]compressedEncodingAllocatorAllocator for encoding of the compressed image if the format is from compressed codec (i.e. bgr8 for JPEG).
[out]numChannelsNumber of channels of the raw image data (1 for mono/depth images, 3-4 for color).
[out]bitDepthNumber of bits used for encoding one raw channel value.
[out]isColorWhether the image is a color image or not.
[in,out]errorStringAllocatorAllocator for explanation why the parsing failed (used only in case of failure).
Returns
Whether the parsing succeeded. If not, the output parameters are not valid, and the buffer created using errorStringAllocator contains the explanation why the parsing failed.

◆ makeCompressedDepthTransportFormat()

bool makeCompressedDepthTransportFormat ( const char *  compressionFormat,
const char *  rawEncoding,
int  bitDepth,
cras::allocator_t  formatAllocator,
cras::allocator_t  errorStringAllocator 
)

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

Parameters
[in]compressionFormatThe compression format ("png" or "rvl").
[in]rawEncodingEncoding of the raw image (before compression, after decompression).
[in]bitDepthNumber of bits used for encoding one raw channel value.
[in,out]formatAllocatorAllocator for the string for the format field.
[in,out]errorStringAllocatorAllocator for explanation what failed (used only in case of failure).
Returns
Whether the conversion succeeded. If not, formatAllocator is not used, and the buffer created using errorStringAllocator contains the explanation why the conversion failed.

◆ makeCompressedTransportFormat()

bool makeCompressedTransportFormat ( const char *  compressionFormat,
const char *  rawEncoding,
const char *  compressedEncoding,
int  numChannels,
int  bitDepth,
bool  isColor,
cras::allocator_t  formatAllocator,
cras::allocator_t  errorStringAllocator 
)

Convert the compressed transport parameters into a string to be filled in field sensor_msgs::CompressedImage::format.

Parameters
[in]compressionFormatThe compression format ("jpeg" or "png").
[in]rawEncodingEncoding of the raw image (before compression, after decompression).
[in]compressedEncodingEncoding of the compressed image (i.e. bgr8 for JPEG).
[in]numChannelsNumber of channels of the raw image data (1 for mono/depth images, 3-4 for color).
[in]bitDepthNumber of bits used for encoding one raw channel value.
[in]isColorWhether the image is a color image or not.
[in,out]formatAllocatorAllocator for the string for the format field.
[in,out]errorStringAllocatorAllocator for explanation what failed (used only in case of failure).
Returns
Whether the conversion succeeded. If not, formatAllocator is not used, and the buffer created using errorStringAllocator contains the explanation why the conversion failed.

◆ parseCompressedDepthTransportFormat()

bool parseCompressedDepthTransportFormat ( const char *  format,
cras::allocator_t  compressionFormatAllocator,
cras::allocator_t  rawEncodingAllocator,
int bitDepth,
cras::allocator_t  errorStringAllocator 
)

Parse the string from field sensor_msgs::CompressedImage::format using compressedDepth transport into individual components.

Parameters
[in]formatThe format field text.
[in,out]compressionFormatAllocatorAllocator for the compression format ("png" or "rvl").
[in,out]rawEncodingAllocatorAllocator for encoding of the raw image (before compression, after decompression).
[out]bitDepthNumber of bits used for encoding one raw channel value.
[in,out]errorStringAllocatorAllocator for explanation why the parsing failed (used only in case of failure).
Returns
Whether the parsing succeeded. If not, the output parameters are not valid, and the buffer created using errorStringAllocator contains the explanation why the parsing failed.

◆ parseCompressedTransportFormat()

bool parseCompressedTransportFormat ( const char *  format,
cras::allocator_t  compressionFormatAllocator,
cras::allocator_t  rawEncodingAllocator,
cras::allocator_t  compressedEncodingAllocator,
int numChannels,
int bitDepth,
bool &  isColor,
cras::allocator_t  errorStringAllocator 
)

C API ///.

Parse the string from field sensor_msgs::CompressedImage::format using compressed transport into individual components.

Parameters
[in]formatThe format field text.
[in,out]compressionFormatAllocatorAllocator for the compression format ("jpeg" or "png").
[in,out]rawEncodingAllocatorAllocator for encoding of the raw image (before compression, after decompression).
[in,out]compressedEncodingAllocatorAllocator for encoding of the compressed image (i.e. bgr8 for JPEG).
[out]numChannelsNumber of channels of the raw image data (1 for mono/depth images, 3-4 for color).
[out]bitDepthNumber of bits used for encoding one raw channel value.
[out]isColorWhether the image is a color image or not.
[in,out]errorStringAllocatorAllocator for explanation why the parsing failed (used only in case of failure).
Returns
Whether the parsing succeeded. If not, the output parameters are not valid, and the buffer created using errorStringAllocator contains the explanation why the parsing failed.


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