17 #include <dynamic_reconfigure/Config.h> 18 #include <sensor_msgs/CompressedImage.h> 19 #include <sensor_msgs/Image.h> 21 #include <compressed_depth_image_transport/CompressedDepthPublisherConfig.h> 62 typedef cras::expected<sensor_msgs::CompressedImage, std::string>
EncodeResult;
79 EncodeResult encode(
const sensor_msgs::Image& raw,
80 const compressed_depth_image_transport::CompressedDepthPublisherConfig& config)
const;
90 std::string getTransportName()
const override;
93 const dynamic_reconfigure::Config& config)
const override;
96 const dynamic_reconfigure::Config& config)
const override;
109 const sensor_msgs::CompressedImage& compressed,
const std::string& matchFormat)
const;
118 const sensor_msgs::CompressedImage& compressed)
const;
137 double depth_max,
double depth_quantization,
int png_level)
const;
144 cv::Mat decodeRVL(
const std::vector<uint8_t>& compressed)
const;
151 void encodeRVL(
const cv::Mat& depthImg16UC1, std::vector<uint8_t>& compressed)
const;
159 cv::Mat fromInvDepth(
const cv::Mat& invDepthImg,
171 cv::Mat toInvDepth(
const cv::Mat& depthImg,
double depth_max,
double depth_quantization,
209 sensor_msgs::Image::_height_type rawHeight,
210 sensor_msgs::Image::_width_type rawWidth,
211 const char* rawEncoding,
212 sensor_msgs::Image::_is_bigendian_type rawIsBigEndian,
213 sensor_msgs::Image::_step_type rawStep,
214 size_t rawDataLength,
215 const uint8_t rawData[],
218 #
if COMPRESSED_DEPTH_HAS_RVL == 1
219 const char* configFormat,
221 double configDepthMax,
222 double configDepthQuantization,
252 const char* compressedFormat,
253 size_t compressedDataLength,
254 const uint8_t compressedData[],
255 sensor_msgs::Image::_height_type& rawHeight,
256 sensor_msgs::Image::_width_type& rawWidth,
258 sensor_msgs::Image::_is_bigendian_type& rawIsBigEndian,
259 sensor_msgs::Image::_step_type& rawStep,
cras::expected< sensor_msgs::CompressedImage, std::string > EncodeResult
Result of image encoding. Either a sensor_msgs::CompressedImage message, or error message...
cras::expected< cras::ShapeShifter, std::string > EncodeResult
Result of image encoding. Either a shapeshifter holding the compressed message, or error message...
cras::expected< sensor_msgs::Image, std::string > DecodeResult
Result of image decoding. Either a sensor_msgs::Image holding the raw message, or error message...
Image transport codec corresponding to compressed_depth_image_transport.
sensor_msgs::Image::Ptr decodeCompressedDepthImage(const sensor_msgs::CompressedImage &compressed_image)
cras::expected< cras::optional< CompressedImageContent >, std::string > GetCompressedContentResult
Result of getting the actual compressed image data.
Base for all image transport codecs.
bool compressed_depth_codec_has_rvl()
Whether the RVL encoding is available. This should be false on Melodic and true on Noetic...
bool compressedDepthCodecEncode(sensor_msgs::Image::_height_type rawHeight, sensor_msgs::Image::_width_type rawWidth, const char *rawEncoding, sensor_msgs::Image::_is_bigendian_type rawIsBigEndian, sensor_msgs::Image::_step_type rawStep, size_t rawDataLength, const uint8_t rawData[], cras::allocator_t compressedFormatAllocator, cras::allocator_t compressedDataAllocator, double configDepthMax, double configDepthQuantization, int configPngLevel, cras::allocator_t errorStringAllocator, cras::allocator_t logMessagesAllocator)
Encode the given raw image using compressedDepth codec with the given config.
Base for all image transport codecs. All codecs have to extend class ImageTransportCodec and implemen...
bool compressedDepthCodecDecode(const char *compressedFormat, size_t compressedDataLength, const uint8_t compressedData[], sensor_msgs::Image::_height_type &rawHeight, sensor_msgs::Image::_width_type &rawWidth, cras::allocator_t rawEncodingAllocator, sensor_msgs::Image::_is_bigendian_type &rawIsBigEndian, sensor_msgs::Image::_step_type &rawStep, cras::allocator_t rawDataAllocator, cras::allocator_t errorStringAllocator, cras::allocator_t logMessagesAllocator)
Decode the given compressed image using compressedDepth codec.
void *(* allocator_t)(size_t)
sensor_msgs::CompressedImage::Ptr encodeCompressedDepthImage(const sensor_msgs::Image &message, double depth_max, double depth_quantization, int png_level)
::cras::LogHelper::Ptr LogHelperPtr