Public Types | Public Member Functions | List of all members
image_transport_codecs::ImageTransportCodecPlugin Class Referenceabstract

Basic interface of an image transport codec plugin. More...

#include <image_transport_codec_plugin.h>

Inheritance diagram for image_transport_codecs::ImageTransportCodecPlugin:
Inheritance graph
[legend]

Public Types

typedef boost::shared_ptr< const ImageTransportCodecPluginConstPtr
 Shared pointer to const ImageTransportCodecPlugin. More...
 
typedef boost::shared_ptr< ImageTransportCodecPluginPtr
 Shared pointer to ImageTransportCodecPlugin. More...
 

Public Member Functions

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

Detailed Description

Basic interface of an image transport codec plugin.

Note
Do not forget to register the codec plugin library via pluginlib:
  • terminology: "codec library" is the C++ library implementing the ImageTransportCodec interface. "codec plugin library" is a different library (cannot be the same!) which implements the ImageTransportCodecPlugin interface.
  • put this at the beginning of the plugin .cpp file: #include <pluginlib/class_list_macros.h>
  • put this to the end of the plugin .cpp file: PLUGINLIB_EXPORT_CLASS(<PLUGIN>, image_transport_codecs::ImageTransportCodecPlugin)
    • substitute <PLUGIN> with the fully qualified name of your plugin class
  • do NOT add the codec plugin library to catkin_package(LIBRARIES...) in your CMakeLists.txt.
  • DO add the codec (not plugin) library to catkin_package(LIBRARIES...) in your CMakeLists.txt.
  • implement the plugin to be just a thin wrapper around the codec library (ImageTransportCodecPluginBase can make that really easy)
  • add <exec_depend>image_transport_codecs</exec_depend> to your package.xml
  • add <export><image_transport_codecs plugin="${prefix}/plugins.xml" /></export> to your package.xml
  • create file plugins.xml in the root of your package with the following content
    <library path="lib/libPLUGIN_LIB_NAME">
    <class name="image_transport_codecs/CODEC" type="PLUGIN"
    base_class_type="image_transport_codecs::ImageTransportCodecPlugin">
    <description>MY PLUGIN DESCRIPTION</description>
    </class>
    • substitute CODEC with the topic suffix your codec uses
    • substitute PLUGIN with the fully qualified name of your codec plugin class
    • substitute PLUGIN_LIB_NAME with the name of the dynamic library your codec plugin uses
    • substitute MY PLUGIN DESCRIPTION with some meaningful description of the codec
  • do not forget to install the codec library, codec plugin library, includes of the codec library and plugins.xml files in your CMakeLists.txt.

Definition at line 58 of file image_transport_codec_plugin.h.

Member Typedef Documentation

◆ ConstPtr

Shared pointer to const ImageTransportCodecPlugin.

Definition at line 65 of file image_transport_codec_plugin.h.

◆ Ptr

Shared pointer to ImageTransportCodecPlugin.

Definition at line 62 of file image_transport_codec_plugin.h.

Constructor & Destructor Documentation

◆ ~ImageTransportCodecPlugin()

virtual image_transport_codecs::ImageTransportCodecPlugin::~ImageTransportCodecPlugin ( )
virtualdefault

Member Function Documentation

◆ decode()

virtual ImageTransportCodec::DecodeResult image_transport_codecs::ImageTransportCodecPlugin::decode ( const topic_tools::ShapeShifter compressed,
const dynamic_reconfigure::Config &  config 
) const
pure virtual

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.

Implemented in image_transport_codecs::ImageTransportCodecPluginBase< Codec >.

◆ encode()

virtual ImageTransportCodec::EncodeResult image_transport_codecs::ImageTransportCodecPlugin::encode ( const sensor_msgs::Image &  raw,
const dynamic_reconfigure::Config &  config 
) const
pure virtual

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.

Implemented in image_transport_codecs::ImageTransportCodecPluginBase< Codec >.

◆ getCompressedImageContent()

virtual ImageTransportCodec::GetCompressedContentResult image_transport_codecs::ImageTransportCodecPlugin::getCompressedImageContent ( const topic_tools::ShapeShifter compressed,
const std::string &  matchFormat 
) const
pure virtual

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.

Implemented in image_transport_codecs::ImageTransportCodecPluginBase< Codec >.

◆ getTransportName()

virtual std::string image_transport_codecs::ImageTransportCodecPlugin::getTransportName ( ) const
pure virtual

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.

Implemented in image_transport_codecs::ImageTransportCodecPluginBase< Codec >.

◆ setLogHelper()

virtual void image_transport_codecs::ImageTransportCodecPlugin::setLogHelper ( const cras::LogHelperPtr logHelper)
pure virtual

Use the given log helper for logging messages.

Parameters
[in]logHelperThe log helper to use.

Implemented in image_transport_codecs::ImageTransportCodecPluginBase< Codec >.


The documentation for this class was generated from the following file:


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