Classes | Namespaces | Functions
qoi_codec.h File Reference

Image transport codec working with QOI format. More...

#include <memory>
#include <string>
#include <dynamic_reconfigure/Config.h>
#include <sensor_msgs/CompressedImage.h>
#include <sensor_msgs/Image.h>
#include <cras_cpp_common/c_api.h>
#include <cras_cpp_common/log_utils.h>
#include <cras_cpp_common/log_utils/node.h>
#include <image_transport_codecs/image_transport_codec.h>
Include dependency graph for qoi_codec.h:

Go to the source code of this file.

Classes

class  qoi_image_transport::QoiCodec
 Image transport codec for QOI format. More...
 

Namespaces

 qoi_image_transport
 

Functions

bool qoiCodecDecode (const char *compressedFormat, 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, cras::allocator_t errorStringAllocator, cras::allocator_t logMessagesAllocator)
 Decode the given compressed image using qoi codec with the given config. More...
 
bool qoiCodecEncode (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 compressedFormatAllocator, cras::allocator_t compressedDataAllocator, cras::allocator_t errorStringAllocator, cras::allocator_t logMessagesAllocator)
 Encode the given raw image using qoi codec with the given config. More...
 

Detailed Description

Image transport codec working with QOI format.

Author
Martin Pecka

Definition in file qoi_codec.h.

Function Documentation

◆ qoiCodecDecode()

bool qoiCodecDecode ( const char *  compressedFormat,
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,
cras::allocator_t  errorStringAllocator,
cras::allocator_t  logMessagesAllocator 
)

Decode the given compressed image using qoi 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]compressedFormatThe format field of the compressed image.
[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,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: qoi_image_transport::QoiCodec::decode().

◆ qoiCodecEncode()

bool qoiCodecEncode ( 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  compressedFormatAllocator,
cras::allocator_t  compressedDataAllocator,
cras::allocator_t  errorStringAllocator,
cras::allocator_t  logMessagesAllocator 
)

Encode the given raw image using qoi 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]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]compressedFormatAllocatorAllocator for the format field of the compressed image.
[in,out]compressedDataAllocatorAllocator for the byte data of the compressed image.
[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: qoi_image_transport::QoiCodec::encode().


qoi_image_transport
Author(s): Martin Pecka
autogenerated on Sat Apr 5 2025 03:02:01