image_transport_codec_plugin.h
Go to the documentation of this file.
1 #pragma once
2 
3 // SPDX-License-Identifier: BSD-3-Clause
4 // SPDX-FileCopyrightText: Czech Technical University in Prague
5 
13 #include <string>
14 
15 #include <dynamic_reconfigure/Config.h>
16 #include <sensor_msgs/Image.h>
17 #include <topic_tools/shape_shifter.h>
18 
21 
22 namespace image_transport_codecs
23 {
24 
59 {
60 public:
63 
66 
67  virtual ~ImageTransportCodecPlugin() = default;
68 
73  virtual void setLogHelper(const cras::LogHelperPtr& logHelper) = 0;
74 
80  virtual std::string getTransportName() const = 0;
81 
88  virtual ImageTransportCodec::EncodeResult encode(const sensor_msgs::Image& raw,
89  const dynamic_reconfigure::Config& config) const = 0;
90 
98  const dynamic_reconfigure::Config& config) const = 0;
99 
111  const topic_tools::ShapeShifter& compressed, const std::string& matchFormat) const = 0;
112 };
113 
137 template<typename Codec>
139 {
140 public:
141  void setLogHelper(const cras::LogHelperPtr& logHelper) override
142  {
143  this->codec.setCrasLogger(logHelper);
144  }
145 
146  std::string getTransportName() const override
147  {
148  return this->codec.getTransportName();
149  }
150 
151  ImageTransportCodec::EncodeResult encode(const sensor_msgs::Image& raw,
152  const dynamic_reconfigure::Config& config) const override
153  {
154  return this->codec.encode(raw, config);
155  }
156 
158  const dynamic_reconfigure::Config& config) const override
159  {
160  return this->codec.decode(compressed, config);
161  }
162 
164  const topic_tools::ShapeShifter& compressed, const std::string& matchFormat) const override
165  {
166  return this->codec.getCompressedImageContent(compressed, matchFormat);
167  }
168 
169 private:
170  Codec codec;
171 };
172 
173 }
image_transport_codecs::ImageTransportCodecPlugin::ConstPtr
boost::shared_ptr< const ImageTransportCodecPlugin > ConstPtr
Shared pointer to const ImageTransportCodecPlugin.
Definition: image_transport_codec_plugin.h:65
image_transport_codecs::ImageTransportCodecPluginBase::setLogHelper
void setLogHelper(const cras::LogHelperPtr &logHelper) override
Use the given log helper for logging messages.
Definition: image_transport_codec_plugin.h:141
boost::shared_ptr
image_transport_codecs::ImageTransportCodecPluginBase::codec
Codec codec
The codec used by this plugin.
Definition: image_transport_codec_plugin.h:170
image_transport_codecs::ImageTransportCodecPlugin::getTransportName
virtual std::string getTransportName() const =0
Get the name of the codec/transport (used e.g. as topic suffix).
image_transport_codecs::ImageTransportCodec::DecodeResult
cras::expected< sensor_msgs::Image, std::string > DecodeResult
Result of image decoding. Either a sensor_msgs::Image holding the raw message, or error message.
Definition: image_transport_codec.h:95
image_transport_codecs::ImageTransportCodec::GetCompressedContentResult
cras::expected< cras::optional< CompressedImageContent >, std::string > GetCompressedContentResult
Result of getting the actual compressed image data.
Definition: image_transport_codec.h:98
log_utils.h
image_transport_codec.h
Base for all image transport codecs.
image_transport_codecs::ImageTransportCodecPlugin::~ImageTransportCodecPlugin
virtual ~ImageTransportCodecPlugin()=default
image_transport_codecs::ImageTransportCodecPlugin::Ptr
boost::shared_ptr< ImageTransportCodecPlugin > Ptr
Shared pointer to ImageTransportCodecPlugin.
Definition: image_transport_codec_plugin.h:62
image_transport_codecs::ImageTransportCodecPluginBase::decode
ImageTransportCodec::DecodeResult decode(const topic_tools::ShapeShifter &compressed, const dynamic_reconfigure::Config &config) const override
Decode the given compressed image into a raw image.
Definition: image_transport_codec_plugin.h:157
image_transport_codecs::ImageTransportCodecPlugin::getCompressedImageContent
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....
image_transport_codecs::ImageTransportCodecPluginBase::getTransportName
std::string getTransportName() const override
Get the name of the codec/transport (used e.g. as topic suffix).
Definition: image_transport_codec_plugin.h:146
image_transport_codecs::ImageTransportCodecPlugin::encode
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.
image_transport_codecs::ImageTransportCodecPluginBase
Convenience class for implementing image transport codec plugins, which just relays the whole API to ...
Definition: image_transport_codec_plugin.h:138
image_transport_codecs::ImageTransportCodecPluginBase::encode
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.
Definition: image_transport_codec_plugin.h:151
image_transport_codecs::ImageTransportCodecPluginBase::getCompressedImageContent
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....
Definition: image_transport_codec_plugin.h:163
cras::LogHelperPtr
::cras::LogHelper::Ptr LogHelperPtr
image_transport_codecs
Definition: compressed_codec.h:29
image_transport_codecs::ImageTransportCodecPlugin::setLogHelper
virtual void setLogHelper(const cras::LogHelperPtr &logHelper)=0
Use the given log helper for logging messages.
topic_tools::ShapeShifter
image_transport_codecs::ImageTransportCodec::EncodeResult
cras::expected< cras::ShapeShifter, std::string > EncodeResult
Result of image encoding. Either a shapeshifter holding the compressed message, or error message.
Definition: image_transport_codec.h:92
image_transport_codecs::ImageTransportCodecPlugin::decode
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.
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