parse_compressed_format.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 #include <utility>
15 
16 #include <sensor_msgs/Image.h>
17 
18 #include <cras_cpp_common/c_api.h>
21 
22 namespace image_transport_codecs
23 {
24 
29 {
30  JPEG,
31  PNG,
32 };
33 
38 {
40  std::string formatString;
41  std::string rawEncoding;
42  std::string compressedEncoding;
44  int bitDepth;
45  bool isColor;
46 
47  bool operator==(const CompressedTransportFormat& other) const;
48 };
49 
56 cras::expected<CompressedTransportFormat, std::string> parseCompressedTransportFormat(const std::string& format);
57 
65 
73  const std::string& imageEncoding, const CompressedTransportCompressionFormat& compressionFormat);
74 
82  const sensor_msgs::Image& image, const CompressedTransportCompressionFormat& compressionFormat);
83 
91 cras::expected<CompressedTransportFormat, std::string> extractCompressedTransportFormat(
92  const std::string& imageEncoding, const std::string& compressionFormat);
93 
101 cras::expected<CompressedTransportFormat, std::string> extractCompressedTransportFormat(
102  const sensor_msgs::Image& image, const std::string& compressionFormat);
103 
108 {
109  PNG,
110  RVL,
111 };
112 
117 {
119  std::string formatString;
120  std::string rawEncoding;
121  int bitDepth;
122 
123  bool operator==(const CompressedDepthTransportFormat& other) const;
124 };
125 
132 cras::expected<CompressedDepthTransportFormat, std::string> parseCompressedDepthTransportFormat(
133  const std::string& format);
134 
142 
151  const std::string& imageEncoding, const CompressedDepthTransportCompressionFormat& compressionFormat);
152 
161  const sensor_msgs::Image& image, const CompressedDepthTransportCompressionFormat& compressionFormat);
162 
171 cras::expected<CompressedDepthTransportFormat, std::string> extractCompressedDepthTransportFormat(
172  const std::string& imageEncoding, const std::string& compressionFormat);
173 
182 cras::expected<CompressedDepthTransportFormat, std::string> extractCompressedDepthTransportFormat(
183  const sensor_msgs::Image& image, const std::string& compressionFormat);
184 
193 cras::expected<
194  std::pair<cras::optional<CompressedTransportFormat>, cras::optional<CompressedDepthTransportFormat>>, std::string>
195 guessAnyCompressedImageTransportFormat(const sensor_msgs::CompressedImage& image);
196 
197 }
198 
202 
218 extern "C" bool parseCompressedTransportFormat(
219  const char* format,
220  cras::allocator_t compressionFormatAllocator,
221  cras::allocator_t rawEncodingAllocator,
222  cras::allocator_t compressedEncodingAllocator,
223  int& numChannels,
224  int& bitDepth,
225  bool& isColor,
226  cras::allocator_t errorStringAllocator
227 );
228 
243 extern "C" bool makeCompressedTransportFormat(
244  const char* compressionFormat,
245  const char* rawEncoding,
246  const char* compressedEncoding,
247  int numChannels,
248  int bitDepth,
249  bool isColor,
250  cras::allocator_t formatAllocator,
251  cras::allocator_t errorStringAllocator
252 );
253 
266 extern "C" bool extractCompressedTransportFormat(
267  const char* imageEncoding,
268  const char* compressionFormat,
269  cras::allocator_t compressedEncodingAllocator,
270  int& numChannels,
271  int& bitDepth,
272  bool& isColor,
273  cras::allocator_t errorStringAllocator
274 );
275 
289  const char* format,
290  cras::allocator_t compressionFormatAllocator,
291  cras::allocator_t rawEncodingAllocator,
292  int& bitDepth,
293  cras::allocator_t errorStringAllocator
294 );
295 
307 extern "C" bool makeCompressedDepthTransportFormat(
308  const char* compressionFormat,
309  const char* rawEncoding,
310  int bitDepth,
311  cras::allocator_t formatAllocator,
312  cras::allocator_t errorStringAllocator
313 );
314 
325  const char* imageEncoding,
326  const char* compressionFormat,
327  int& bitDepth,
328  cras::allocator_t errorStringAllocator
329 );
330 
356  const char* format,
357  const uint8_t imageHeader[64],
358  bool& isCompressedDepth,
359  cras::allocator_t compressionFormatAllocator,
360  cras::allocator_t rawEncodingAllocator,
361  cras::allocator_t compressedEncodingAllocator,
362  int& numChannels,
363  int& bitDepth,
364  bool& isColor,
365  cras::allocator_t errorStringAllocator
366 );
bool isColor
Whether the image is a color image or not.
std::string formatString
Text version of the compression format ("png"/"rvl").
std::string formatString
Text version of the compression format ("jpeg"/"png").
Decoded meaning of field sensor_msgs::CompressedImage::format for compressed transport.
std::string rawEncoding
Encoding of the raw image (before compression, after decompression).
CompressedDepthTransportCompressionFormat format
The compression format (PNG/RVL).
std::string makeCompressedDepthTransportFormat(const CompressedDepthTransportFormat &format)
Convert the CompressedDepthTransportFormat structure into a string to be filled in field sensor_msgs:...
Decoded meaning of field sensor_msgs::CompressedImage::format for compressedDepth transport...
compressionFormat
cras::expected< std::pair< cras::optional< CompressedTransportFormat >, cras::optional< CompressedDepthTransportFormat > >, std::string > guessAnyCompressedImageTransportFormat(const sensor_msgs::CompressedImage &image)
Parse the string from field sensor_msgs::CompressedImage::format using either compressed or compresse...
std::string compressedEncoding
Encoding of the compressed image (i.e. bgr8 for JPEG).
CompressedTransportCompressionFormat format
The compression format (JPEG/PNG).
bool operator==(const ::ros::Rate &r1, const ::ros::Rate &r2)
int bitDepth
Number of bits used for encoding one depth value.
CompressedTransportCompressionFormat
Compression format of compressed codec (JPEG/PNG).
cras::expected< CompressedTransportFormat, std::string > parseCompressedTransportFormat(const std::string &format)
Parse the string from field sensor_msgs::CompressedImage::format using compressed transport into Comp...
void *(* allocator_t)(size_t)
RVL compression format (only usable in Noetic).
int bitDepth
Number of bits used for encoding one raw channel value.
std::string makeCompressedTransportFormat(const CompressedTransportFormat &format)
Convert the CompressedTransportFormat structure into a string to be filled in field sensor_msgs::Comp...
cras::expected< CompressedDepthTransportFormat, std::string > parseCompressedDepthTransportFormat(const std::string &format)
Parse the string from field sensor_msgs::CompressedImage::format using compressedDepth transport into...
CompressedDepthTransportFormat extractCompressedDepthTransportFormat(const std::string &imageEncoding, const CompressedDepthTransportCompressionFormat &compressionFormat)
Create the CompressedDepthTransportFormat structure for the given raw image compressed with the given...
std::string rawEncoding
Encoding of the raw image (before compression, after decompression).
CompressedDepthTransportCompressionFormat
Compression format of compressedDepth codec (PNG/RVL). RVL is only usable in Noetic.
int numChannels
Number of channels of the raw image data (1 for mono/depth images, 3-4 for color).
CompressedTransportFormat extractCompressedTransportFormat(const std::string &imageEncoding, const CompressedTransportCompressionFormat &compressionFormat)
Create the CompressedTransportFormat structure for the given raw image compressed with the given meth...


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