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>
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... | |
Methods for parsing the values of field sensor_msgs::CompressedImage::format
for compressed
and compressedDepth
codecs.
Definition in file parse_compressed_format.h.
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.
[in] | imageEncoding | encoding field of the raw image. |
[in] | compressionFormat | The compression format ("png" or "rvl"). |
[out] | bitDepth | Number of bits used for encoding one raw channel value. |
[in,out] | errorStringAllocator | Allocator for explanation why the parsing failed (used only in case of failure). |
errorStringAllocator
contains the explanation why the extraction failed. 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.
[in] | imageEncoding | encoding field of the raw image. |
[in] | compressionFormat | The compression format ("jpeg" or "png"). |
[in,out] | compressedEncodingAllocator | Allocator for encoding of the compressed image (i.e. bgr8 for JPEG). |
[out] | numChannels | Number of channels of the raw image data (1 for mono/depth images, 3-4 for color). |
[out] | bitDepth | Number of bits used for encoding one raw channel value. |
[out] | isColor | Whether the image is a color image or not. |
[in,out] | errorStringAllocator | Allocator for explanation why the parsing failed (used only in case of failure). |
errorStringAllocator
contains the explanation why the extraction failed. 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.
[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. [in] | format | The format field text. |
[in] | imageHeader | First 64 bytes of the image's data field. |
[out] | isCompressedDepth | True if the image should be decoded using compressedDepth transport. |
[in,out] | compressionFormatAllocator | Allocator for the compression format ("jpeg", "png" or "rvl"). |
[in,out] | rawEncodingAllocator | Allocator for encoding of the raw image (before compression). |
[in,out] | compressedEncodingAllocator | Allocator for encoding of the compressed image if the format is from compressed codec (i.e. bgr8 for JPEG). |
[out] | numChannels | Number of channels of the raw image data (1 for mono/depth images, 3-4 for color). |
[out] | bitDepth | Number of bits used for encoding one raw channel value. |
[out] | isColor | Whether the image is a color image or not. |
[in,out] | errorStringAllocator | Allocator for explanation why the parsing failed (used only in case of failure). |
errorStringAllocator
contains the explanation why the parsing failed. 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
.
[in] | compressionFormat | The compression format ("png" or "rvl"). |
[in] | rawEncoding | Encoding of the raw image (before compression, after decompression). |
[in] | bitDepth | Number of bits used for encoding one raw channel value. |
[in,out] | formatAllocator | Allocator for the string for the format field. |
[in,out] | errorStringAllocator | Allocator for explanation what failed (used only in case of failure). |
formatAllocator
is not used, and the buffer created using errorStringAllocator
contains the explanation why the conversion failed. 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
.
[in] | compressionFormat | The compression format ("jpeg" or "png"). |
[in] | rawEncoding | Encoding of the raw image (before compression, after decompression). |
[in] | compressedEncoding | Encoding of the compressed image (i.e. bgr8 for JPEG). |
[in] | numChannels | Number of channels of the raw image data (1 for mono/depth images, 3-4 for color). |
[in] | bitDepth | Number of bits used for encoding one raw channel value. |
[in] | isColor | Whether the image is a color image or not. |
[in,out] | formatAllocator | Allocator for the string for the format field. |
[in,out] | errorStringAllocator | Allocator for explanation what failed (used only in case of failure). |
formatAllocator
is not used, and the buffer created using errorStringAllocator
contains the explanation why the conversion failed. 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.
[in] | format | The format field text. |
[in,out] | compressionFormatAllocator | Allocator for the compression format ("png" or "rvl"). |
[in,out] | rawEncodingAllocator | Allocator for encoding of the raw image (before compression, after decompression). |
[out] | bitDepth | Number of bits used for encoding one raw channel value. |
[in,out] | errorStringAllocator | Allocator for explanation why the parsing failed (used only in case of failure). |
errorStringAllocator
contains the explanation why the parsing failed. 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.
[in] | format | The format field text. |
[in,out] | compressionFormatAllocator | Allocator for the compression format ("jpeg" or "png"). |
[in,out] | rawEncodingAllocator | Allocator for encoding of the raw image (before compression, after decompression). |
[in,out] | compressedEncodingAllocator | Allocator for encoding of the compressed image (i.e. bgr8 for JPEG). |
[out] | numChannels | Number of channels of the raw image data (1 for mono/depth images, 3-4 for color). |
[out] | bitDepth | Number of bits used for encoding one raw channel value. |
[out] | isColor | Whether the image is a color image or not. |
[in,out] | errorStringAllocator | Allocator for explanation why the parsing failed (used only in case of failure). |
errorStringAllocator
contains the explanation why the parsing failed.