Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
image_transport_codecs::ImageTransportCodecs Class Reference

Plugin-based interface for compressing and decompressing images using codec plugins. More...

#include <image_transport_codecs.h>

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

Public Member Functions

void addCodec (const ImageTransportCodecPlugin::ConstPtr &codec)
 Manually add a codec instance. This is usually not needed as the codecs are autodetected using pluginlib. More...
 
virtual ImageTransportCodec::DecodeResult decode (const topic_tools::ShapeShifter &compressed, const std::string &topicOrCodec, const dynamic_reconfigure::Config &config)
 Decode the given compressed image shapeshifter into a raw image. More...
 
ImageTransportCodec::DecodeResult decode (const topic_tools::ShapeShifter &compressed, const std::string &topicOrCodec)
 Decode the given compressed image shapeshifter into a raw image using the default decompression parameters. More...
 
ImageTransportCodec::DecodeResult decode (const topic_tools::ShapeShifter &compressed, const std::string &topicOrCodec, const XmlRpc::XmlRpcValue &config)
 Decode the given compressed image shapeshifter into a raw image. More...
 
ImageTransportCodec::DecodeResult decode (const topic_tools::ShapeShifter &compressed, const std::string &topicOrCodec, const ros::NodeHandle &nh, const std::string &param)
 Decode the given compressed image shapeshifter into a raw image. More...
 
template<typename Config >
ImageTransportCodec::DecodeResult decode (const topic_tools::ShapeShifter &compressed, const std::string &topicOrCodec, const Config &config)
 Decode the given compressed image shapeshifter into a raw image. More...
 
template<typename M >
ImageTransportCodec::DecodeResult decodeTyped (const M &compressed, const std::string &topicOrCodec, const dynamic_reconfigure::Config &config)
 Decode the given compressed image into a raw image. More...
 
template<typename M >
ImageTransportCodec::DecodeResult decodeTyped (const M &compressed, const std::string &topicOrCodec)
 Decode the given compressed image into a raw image using the default decompression parameters. More...
 
template<typename M >
ImageTransportCodec::DecodeResult decodeTyped (const M &compressed, const std::string &topicOrCodec, const XmlRpc::XmlRpcValue &config)
 Decode the given compressed image into a raw image. More...
 
template<typename M >
ImageTransportCodec::DecodeResult decodeTyped (const M &compressed, const std::string &topicOrCodec, const ros::NodeHandle &nh, const std::string &param)
 Decode the given compressed image into a raw image. More...
 
template<typename M , typename Config >
ImageTransportCodec::DecodeResult decodeTyped (const M &compressed, const std::string &topicOrCodec, const Config &config)
 Decode the given compressed image into a raw image. More...
 
virtual ImageTransportCodec::EncodeResult encode (const sensor_msgs::Image &raw, const std::string &topicOrCodec, const dynamic_reconfigure::Config &config)
 Encode the given raw image into a compressed image shapeshifter. More...
 
ImageTransportCodec::EncodeResult encode (const sensor_msgs::Image &raw, const std::string &topicOrCodec)
 Encode the given raw image into a compressed image shapeshifter using the default compression parameters. More...
 
ImageTransportCodec::EncodeResult encode (const sensor_msgs::Image &raw, const std::string &topicOrCodec, const XmlRpc::XmlRpcValue &config)
 Encode the given raw image into a compressed image shapeshifter. More...
 
ImageTransportCodec::EncodeResult encode (const sensor_msgs::Image &raw, const std::string &topicOrCodec, const ros::NodeHandle &nh, const std::string &param)
 Encode the given raw image into a compressed image shapeshifter. More...
 
template<typename Config >
ImageTransportCodec::EncodeResult encode (const sensor_msgs::Image &raw, const std::string &topicOrCodec, const Config &config)
 Encode the given raw image into a compressed image shapeshifter. More...
 
template<typename M >
cras::expected< M, std::string > encodeTyped (const sensor_msgs::Image &raw, const std::string &topicOrCodec, const dynamic_reconfigure::Config &config)
 Encode the given raw image into a compressed image. More...
 
template<typename M >
cras::expected< M, std::string > encodeTyped (const sensor_msgs::Image &raw, const std::string &topicOrCodec)
 Encode the given raw image into a compressed image using the default compression parameters. More...
 
template<typename M >
cras::expected< M, std::string > encodeTyped (const sensor_msgs::Image &raw, const std::string &topicOrCodec, const XmlRpc::XmlRpcValue &config)
 Encode the given raw image into a compressed image. More...
 
template<typename M >
cras::expected< M, std::string > encodeTyped (const sensor_msgs::Image &raw, const std::string &topicOrCodec, const ros::NodeHandle &nh, const std::string &param)
 Encode the given raw image into a compressed image. More...
 
template<typename M , typename Config >
cras::expected< M, std::string > encodeTyped (const sensor_msgs::Image &raw, const std::string &topicOrCodec, const Config &config)
 Encode the given raw image into a compressed image. More...
 
virtual ImageTransportCodec::GetCompressedContentResult getCompressedImageContent (const topic_tools::ShapeShifter &compressed, const std::string &topicOrCodec, const std::string &matchFormat) 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...
 
ImageTransportCodec::GetCompressedContentResult getCompressedImageContent (const topic_tools::ShapeShifter &compressed, const std::string &topicOrCodec) 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...
 
 ImageTransportCodecs (const cras::LogHelperPtr &log=std::make_shared< cras::NodeLogHelper >())
 Create the codec interface and load all available codecs. More...
 
virtual ~ImageTransportCodecs ()
 
- Public Member Functions inherited from cras::HasLogger
::cras::LogHelperConstPtr getCrasLogger () const
 
 HasLogger (const ::cras::LogHelperPtr &log)
 
void setCrasLogger (const ::cras::LogHelperPtr &log)
 

Protected Member Functions

void loadCodecs ()
 Load all codecs available via pluginlib. This function can be called multiple times without negative performance impact - the loading is only done for the first time. More...
 
std::string parseTransport (const std::string &topicOrCodec) const
 Parse the name of the codec from a topic. More...
 

Protected Attributes

std::unordered_map< std::string, ImageTransportCodecPlugin::ConstPtrcodecs
 Loaded codecs. More...
 
std::unique_ptr< pluginlib::ClassLoader< ImageTransportCodecPlugin > > loader
 Pluginlib loader of codecs. More...
 
- Protected Attributes inherited from cras::HasLogger
::cras::LogHelperPtr log
 

Detailed Description

Plugin-based interface for compressing and decompressing images using codec plugins.

Example usage:

sensor_msgs::Image raw = ...;
auto result = codecs.encode(raw, "compressed");
if (!result)
{
ROS_ERROR_STREAM("Error encoding image: " << result.error();
return false;
}
sensor_msgs::CompressedImage compressed = result.value();

Definition at line 48 of file image_transport_codecs.h.

Constructor & Destructor Documentation

◆ ImageTransportCodecs()

image_transport_codecs::ImageTransportCodecs::ImageTransportCodecs ( const cras::LogHelperPtr log = std::make_shared< cras::NodeLogHelper >())
explicit

Create the codec interface and load all available codecs.

Parameters
[in]logLog helper.

◆ ~ImageTransportCodecs()

virtual image_transport_codecs::ImageTransportCodecs::~ImageTransportCodecs ( )
virtual

Member Function Documentation

◆ addCodec()

void image_transport_codecs::ImageTransportCodecs::addCodec ( const ImageTransportCodecPlugin::ConstPtr codec)

Manually add a codec instance. This is usually not needed as the codecs are autodetected using pluginlib.

Parameters
[in]codecThe codec to add.

◆ decode() [1/5]

virtual ImageTransportCodec::DecodeResult image_transport_codecs::ImageTransportCodecs::decode ( const topic_tools::ShapeShifter compressed,
const std::string &  topicOrCodec,
const dynamic_reconfigure::Config &  config 
)
virtual

Decode the given compressed image shapeshifter into a raw image.

Parameters
[in]compressedThe shapeshifter of the compressed image to be decoded.
[in]topicOrCodecEither the output of a codec's getTransportName(), or name of a topic from which the compressed message was received (so that it is possible to parse the codec from the topic). Do not pass the raw image topic - that would result in using RawCodecPlugin which you probably do not want.
[in]configConfig of the decompression (if it has any parameters).
Returns
The decoded raw image (if decoding succeeds), or an error message.

◆ decode() [2/5]

ImageTransportCodec::DecodeResult image_transport_codecs::ImageTransportCodecs::decode ( const topic_tools::ShapeShifter compressed,
const std::string &  topicOrCodec 
)

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

Parameters
[in]compressedThe shapeshifter of the compressed image to be decoded.
[in]topicOrCodecEither the output of a codec's getTransportName(), or name of a topic from which the compressed message was received (so that it is possible to parse the codec from the topic). Do not pass the raw image topic - that would result in using RawCodecPlugin which you probably do not want.
Returns
The decoded raw image (if decoding succeeds), or an error message.

◆ decode() [3/5]

ImageTransportCodec::DecodeResult image_transport_codecs::ImageTransportCodecs::decode ( const topic_tools::ShapeShifter compressed,
const std::string &  topicOrCodec,
const XmlRpc::XmlRpcValue config 
)

Decode the given compressed image shapeshifter into a raw image.

Parameters
[in]compressedThe shapeshifter of the compressed image to be decoded.
[in]topicOrCodecEither the output of a codec's getTransportName(), or name of a topic from which the compressed message was received (so that it is possible to parse the codec from the topic). Do not pass the raw image topic - that would result in using RawCodecPlugin which you probably do not want.
[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]

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

Decode the given compressed image shapeshifter into a raw image.

Parameters
[in]compressedThe shapeshifter of the compressed image to be decoded.
[in]topicOrCodecEither the output of a codec's getTransportName(), or name of a topic from which the compressed message was received (so that it is possible to parse the codec from the topic). Do not pass the raw image topic - that would result in using RawCodecPlugin which you probably do not want.
[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 >
ImageTransportCodec::DecodeResult image_transport_codecs::ImageTransportCodecs::decode ( const topic_tools::ShapeShifter compressed,
const std::string &  topicOrCodec,
const Config &  config 
)
inline

Decode the given compressed image shapeshifter 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]topicOrCodecEither the output of a codec's getTransportName(), or name of a topic from which the compressed message was received (so that it is possible to parse the codec from the topic). Do not pass the raw image topic - that would result in using RawCodecPlugin which you probably do not want.
[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 235 of file image_transport_codecs.h.

◆ decodeTyped() [1/5]

template<typename M >
ImageTransportCodec::DecodeResult image_transport_codecs::ImageTransportCodecs::decodeTyped ( const M &  compressed,
const std::string &  topicOrCodec,
const dynamic_reconfigure::Config &  config 
)
inline

Decode the given compressed image into a raw image.

Template Parameters
MType of the compressed message.
Parameters
[in]compressedThe compressed image to be decoded.
[in]topicOrCodecEither the output of a codec's getTransportName(), or name of a topic from which the compressed message was received (so that it is possible to parse the codec from the topic). Do not pass the raw image topic - that would result in using RawCodecPlugin which you probably do not want.
[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 284 of file image_transport_codecs.h.

◆ decodeTyped() [2/5]

template<typename M >
ImageTransportCodec::DecodeResult image_transport_codecs::ImageTransportCodecs::decodeTyped ( const M &  compressed,
const std::string &  topicOrCodec 
)
inline

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

Template Parameters
MType of the compressed message.
Parameters
[in]compressedThe compressed image to be decoded.
[in]topicOrCodecEither the output of a codec's getTransportName(), or name of a topic from which the compressed message was received (so that it is possible to parse the codec from the topic). Do not pass the raw image topic - that would result in using RawCodecPlugin which you probably do not want.
Returns
The decoded raw image (if decoding succeeds), or an error message.

Definition at line 319 of file image_transport_codecs.h.

◆ decodeTyped() [3/5]

template<typename M >
ImageTransportCodec::DecodeResult image_transport_codecs::ImageTransportCodecs::decodeTyped ( const M &  compressed,
const std::string &  topicOrCodec,
const XmlRpc::XmlRpcValue config 
)
inline

Decode the given compressed image into a raw image.

Template Parameters
MType of the compressed message.
Parameters
[in]compressedThe compressed image to be decoded.
[in]topicOrCodecEither the output of a codec's getTransportName(), or name of a topic from which the compressed message was received (so that it is possible to parse the codec from the topic). Do not pass the raw image topic - that would result in using RawCodecPlugin which you probably do not want.
[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.

Definition at line 359 of file image_transport_codecs.h.

◆ decodeTyped() [4/5]

template<typename M >
ImageTransportCodec::DecodeResult image_transport_codecs::ImageTransportCodecs::decodeTyped ( const M &  compressed,
const std::string &  topicOrCodec,
const ros::NodeHandle nh,
const std::string &  param 
)
inline

Decode the given compressed image into a raw image.

Template Parameters
MType of the compressed message.
Parameters
[in]compressedThe compressed image to be decoded.
[in]topicOrCodecEither the output of a codec's getTransportName(), or name of a topic from which the compressed message was received (so that it is possible to parse the codec from the topic). Do not pass the raw image topic - that would result in using RawCodecPlugin which you probably do not want.
[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.

Definition at line 403 of file image_transport_codecs.h.

◆ decodeTyped() [5/5]

template<typename M , typename Config >
ImageTransportCodec::DecodeResult image_transport_codecs::ImageTransportCodecs::decodeTyped ( const M &  compressed,
const std::string &  topicOrCodec,
const Config &  config 
)
inline

Decode the given compressed image into a raw image.

Template Parameters
MType of the compressed message.
ConfigType of the config object. This should be the generated dynamic_reconfigure interface of the corresponding image_transport publisher.
Parameters
[in]compressedThe compressed image to be decoded.
[in]topicOrCodecEither the output of a codec's getTransportName(), or name of a topic from which the compressed message was received (so that it is possible to parse the codec from the topic). Do not pass the raw image topic - that would result in using RawCodecPlugin which you probably do not want.
[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 445 of file image_transport_codecs.h.

◆ encode() [1/5]

virtual ImageTransportCodec::EncodeResult image_transport_codecs::ImageTransportCodecs::encode ( const sensor_msgs::Image &  raw,
const std::string &  topicOrCodec,
const dynamic_reconfigure::Config &  config 
)
virtual

Encode the given raw image into a compressed image shapeshifter.

Parameters
[in]rawThe input raw image.
[in]topicOrCodecEither the output of a codec's getTransportName(), or name of a topic where the compressed message will be published (so that it is possible to parse the codec from the topic). Do not pass the raw image topic - that would result in using RawCodecPlugin which you probably do not want.
[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.

◆ encode() [2/5]

ImageTransportCodec::EncodeResult image_transport_codecs::ImageTransportCodecs::encode ( const sensor_msgs::Image &  raw,
const std::string &  topicOrCodec 
)

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

Parameters
[in]rawThe input raw image.
[in]topicOrCodecEither the output of a codec's getTransportName(), or name of a topic where the compressed message will be published (so that it is possible to parse the codec from the topic). Do not pass the raw image topic - that would result in using RawCodecPlugin which you probably do not want.
Returns
The output shapeshifter holding the compressed image message (if encoding succeeds), or an error message.

◆ encode() [3/5]

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

Encode the given raw image into a compressed image shapeshifter.

Parameters
[in]rawThe input raw image.
[in]topicOrCodecEither the output of a codec's getTransportName(), or name of a topic where the compressed message will be published (so that it is possible to parse the codec from the topic). Do not pass the raw image topic - that would result in using RawCodecPlugin which you probably do not want.
[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]

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

Encode the given raw image into a compressed image shapeshifter.

Parameters
[in]rawThe input raw image.
[in]topicOrCodecEither the output of a codec's getTransportName(), or name of a topic where the compressed message will be published (so that it is possible to parse the codec from the topic). Do not pass the raw image topic - that would result in using RawCodecPlugin which you probably do not want.
[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 >
ImageTransportCodec::EncodeResult image_transport_codecs::ImageTransportCodecs::encode ( const sensor_msgs::Image &  raw,
const std::string &  topicOrCodec,
const Config &  config 
)
inline

Encode the given raw image into a compressed image shapeshifter.

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]topicOrCodecEither the output of a codec's getTransportName(), or name of a topic where the compressed message will be published (so that it is possible to parse the codec from the topic). Do not pass the raw image topic - that would result in using RawCodecPlugin which you probably do not want.
[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_codecs.h.

◆ encodeTyped() [1/5]

template<typename M >
cras::expected<M, std::string> image_transport_codecs::ImageTransportCodecs::encodeTyped ( const sensor_msgs::Image &  raw,
const std::string &  topicOrCodec,
const dynamic_reconfigure::Config &  config 
)
inline

Encode the given raw image into a compressed image.

Template Parameters
MType of the compressed message.
Parameters
[in]rawThe input raw image.
[in]topicOrCodecEither the output of a codec's getTransportName(), or name of a topic where the compressed message will be published (so that it is possible to parse the codec from the topic). Do not pass the raw image topic - that would result in using RawCodecPlugin which you probably do not want.
[in]configConfig of the compression (if it has any parameters).
Returns
The compressed image message (if encoding succeeds), or an error message.

Definition at line 255 of file image_transport_codecs.h.

◆ encodeTyped() [2/5]

template<typename M >
cras::expected<M, std::string> image_transport_codecs::ImageTransportCodecs::encodeTyped ( const sensor_msgs::Image &  raw,
const std::string &  topicOrCodec 
)
inline

Encode the given raw image into a compressed image using the default compression parameters.

Template Parameters
MType of the compressed message.
Parameters
[in]rawThe input raw image.
[in]topicOrCodecEither the output of a codec's getTransportName(), or name of a topic where the compressed message will be published (so that it is possible to parse the codec from the topic). Do not pass the raw image topic - that would result in using RawCodecPlugin which you probably do not want.
Returns
The compressed image message (if encoding succeeds), or an error message.

Definition at line 303 of file image_transport_codecs.h.

◆ encodeTyped() [3/5]

template<typename M >
cras::expected<M, std::string> image_transport_codecs::ImageTransportCodecs::encodeTyped ( const sensor_msgs::Image &  raw,
const std::string &  topicOrCodec,
const XmlRpc::XmlRpcValue config 
)
inline

Encode the given raw image into a compressed image.

Template Parameters
MType of the compressed message.
Parameters
[in]rawThe input raw image.
[in]topicOrCodecEither the output of a codec's getTransportName(), or name of a topic where the compressed message will be published (so that it is possible to parse the codec from the topic). Do not pass the raw image topic - that would result in using RawCodecPlugin which you probably do not want.
[in]configConfig of the compression (if it has any parameters). Pass a XmlRpc dict.
Returns
The compressed image message (if encoding succeeds), or an error message.

Definition at line 336 of file image_transport_codecs.h.

◆ encodeTyped() [4/5]

template<typename M >
cras::expected<M, std::string> image_transport_codecs::ImageTransportCodecs::encodeTyped ( const sensor_msgs::Image &  raw,
const std::string &  topicOrCodec,
const ros::NodeHandle nh,
const std::string &  param 
)
inline

Encode the given raw image into a compressed image.

Template Parameters
MType of the compressed message.
Parameters
[in]rawThe input raw image.
[in]topicOrCodecEither the output of a codec's getTransportName(), or name of a topic where the compressed message will be published (so that it is possible to parse the codec from the topic). Do not pass the raw image topic - that would result in using RawCodecPlugin which you probably do not want.
[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 compressed image message (if encoding succeeds), or an error message.

Definition at line 383 of file image_transport_codecs.h.

◆ encodeTyped() [5/5]

template<typename M , typename Config >
cras::expected<M, std::string> image_transport_codecs::ImageTransportCodecs::encodeTyped ( const sensor_msgs::Image &  raw,
const std::string &  topicOrCodec,
const Config &  config 
)
inline

Encode the given raw image into a compressed image.

Template Parameters
MType of the compressed message.
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]topicOrCodecEither the output of a codec's getTransportName(), or name of a topic where the compressed message will be published (so that it is possible to parse the codec from the topic). Do not pass the raw image topic - that would result in using RawCodecPlugin which you probably do not want.
[in]configConfig of the compression (if it has any parameters).
Returns
The compressed image message (if encoding succeeds), or an error message.

Definition at line 423 of file image_transport_codecs.h.

◆ getCompressedImageContent() [1/2]

virtual ImageTransportCodec::GetCompressedContentResult image_transport_codecs::ImageTransportCodecs::getCompressedImageContent ( const topic_tools::ShapeShifter compressed,
const std::string &  topicOrCodec,
const std::string &  matchFormat 
) const
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]topicOrCodecEither the output of a codec's getTransportName(), or name of a topic from which the compressed message was received (so that it is possible to parse the codec from the topic). Do not pass the raw image topic - that would result in using RawCodecPlugin which you probably do not want.
[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.

◆ getCompressedImageContent() [2/2]

ImageTransportCodec::GetCompressedContentResult image_transport_codecs::ImageTransportCodecs::getCompressedImageContent ( const topic_tools::ShapeShifter compressed,
const std::string &  topicOrCodec 
) 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.
[in]topicOrCodecEither the output of a codec's getTransportName(), or name of a topic from which the compressed message was received (so that it is possible to parse the codec from the topic). Do not pass the raw image topic - that would result in using RawCodecPlugin which you probably do not want.
Returns
If it makes sense, the contained image bytes. If not, empty result. If an error occurred, it is reported as the unexpected result.

◆ loadCodecs()

void image_transport_codecs::ImageTransportCodecs::loadCodecs ( )
protected

Load all codecs available via pluginlib. This function can be called multiple times without negative performance impact - the loading is only done for the first time.

◆ parseTransport()

std::string image_transport_codecs::ImageTransportCodecs::parseTransport ( const std::string &  topicOrCodec) const
protected

Parse the name of the codec from a topic.

Parameters
[in]topicOrCodecEither the output of a codec's getTransportName(), or name of an image topic.
Returns
Name of the codec, or empty string if not found.

Member Data Documentation

◆ codecs

std::unordered_map<std::string, ImageTransportCodecPlugin::ConstPtr> image_transport_codecs::ImageTransportCodecs::codecs
protected

Loaded codecs.

Definition at line 468 of file image_transport_codecs.h.

◆ loader

std::unique_ptr<pluginlib::ClassLoader<ImageTransportCodecPlugin> > image_transport_codecs::ImageTransportCodecs::loader
protected

Pluginlib loader of codecs.

Definition at line 467 of file image_transport_codecs.h.


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