Classes | Namespaces | Functions
image_transport_codecs.h File Reference

Plugin-based interface for compressing and decompressing images using codec plugins. More...

#include <list>
#include <memory>
#include <string>
#include <unordered_map>
#include <dynamic_reconfigure/Config.h>
#include <pluginlib/class_loader.hpp>
#include <topic_tools/shape_shifter.h>
#include <cras_cpp_common/c_api.h>
#include <cras_cpp_common/log_utils.h>
#include <cras_cpp_common/log_utils/node.h>
#include <cras_cpp_common/xmlrpc_value_utils.hpp>
#include <cras_topic_tools/shape_shifter.h>
#include <image_transport_codecs/image_transport_codec.h>
#include <image_transport_codecs/image_transport_codec_plugin.h>
Include dependency graph for image_transport_codecs.h:

Go to the source code of this file.

Classes

class  image_transport_codecs::ImageTransportCodecs
 Plugin-based interface for compressing and decompressing images using codec plugins. More...
 

Namespaces

 image_transport_codecs
 

Functions

bool getCompressedImageContents (const char *topicOrCodec, const char *compressedType, const char *compressedMd5sum, size_t compressedDataLength, const uint8_t compressedData[], const char *matchFormat, bool &hasData, cras::allocator_t formatAllocator, cras::allocator_t dataAllocator, cras::allocator_t errorStringAllocator, cras::allocator_t logMessagesAllocator)
 Return the part of the encoded message that represents the actual image data (i.e. the part that can be passed to external decoders or saved to a file). If the codec messages have no such meaning, empty result is returned. More...
 
bool imageTransportCodecsDecode (const char *topicOrCodec, const char *compressedType, const char *compressedMd5sum, 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, size_t serializedConfigLength, const uint8_t serializedConfig[], cras::allocator_t errorStringAllocator, cras::allocator_t logMessagesAllocator)
 Decode the given compressed image using compressed codec with the given config. More...
 
bool imageTransportCodecsEncode (const char *topicOrCodec, 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 compressedTypeAllocator, cras::allocator_t md5SumAllocator, cras::allocator_t compressedDataAllocator, size_t serializedConfigLength, const uint8_t serializedConfig[], cras::allocator_t errorStringAllocator, cras::allocator_t logMessagesAllocator)
 C API ///. More...
 

Detailed Description

Plugin-based interface for compressing and decompressing images using codec plugins.

Author
Martin Pecka

Definition in file image_transport_codecs.h.

Function Documentation

◆ getCompressedImageContents()

bool getCompressedImageContents ( const char *  topicOrCodec,
const char *  compressedType,
const char *  compressedMd5sum,
size_t  compressedDataLength,
const uint8_t  compressedData[],
const char *  matchFormat,
bool &  hasData,
cras::allocator_t  formatAllocator,
cras::allocator_t  dataAllocator,
cras::allocator_t  errorStringAllocator,
cras::allocator_t  logMessagesAllocator 
)

Return the part of the encoded message that represents the actual image data (i.e. the part that can be passed to external decoders or saved to a file). If the codec messages have no such meaning, empty result is returned.

This is a C API to allow interfacing this library from other programming languages. Do not use it in C++.

Parameters
[in]topicOrCodecEither the output of a codec's getTransportName(), or name of a topic from which the compressed message was received (so that it is possible to parse the codec from the topic). Do not pass the raw image topic - that would result in using RawCodecPlugin which you probably do not want.
[in]compressedTypeThe string version of the type of the compressed message.
[in]compressedMd5sumThe MD5 sum of the compressed message.
[in]compressedDataLengthLength of the compressed image data in bytes.
[in]compressedDataBytes of the compressed image.
[in]matchFormatIf nonempty, the image data is only returned if their format field would match the given one. The matching should be case-insensitive.
[out]hasDataWhether some content data were found in the image.
[in,out]formatAllocatorAllocator for content format string.
[in,out]dataAllocatorAllocator for the content bytes.
[in,out]errorStringAllocatorAllocator for error string in case the encoding fails.
[in,out]logMessagesAllocatorAllocator for log messages to be passed to the calling code. Each allocated message should be properly reported by the native logging mechanism after this call finishes. The messages are serialized rosgraph_msgs::Log messages.
Returns
Whether the function has succeeded. If yes, output parameters are set, formatAllocator and dataAllocator allocate their buffers and write the output to them. If not, errorStringAllocator allocates its buffer and stores the error string in it.
See also
Corresponding C++ API function: image_transport_codecs::ImageTransportCodecs::getCompressedImageContent().

◆ imageTransportCodecsDecode()

bool imageTransportCodecsDecode ( const char *  topicOrCodec,
const char *  compressedType,
const char *  compressedMd5sum,
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,
size_t  serializedConfigLength,
const uint8_t  serializedConfig[],
cras::allocator_t  errorStringAllocator,
cras::allocator_t  logMessagesAllocator 
)

Decode the given compressed image using compressed codec with the given config.

This is a C API to allow interfacing this library from other programming languages. Do not use it in C++.

Parameters
[in]topicOrCodecEither the output of a codec's getTransportName(), or name of a topic from which the compressed message was received (so that it is possible to parse the codec from the topic). Do not pass the raw image topic - that would result in using RawCodecPlugin which you probably do not want.
[in]compressedTypeThe string version of the type of the compressed message.
[in]compressedMd5sumThe MD5 sum of the compressed message.
[in]compressedDataLengthLength of the compressed image data in bytes.
[in]compressedDataBytes of the compressed image.
[out]rawHeightRaw image height, that is, number of rows.
[out]rawWidthRaw image width, that is, number of columns.
[in,out]rawEncodingAllocatorAllocator for raw image encoding of pixels – channel meaning, ordering, size.
[out]rawIsBigEndianIs raw image bigendian?
[out]rawStepRaw image full row length in bytes.
[in,out]rawDataAllocatorAllocator for raw image bytes.
[in]serializedConfigLengthLength of the dynamic_reconfigure::Config serialization.
[in]serializedConfigBytes of the serialized dynamic_reconfigure::Config.
[in,out]errorStringAllocatorAllocator for error string in case the encoding fails.
[in,out]logMessagesAllocatorAllocator for log messages to be passed to the calling code. Each allocated message should be properly reported by the native logging mechanism after this call finishes. The messages are serialized rosgraph_msgs::Log messages.
Returns
Whether the encoding has succeeded. If yes, output parameters are set, rawEncodingAllocator and rawDataAllocator allocate their buffers and write the output to them. If not, errorStringAllocator allocates its buffer and stores the error string in it.
See also
Corresponding C++ API function: image_transport_codecs::ImageTransportCodecs::decode().

◆ imageTransportCodecsEncode()

bool imageTransportCodecsEncode ( const char *  topicOrCodec,
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  compressedTypeAllocator,
cras::allocator_t  md5SumAllocator,
cras::allocator_t  compressedDataAllocator,
size_t  serializedConfigLength,
const uint8_t  serializedConfig[],
cras::allocator_t  errorStringAllocator,
cras::allocator_t  logMessagesAllocator 
)

C API ///.

Encode the given raw image using an automatically determined codec with the given config.

This is a C API to allow interfacing this library from other programming languages. Do not use it in C++.

Parameters
[in]topicOrCodecEither the output of a codec's getTransportName(), or name of a topic where the compressed message will be published (so that it is possible to parse the codec from the topic). Do not pass the raw image topic - that would result in using RawCodecPlugin which you probably do not want.
[in]rawHeightRaw image height, that is, number of rows.
[in]rawWidthRaw image width, that is, number of columns.
[in]rawEncodingRaw image encoding of pixels – channel meaning, ordering, size.
[in]rawIsBigEndianIs raw image bigendian?
[in]rawStepRaw image full row length in bytes.
[in]rawDataLengthLength of raw image data in bytes, should be step * rows.
[in]rawDataThe raw image bytes.
[in,out]compressedTypeAllocatorAllocator for the string version of the type of the compressed message.
[in,out]md5SumAllocatorAllocator for the MD5 sum of the compressed message.
[in,out]compressedDataAllocatorAllocator for the byte data of the compressed image.
[in]serializedConfigLengthLength of the dynamic_reconfigure::Config serialization.
[in]serializedConfigBytes of the serialized dynamic_reconfigure::Config.
[in,out]errorStringAllocatorAllocator for error string in case the encoding fails.
[in,out]logMessagesAllocatorAllocator for log messages to be passed to the calling code. Each allocated message should be properly reported by the native logging mechanism after this call finishes. The messages are serialized rosgraph_msgs::Log messages.
Returns
Whether the encoding has succeeded. If yes, compressedFormatAllocator and compressedDataAllocator allocate their buffers and write the output to them. If not, errorStringAllocator allocates its buffer and stores the error string in it.
See also
Corresponding C++ API function: image_transport_codecs::ImageTransportCodecs::encode().


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