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

Base for all image transport codecs. All codecs have to extend class ImageTransportCodec and implement the pure virtual methods std::string getTransportName() const, encode(const sensor_msgs::Image&, const dynamic_reconfigure::Config&) const and decode(const topic_tools::ShapeShifter&, const dynamic_reconfigure::Config&) const. There are other convenience methods provided, but all of them are based on these implementations. More...

#include <image_transport_codec.h>

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

Public Types

typedef boost::shared_ptr< const ImageTransportCodecConstPtr
 Shared pointer to const ImageTransportCodec. More...
 
typedef cras::expected< sensor_msgs::Image, std::string > DecodeResult
 Result of image decoding. Either a sensor_msgs::Image holding the raw message, or error message. More...
 
typedef cras::expected< cras::ShapeShifter, std::string > EncodeResult
 Result of image encoding. Either a shapeshifter holding the compressed message, or error message. More...
 
typedef cras::expected< cras::optional< CompressedImageContent >, std::string > GetCompressedContentResult
 Result of getting the actual compressed image data. More...
 
typedef boost::shared_ptr< ImageTransportCodecPtr
 Shared pointer to ImageTransportCodec. More...
 

Public Member Functions

virtual DecodeResult decode (const topic_tools::ShapeShifter &compressed, const dynamic_reconfigure::Config &config) const =0
 Decode the given compressed image into a raw image. More...
 
DecodeResult decode (const topic_tools::ShapeShifter &compressed) const
 Decode the given compressed image into a raw image using the default decompression parameters. More...
 
DecodeResult decode (const topic_tools::ShapeShifter &compressed, const XmlRpc::XmlRpcValue &config) const
 Decode the given compressed image into a raw image. More...
 
DecodeResult decode (const topic_tools::ShapeShifter &compressed, const ros::NodeHandle &nh, const std::string &param) const
 Decode the given compressed image into a raw image. More...
 
template<typename Config >
DecodeResult decode (const topic_tools::ShapeShifter &compressed, const Config &config) const
 Decode the given compressed image into a raw image. More...
 
virtual 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...
 
EncodeResult encode (const sensor_msgs::Image &raw) const
 Encode the given raw image into the given shapeshifter object using the default compression parameters. More...
 
EncodeResult encode (const sensor_msgs::Image &raw, const XmlRpc::XmlRpcValue &config) const
 Encode the given raw image into the given shapeshifter object. More...
 
EncodeResult encode (const sensor_msgs::Image &raw, const ros::NodeHandle &nh, const std::string &param) const
 Encode the given raw image into the given shapeshifter object. More...
 
template<typename Config >
EncodeResult encode (const sensor_msgs::Image &raw, const Config &config) const
 Encode the given raw image into the given shapeshifter object. More...
 
virtual 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...
 
GetCompressedContentResult getCompressedImageContent (const topic_tools::ShapeShifter &compressed) const
 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...
 
 ImageTransportCodec (const cras::LogHelperPtr &logHelper)
 Create an instance of the codec. More...
 
virtual ~ImageTransportCodec ()
 
- Public Member Functions inherited from cras::HasLogger
::cras::LogHelperConstPtr getCrasLogger () const
 
 HasLogger (const ::cras::LogHelperPtr &log)
 
void setCrasLogger (const ::cras::LogHelperPtr &log)
 

Additional Inherited Members

- Protected Attributes inherited from cras::HasLogger
::cras::LogHelperPtr log
 

Detailed Description

Base for all image transport codecs. All codecs have to extend class ImageTransportCodec and implement the pure virtual methods std::string getTransportName() const, encode(const sensor_msgs::Image&, const dynamic_reconfigure::Config&) const and decode(const topic_tools::ShapeShifter&, const dynamic_reconfigure::Config&) const. There are other convenience methods provided, but all of them are based on these implementations.

Each codec should be implemented as a standalone library for direct use, and also as a plugin inheriting from ImageTransportCodecPlugin for generic use via ImageTransportCodecs.

Note
As there is no common superclass for ROS messages and each codec can output compressed messages of different type, the generic interface for the compressed messages is ShapeShifter. The good thing is it offers a really generic way of working with messages. The bad thing is that it does that through (de)serialization of the messages, which might become a bottleneck in high-performance applications. Therefore, if you know the codec in advance, you should directly use the concrete codec and not this generic interface.
Note
The EncodeResult and DecodeResult types used for outputs of the API functions make use of cras::expected, which is an implementation of the proposed std::expected template. Generally, expected can either hold the result (in the expected case), or an error (in the unexpected case). So after getting the encoding/decoding result, you always first have to check it for validity (if (!result) return false). On a valid result, you can call cras::expected::value() to get the expected object. On an invalid result, you can call cras::expected::error() to get the error message.
Note
Throughout this interface, you will see usages of cras::ShapeShifter instead of topic_tools::ShapeShifter. These two are the same API-wise, but cras::ShapeShifter contains a super-important bugfix without which your programs would quickly segfault. Generally, it is not safe to make copies of topic_tools::ShapeShifter (not even returning it from functions!). cras::ShapeShifter makes copying possible. Note that it is safe to pass around references to topic_tools::ShapeShifter (but you can never copy the objects).

Definition at line 81 of file image_transport_codec.h.

Member Typedef Documentation

◆ ConstPtr

Shared pointer to const ImageTransportCodec.

Definition at line 88 of file image_transport_codec.h.

◆ DecodeResult

typedef cras::expected<sensor_msgs::Image, std::string> image_transport_codecs::ImageTransportCodec::DecodeResult

Result of image decoding. Either a sensor_msgs::Image holding the raw message, or error message.

Definition at line 95 of file image_transport_codec.h.

◆ EncodeResult

Result of image encoding. Either a shapeshifter holding the compressed message, or error message.

Definition at line 92 of file image_transport_codec.h.

◆ GetCompressedContentResult

Result of getting the actual compressed image data.

Definition at line 98 of file image_transport_codec.h.

◆ Ptr

Shared pointer to ImageTransportCodec.

Definition at line 85 of file image_transport_codec.h.

Constructor & Destructor Documentation

◆ ImageTransportCodec()

image_transport_codecs::ImageTransportCodec::ImageTransportCodec ( const cras::LogHelperPtr logHelper)
explicit

Create an instance of the codec.

Parameters
[in]logHelperThe logger to use for error messages not directly related to the currently processed image.

◆ ~ImageTransportCodec()

virtual image_transport_codecs::ImageTransportCodec::~ImageTransportCodec ( )
virtual

Member Function Documentation

◆ decode() [1/5]

virtual DecodeResult image_transport_codecs::ImageTransportCodec::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::CompressedCodec, and image_transport_codecs::CompressedDepthCodec.

◆ decode() [2/5]

DecodeResult image_transport_codecs::ImageTransportCodec::decode ( const topic_tools::ShapeShifter compressed) const

Decode the given compressed image into a raw image using the default decompression parameters.

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

◆ decode() [3/5]

DecodeResult image_transport_codecs::ImageTransportCodec::decode ( const topic_tools::ShapeShifter compressed,
const XmlRpc::XmlRpcValue config 
) const

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). Pass a XmlRpc dict.
Returns
The decoded raw image (if decoding succeeds), or an error message.

◆ decode() [4/5]

DecodeResult image_transport_codecs::ImageTransportCodec::decode ( const topic_tools::ShapeShifter compressed,
const ros::NodeHandle nh,
const std::string &  param 
) const

Decode the given compressed image into a raw image.

Parameters
[in]compressedThe shapeshifter of the compressed image to be decoded.
[in]nhNode handle to get parameters from.
[in]paramName of the parameter from which config of the decompression can be read (if it has any parameters).
Returns
The decoded raw image (if decoding succeeds), or an error message.

◆ decode() [5/5]

template<typename Config >
DecodeResult image_transport_codecs::ImageTransportCodec::decode ( const topic_tools::ShapeShifter compressed,
const Config &  config 
) const
inline

Decode the given compressed image into a raw image.

Template Parameters
ConfigType of the config object. This should be the generated dynamic_reconfigure interface of the corresponding image_transport subscriber.
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.

Definition at line 230 of file image_transport_codec.h.

◆ encode() [1/5]

virtual EncodeResult image_transport_codecs::ImageTransportCodec::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::CompressedCodec, and image_transport_codecs::CompressedDepthCodec.

◆ encode() [2/5]

EncodeResult image_transport_codecs::ImageTransportCodec::encode ( const sensor_msgs::Image &  raw) const

Encode the given raw image into the given shapeshifter object using the default compression parameters.

Parameters
[in]rawThe input raw image.
Returns
The output shapeshifter holding the compressed image message (if encoding succeeds), or an error message.

◆ encode() [3/5]

EncodeResult image_transport_codecs::ImageTransportCodec::encode ( const sensor_msgs::Image &  raw,
const XmlRpc::XmlRpcValue config 
) const

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). Pass a XmlRpc dict.
Returns
The output shapeshifter holding the compressed image message (if encoding succeeds), or an error message.

◆ encode() [4/5]

EncodeResult image_transport_codecs::ImageTransportCodec::encode ( const sensor_msgs::Image &  raw,
const ros::NodeHandle nh,
const std::string &  param 
) const

Encode the given raw image into the given shapeshifter object.

Parameters
[in]rawThe input raw image.
[in]nhNode handle to get parameters from.
[in]paramName of the parameter from which config of the compression can be read (if it has any parameters).
Returns
The output shapeshifter holding the compressed image message (if encoding succeeds), or an error message.

◆ encode() [5/5]

template<typename Config >
EncodeResult image_transport_codecs::ImageTransportCodec::encode ( const sensor_msgs::Image &  raw,
const Config &  config 
) const
inline

Encode the given raw image into the given shapeshifter object.

Template Parameters
ConfigType of the config object. This should be the generated dynamic_reconfigure interface of the corresponding image_transport publisher.
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.

Definition at line 214 of file image_transport_codec.h.

◆ getCompressedImageContent() [1/2]

virtual GetCompressedContentResult image_transport_codecs::ImageTransportCodec::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::CompressedCodec, and image_transport_codecs::CompressedDepthCodec.

◆ getCompressedImageContent() [2/2]

GetCompressedContentResult image_transport_codecs::ImageTransportCodec::getCompressedImageContent ( const topic_tools::ShapeShifter compressed) const

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

◆ getTransportName()

virtual std::string image_transport_codecs::ImageTransportCodec::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::CompressedCodec, and image_transport_codecs::CompressedDepthCodec.


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