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>
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... | |
Image transport codec working with QOI format.
Definition in file qoi_codec.h.
| 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++.
| [in] | compressedFormat | The format field of the compressed image. |
| [in] | compressedDataLength | Length of the compressed image data in bytes. |
| [in] | compressedData | Bytes of the compressed image. |
| [out] | rawHeight | Raw image height, that is, number of rows. |
| [out] | rawWidth | Raw image width, that is, number of columns. |
| [in,out] | rawEncodingAllocator | Allocator for raw image encoding of pixels – channel meaning, ordering, size. |
| [out] | rawIsBigEndian | Is raw image bigendian? |
| [out] | rawStep | Raw image full row length in bytes. |
| [in,out] | rawDataAllocator | Allocator for raw image bytes. |
| [in,out] | errorStringAllocator | Allocator for error string in case the encoding fails. |
| [in,out] | logMessagesAllocator | Allocator 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. |
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. qoi_image_transport::QoiCodec::decode(). | 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++.
| [in] | rawHeight | Raw image height, that is, number of rows. |
| [in] | rawWidth | Raw image width, that is, number of columns. |
| [in] | rawEncoding | Raw image encoding of pixels – channel meaning, ordering, size. |
| [in] | rawIsBigEndian | Is raw image bigendian? |
| [in] | rawStep | Raw image full row length in bytes. |
| [in] | rawDataLength | Length of raw image data in bytes, should be step * rows. |
| [in] | rawData | The raw image bytes. |
| [in,out] | compressedFormatAllocator | Allocator for the format field of the compressed image. |
| [in,out] | compressedDataAllocator | Allocator for the byte data of the compressed image. |
| [in,out] | errorStringAllocator | Allocator for error string in case the encoding fails. |
| [in,out] | logMessagesAllocator | Allocator 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. |
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. qoi_image_transport::QoiCodec::encode().