Classes | Namespaces | Functions
compressed_codec.h File Reference

Image transport codec corresponding to compressed_image_transport. More...

#include <memory>
#include <string>
#include <vector>
#include <dynamic_reconfigure/Config.h>
#include <sensor_msgs/CompressedImage.h>
#include <sensor_msgs/Image.h>
#include <compressed_image_transport/CompressedPublisherConfig.h>
#include <compressed_image_transport/CompressedSubscriberConfig.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 compressed_codec.h:

Go to the source code of this file.

Classes

class  image_transport_codecs::CompressedCodec
 Image transport codec corresponding to compressed_image_transport. More...
 

Namespaces

 image_transport_codecs
 

Functions

bool compressed_codec_has_extra_jpeg_options ()
 Whether the extra JPEG encoding options are available (progressive, optimize, restart interval). This should be false on Melodic and true on Noetic. More...
 
bool compressedCodecDecode (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, const char *configMode, cras::allocator_t errorStringAllocator, cras::allocator_t logMessagesAllocator)
 Decode the given compressed image using compressed codec with the given config. More...
 
bool compressedCodecEncode (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, const char *configFormat, int configJpegQuality, int configPngLevel, cras::allocator_t errorStringAllocator, cras::allocator_t logMessagesAllocator)
 Encode the given raw image using compressed codec with the given config. More...
 

Detailed Description

Image transport codec corresponding to compressed_image_transport.

Author
Martin Pecka

Definition in file compressed_codec.h.

Function Documentation

◆ compressed_codec_has_extra_jpeg_options()

bool compressed_codec_has_extra_jpeg_options ( )

Whether the extra JPEG encoding options are available (progressive, optimize, restart interval). This should be false on Melodic and true on Noetic.

Returns
Whether extra JPEG options are available on this installation.

◆ compressedCodecDecode()

bool compressedCodecDecode ( 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,
const char *  configMode,
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]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]configModeColor mode of the decoded image (unchanged/color/gray).
[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::CompressedCodec::decode().

◆ compressedCodecEncode()

bool compressedCodecEncode ( 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,
const char *  configFormat,
int  configJpegQuality,
int  configPngLevel,
cras::allocator_t  errorStringAllocator,
cras::allocator_t  logMessagesAllocator 
)

Encode the given raw 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]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]configFormatCompression format (jpeg or png).
[in]configJpegQualityJPEG quality percentile (1-100).
[in]configJpegProgressiveEnable compression to progressive JPEG (Noetic only).
[in]configJpegOptimizeEnable JPEG compress optimization (Noetic only).
[in]configJpegRestartIntervalJPEG restart interval (Noetic only).
[in]configPngLevelPNG compression level (1-9).
[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::CompressedCodec::encode().


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