image_transport_codec.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 
12 #include <string>
13 #include <vector>
14 
15 #include <dynamic_reconfigure/Config.h>
16 #include <ros/node_handle.h>
17 #include <sensor_msgs/Image.h>
18 #include <topic_tools/shape_shifter.h>
19 #include <xmlrpcpp/XmlRpc.h>
20 
25 
26 namespace image_transport_codecs
27 {
28 
37 {
39  std::string format;
40 
42  std::vector<uint8_t> data;
43 };
44 
82 {
83 public:
86 
89 
90  // There has to be cras::ShapeShifter instead of topic_tools::ShapeShifter to avoid Melodic memory corruption issues.
92  typedef cras::expected<cras::ShapeShifter, std::string> EncodeResult;
93 
95  typedef cras::expected<sensor_msgs::Image, std::string> DecodeResult;
96 
98  typedef cras::expected<cras::optional<CompressedImageContent>, std::string> GetCompressedContentResult;
99 
104  explicit ImageTransportCodec(const cras::LogHelperPtr& logHelper);
105 
106  virtual ~ImageTransportCodec();
107 
113  virtual std::string getTransportName() const = 0;
114 
121  virtual EncodeResult encode(const sensor_msgs::Image& raw, const dynamic_reconfigure::Config& config) const = 0;
122 
129  virtual DecodeResult decode(const topic_tools::ShapeShifter& compressed,
130  const dynamic_reconfigure::Config& config) const = 0;
131 
142  virtual GetCompressedContentResult getCompressedImageContent(
143  const topic_tools::ShapeShifter& compressed, const std::string& matchFormat) const = 0;
144 
153  GetCompressedContentResult getCompressedImageContent(const topic_tools::ShapeShifter& compressed) const;
154 
160  EncodeResult encode(const sensor_msgs::Image& raw) const;
161 
167  DecodeResult decode(const topic_tools::ShapeShifter& compressed) const;
168 
175  EncodeResult encode(const sensor_msgs::Image& raw, const XmlRpc::XmlRpcValue& config) const;
176 
183  DecodeResult decode(const topic_tools::ShapeShifter& compressed, const XmlRpc::XmlRpcValue& config) const;
184 
192  EncodeResult encode(const sensor_msgs::Image& raw, const ros::NodeHandle& nh, const std::string& param) const;
193 
202  DecodeResult decode(const topic_tools::ShapeShifter& compressed, const ros::NodeHandle& nh,
203  const std::string& param) const;
204 
213  template<typename Config>
214  EncodeResult encode(const sensor_msgs::Image& raw, const Config& config) const
215  {
216  dynamic_reconfigure::Config configMsg;
217  config.__toMessage__(configMsg);
218  return this->encode(raw, configMsg);
219  }
220 
229  template<typename Config>
230  DecodeResult decode(const topic_tools::ShapeShifter& compressed, const Config& config) const
231  {
232  dynamic_reconfigure::Config configMsg;
233  config.__toMessage__(configMsg);
234  return this->decode(compressed, configMsg);
235  }
236 };
237 
238 }
cras::expected< cras::ShapeShifter, std::string > EncodeResult
Result of image encoding. Either a shapeshifter holding the compressed message, or error message...
boost::shared_ptr< ImageTransportCodec > Ptr
Shared pointer to ImageTransportCodec.
std::vector< uint8_t > data
The image content.
std::string format
Format of the image. This should be a string recognized by OpenCV, ffmpeg or similar tools...
cras::expected< sensor_msgs::Image, std::string > DecodeResult
Result of image decoding. Either a sensor_msgs::Image holding the raw message, or error message...
The part of a compressed message that represents the actual image data (i.e. data that can be passed ...
boost::shared_ptr< const ImageTransportCodec > ConstPtr
Shared pointer to const ImageTransportCodec.
DecodeResult decode(const topic_tools::ShapeShifter &compressed, const Config &config) const
Decode the given compressed image into a raw image.
cras::expected< cras::optional< CompressedImageContent >, std::string > GetCompressedContentResult
Result of getting the actual compressed image data.
Base for all image transport codecs. All codecs have to extend class ImageTransportCodec and implemen...
EncodeResult encode(const sensor_msgs::Image &raw, const Config &config) const
Encode the given raw image into the given shapeshifter object.
::cras::LogHelper::Ptr LogHelperPtr


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