Public Member Functions | Private Attributes | List of all members
image_transport_codecs::ImageTransportCodecPluginBase< Codec > Class Template Reference

Convenience class for implementing image transport codec plugins, which just relays the whole API to a Codec library. More...

#include <image_transport_codec_plugin.h>

Inheritance diagram for image_transport_codecs::ImageTransportCodecPluginBase< Codec >:
Inheritance graph
[legend]

Public Member Functions

ImageTransportCodec::DecodeResult decode (const topic_tools::ShapeShifter &compressed, const dynamic_reconfigure::Config &config) const override
 Decode the given compressed image into a raw image. More...
 
ImageTransportCodec::EncodeResult encode (const sensor_msgs::Image &raw, const dynamic_reconfigure::Config &config) const override
 Encode the given raw image into the given shapeshifter object. More...
 
ImageTransportCodec::GetCompressedContentResult getCompressedImageContent (const topic_tools::ShapeShifter &compressed, const std::string &matchFormat) const override
 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...
 
std::string getTransportName () const override
 Get the name of the codec/transport (used e.g. as topic suffix). More...
 
void setLogHelper (const cras::LogHelperPtr &logHelper) override
 Use the given log helper for logging messages. More...
 
- Public Member Functions inherited from image_transport_codecs::ImageTransportCodecPlugin
virtual ~ImageTransportCodecPlugin ()=default
 

Private Attributes

Codec codec
 The codec used by this plugin. More...
 

Additional Inherited Members

- Public Types inherited from image_transport_codecs::ImageTransportCodecPlugin
typedef boost::shared_ptr< const ImageTransportCodecPluginConstPtr
 Shared pointer to const ImageTransportCodecPlugin. More...
 
typedef boost::shared_ptr< ImageTransportCodecPluginPtr
 Shared pointer to ImageTransportCodecPlugin. More...
 

Detailed Description

template<typename Codec>
class image_transport_codecs::ImageTransportCodecPluginBase< Codec >

Convenience class for implementing image transport codec plugins, which just relays the whole API to a Codec library.

Template Parameters
CodecClass of the codec.

If used properly, the whole code of the codec plugin library can be as short as:

{
class CompressedImageTransportCodecPlugin : public ImageTransportCodecPluginBase<CompressedCodec> {};
}
PLUGINLIB_EXPORT_CLASS(image_transport_codecs::CompressedImageTransportCodecPlugin,

Definition at line 138 of file image_transport_codec_plugin.h.

Member Function Documentation

◆ decode()

template<typename Codec >
ImageTransportCodec::DecodeResult image_transport_codecs::ImageTransportCodecPluginBase< Codec >::decode ( const topic_tools::ShapeShifter compressed,
const dynamic_reconfigure::Config &  config 
) const
inlineoverridevirtual

Decode the given compressed image into a raw image.

Parameters
[in]compressedThe shapeshifter of the compressed image to be decoded.
[in]configConfig of the decompression (if it has any parameters).
Returns
The decoded raw image (if decoding succeeds), or an error message.

Implements image_transport_codecs::ImageTransportCodecPlugin.

Definition at line 157 of file image_transport_codec_plugin.h.

◆ encode()

template<typename Codec >
ImageTransportCodec::EncodeResult image_transport_codecs::ImageTransportCodecPluginBase< Codec >::encode ( const sensor_msgs::Image &  raw,
const dynamic_reconfigure::Config &  config 
) const
inlineoverridevirtual

Encode the given raw image into the given shapeshifter object.

Parameters
[in]rawThe input raw image.
[in]configConfig of the compression (if it has any parameters).
Returns
The output shapeshifter holding the compressed image message (if encoding succeeds), or an error message.

Implements image_transport_codecs::ImageTransportCodecPlugin.

Definition at line 151 of file image_transport_codec_plugin.h.

◆ getCompressedImageContent()

template<typename Codec >
ImageTransportCodec::GetCompressedContentResult image_transport_codecs::ImageTransportCodecPluginBase< Codec >::getCompressedImageContent ( const topic_tools::ShapeShifter compressed,
const std::string &  matchFormat 
) const
inlineoverridevirtual

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.

Parameters
[in]compressedThe 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.
Returns
If it makes sense, the contained image bytes. If not, empty result. If an error occurred, it is reported as the unexpected result.

Implements image_transport_codecs::ImageTransportCodecPlugin.

Definition at line 163 of file image_transport_codec_plugin.h.

◆ getTransportName()

template<typename Codec >
std::string image_transport_codecs::ImageTransportCodecPluginBase< Codec >::getTransportName ( ) const
inlineoverridevirtual

Get the name of the codec/transport (used e.g. as topic suffix).

Note
This name has to be unique among all defined codecs.
Returns
The transport name.

Implements image_transport_codecs::ImageTransportCodecPlugin.

Definition at line 146 of file image_transport_codec_plugin.h.

◆ setLogHelper()

template<typename Codec >
void image_transport_codecs::ImageTransportCodecPluginBase< Codec >::setLogHelper ( const cras::LogHelperPtr logHelper)
inlineoverridevirtual

Use the given log helper for logging messages.

Parameters
[in]logHelperThe log helper to use.

Implements image_transport_codecs::ImageTransportCodecPlugin.

Definition at line 141 of file image_transport_codec_plugin.h.

Member Data Documentation

◆ codec

template<typename Codec >
Codec image_transport_codecs::ImageTransportCodecPluginBase< Codec >::codec
private

The codec used by this plugin.

Definition at line 170 of file image_transport_codec_plugin.h.


The documentation for this class was generated from the following file:
compressed_codec.h
Image transport codec corresponding to compressed_image_transport.
class_list_macros.h
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
image_transport_codec_plugin.h
Plugin interface to image transport codecs which allows automatic selection of a suitable codec by Im...
image_transport_codecs
Definition: compressed_codec.h:29
image_transport_codecs::ImageTransportCodecPlugin
Basic interface of an image transport codec plugin.
Definition: image_transport_codec_plugin.h:58


image_transport_codecs
Author(s): Martin Pecka
autogenerated on Mon Jun 17 2024 02:49:15