Public Types | Public Member Functions | List of all members
image_transport_codecs::CompressedDepthCodec Class Reference

Image transport codec corresponding to compressed_depth_image_transport. More...

#include <compressed_depth_codec.h>

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

Public Types

typedef cras::expected< sensor_msgs::CompressedImage, std::string > EncodeResult
 Result of image encoding. Either a sensor_msgs::CompressedImage message, or error message. More...
 
- Public Types inherited from image_transport_codecs::ImageTransportCodec
typedef boost::shared_ptr< const ImageTransportCodecConstPtr
 Shared pointer to const ImageTransportCodec. More...
 
typedef cras::expected< sensor_msgs::Image, std::string > DecodeResult
 Result of image decoding. Either a sensor_msgs::Image holding the raw message, or error message. More...
 
typedef cras::expected< cras::ShapeShifter, std::string > EncodeResult
 Result of image encoding. Either a shapeshifter holding the compressed message, or error message. More...
 
typedef cras::expected< cras::optional< CompressedImageContent >, std::string > GetCompressedContentResult
 Result of getting the actual compressed image data. More...
 
typedef boost::shared_ptr< ImageTransportCodecPtr
 Shared pointer to ImageTransportCodec. More...
 

Public Member Functions

 CompressedDepthCodec (const cras::LogHelperPtr &logHelper=std::make_shared< cras::NodeLogHelper >())
 Create an instance of the codec. More...
 
ImageTransportCodec::DecodeResult decode (const sensor_msgs::CompressedImage &compressed) const
 Decode the given compressed image. More...
 
ImageTransportCodec::DecodeResult decode (const topic_tools::ShapeShifter &compressed, const dynamic_reconfigure::Config &config) const override
 Decode the given compressed image into a raw image. More...
 
ImageTransportCodec::DecodeResult decodeCompressedDepthImage (const sensor_msgs::CompressedImage &compressed) const
 Decode the given compressed image. More...
 
cv::Mat decodeRVL (const std::vector< uint8_t > &compressed) const
 Decode a RVL-encoded image into a 16UC1 cv::Mat. More...
 
EncodeResult encode (const sensor_msgs::Image &raw, const compressed_depth_image_transport::CompressedDepthPublisherConfig &config) const
 Encode the given raw image using the given publisher config. More...
 
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. More...
 
EncodeResult encodeCompressedDepthImage (const sensor_msgs::Image &raw, const std::string &compression_format, double depth_max, double depth_quantization, int png_level) const
 Encode the given raw image using the given quantization and compression config. More...
 
void encodeRVL (const cv::Mat &depthImg16UC1, std::vector< uint8_t > &compressed) const
 Encode the given 16UC1 image (i.e. transformed to inverse depth) using RVL. More...
 
cv::Mat fromInvDepth (const cv::Mat &invDepthImg, const compressed_depth_image_transport::ConfigHeader &compressionConfig) const
 Convert a 16UC1 inverse-depth-coded image into a float direct-coded image. More...
 
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. 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 sensor_msgs::CompressedImage &compressed, const std::string &matchFormat) const
 This function returns the bytes of the actual PNG/RVL image (skipping the codec-specific header). More...
 
compressed_depth_image_transport::ConfigHeader getCompressionConfig (const sensor_msgs::CompressedImage &compressed) const
 Get the depth quantization parameters used by compression. More...
 
std::string getTransportName () const override
 Get the name of the codec/transport (used e.g. as topic suffix). More...
 
cv::Mat toInvDepth (const cv::Mat &depthImg, double depth_max, double depth_quantization, compressed_depth_image_transport::ConfigHeader &compressionConfig) const
 Convert a float direct-coded image to 16UC1 inverse-depth-coded image. More...
 
 ~CompressedDepthCodec () override
 
- Public Member Functions inherited from image_transport_codecs::ImageTransportCodec
DecodeResult decode (const topic_tools::ShapeShifter &compressed) const
 Decode the given compressed image into a raw image using the default decompression parameters. More...
 
DecodeResult decode (const topic_tools::ShapeShifter &compressed, const XmlRpc::XmlRpcValue &config) const
 Decode the given compressed image into a raw image. More...
 
DecodeResult decode (const topic_tools::ShapeShifter &compressed, const ros::NodeHandle &nh, const std::string &param) const
 Decode the given compressed image into a raw image. More...
 
template<typename Config >
DecodeResult decode (const topic_tools::ShapeShifter &compressed, const Config &config) const
 Decode the given compressed image into a raw image. More...
 
EncodeResult encode (const sensor_msgs::Image &raw) const
 Encode the given raw image into the given shapeshifter object using the default compression parameters. More...
 
EncodeResult encode (const sensor_msgs::Image &raw, const XmlRpc::XmlRpcValue &config) const
 Encode the given raw image into the given shapeshifter object. More...
 
EncodeResult encode (const sensor_msgs::Image &raw, const ros::NodeHandle &nh, const std::string &param) const
 Encode the given raw image into the given shapeshifter object. More...
 
template<typename Config >
EncodeResult encode (const sensor_msgs::Image &raw, const Config &config) const
 Encode the given raw image into the given shapeshifter object. More...
 
GetCompressedContentResult getCompressedImageContent (const topic_tools::ShapeShifter &compressed) 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 (const cras::LogHelperPtr &logHelper)
 Create an instance of the codec. More...
 
virtual ~ImageTransportCodec ()
 
- Public Member Functions inherited from cras::HasLogger
::cras::LogHelperConstPtr getCrasLogger () const
 
 HasLogger (const ::cras::LogHelperPtr &log)
 
void setCrasLogger (const ::cras::LogHelperPtr &log)
 

Additional Inherited Members

- Protected Attributes inherited from cras::HasLogger
::cras::LogHelperPtr log
 

Detailed Description

Image transport codec corresponding to compressed_depth_image_transport.

This codec exposes the functionality of compressed_depth_image_transport so that it can be used directly without the need to go through running a node and publishing on a topic. E.g.

sensor_msgs::Image raw = ...;
auto result = codec.encode(raw);
if (!result)
{
ROS_ERROR_STREAM("Compression failed: " << result.error());
return false;
}
sensor_msgs::CompressedImage compressed = result.value();

Definition at line 58 of file compressed_depth_codec.h.

Member Typedef Documentation

◆ EncodeResult

typedef cras::expected<sensor_msgs::CompressedImage, std::string> image_transport_codecs::CompressedDepthCodec::EncodeResult

Result of image encoding. Either a sensor_msgs::CompressedImage message, or error message.

Definition at line 62 of file compressed_depth_codec.h.

Constructor & Destructor Documentation

◆ CompressedDepthCodec()

image_transport_codecs::CompressedDepthCodec::CompressedDepthCodec ( const cras::LogHelperPtr logHelper = std::make_shared< cras::NodeLogHelper >())
explicit

Create an instance of the codec.

Parameters
[in]logHelperThe logger to use for error messages not directly related to the currently processed image.

◆ ~CompressedDepthCodec()

image_transport_codecs::CompressedDepthCodec::~CompressedDepthCodec ( )
override

Member Function Documentation

◆ decode() [1/2]

ImageTransportCodec::DecodeResult image_transport_codecs::CompressedDepthCodec::decode ( const sensor_msgs::CompressedImage &  compressed) const

Decode the given compressed image.

Parameters
[in]compressedThe image to decode.
Returns
The decoded raw image, or an error.
See also
Corresponding C API function: compressedDepthCodecDecode().

◆ decode() [2/2]

ImageTransportCodec::DecodeResult image_transport_codecs::CompressedDepthCodec::decode ( const topic_tools::ShapeShifter compressed,
const dynamic_reconfigure::Config &  config 
) const
overridevirtual

Decode the given compressed image into a raw image.

Parameters
[in]compressedThe shapeshifter of the compressed image to be decoded.
[in]configConfig of the decompression (if it has any parameters).
Returns
The decoded raw image (if decoding succeeds), or an error message.

Implements image_transport_codecs::ImageTransportCodec.

◆ decodeCompressedDepthImage()

ImageTransportCodec::DecodeResult image_transport_codecs::CompressedDepthCodec::decodeCompressedDepthImage ( const sensor_msgs::CompressedImage &  compressed) const

Decode the given compressed image.

Parameters
[in]compressedThe image to decode.
Returns
The decoded raw image, or an error.

◆ decodeRVL()

cv::Mat image_transport_codecs::CompressedDepthCodec::decodeRVL ( const std::vector< uint8_t > &  compressed) const

Decode a RVL-encoded image into a 16UC1 cv::Mat.

Parameters
[in]compressedBytes of a RVL-encoded image.
Returns
2D matrix representing the decoded raw image.

◆ encode() [1/2]

EncodeResult image_transport_codecs::CompressedDepthCodec::encode ( const sensor_msgs::Image &  raw,
const compressed_depth_image_transport::CompressedDepthPublisherConfig &  config 
) const

Encode the given raw image using the given publisher config.

Parameters
[in]rawThe raw image to encode.
[in]configConfiguration of the encoder (corresponds to the dynamic_reconfigure parameters of publisher).
Returns
The encoded image, or an error.
See also
Corresponding C API function: compressedDepthCodecEncode().

◆ encode() [2/2]

ImageTransportCodec::EncodeResult image_transport_codecs::CompressedDepthCodec::encode ( const sensor_msgs::Image &  raw,
const dynamic_reconfigure::Config &  config 
) const
overridevirtual

Encode the given raw image into the given shapeshifter object.

Parameters
[in]rawThe input raw image.
[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.

Implements image_transport_codecs::ImageTransportCodec.

◆ encodeCompressedDepthImage()

EncodeResult image_transport_codecs::CompressedDepthCodec::encodeCompressedDepthImage ( const sensor_msgs::Image &  raw,
const std::string &  compression_format,
double  depth_max,
double  depth_quantization,
int  png_level 
) const

Encode the given raw image using the given quantization and compression config.

Parameters
[in]rawThe raw image to encode.
[in]compression_formatThe compression format (png or rvl).
[in]depth_maxMaximum depth value in meters (1-100).
[in]depth_quantizationDepth value at which the sensor accuracy is 1 m (Kinect: >75) (1-150).
[in]png_levelPNG compression level (if PNG is used) (1-9).
Returns
The encoded image, or an error.

◆ encodeRVL()

void image_transport_codecs::CompressedDepthCodec::encodeRVL ( const cv::Mat &  depthImg16UC1,
std::vector< uint8_t > &  compressed 
) const

Encode the given 16UC1 image (i.e. transformed to inverse depth) using RVL.

Parameters
[in]depthImg16UC12D cv::Mat with the image in inverse depth coding.
[out]compressedBytes of the compressed image.

◆ fromInvDepth()

cv::Mat image_transport_codecs::CompressedDepthCodec::fromInvDepth ( const cv::Mat &  invDepthImg,
const compressed_depth_image_transport::ConfigHeader compressionConfig 
) const

Convert a 16UC1 inverse-depth-coded image into a float direct-coded image.

Parameters
[in]invDepthImgThe raw image coded with inverse depth.
[in]compressionConfigQuantization settings.
Returns
The raw image coded with direct depth in floats.

◆ getCompressedImageContent() [1/2]

ImageTransportCodec::GetCompressedContentResult image_transport_codecs::CompressedDepthCodec::getCompressedImageContent ( const topic_tools::ShapeShifter compressed,
const std::string &  matchFormat 
) const
overridevirtual

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]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.

Implements image_transport_codecs::ImageTransportCodec.

◆ getCompressedImageContent() [2/2]

ImageTransportCodec::GetCompressedContentResult image_transport_codecs::CompressedDepthCodec::getCompressedImageContent ( const sensor_msgs::CompressedImage &  compressed,
const std::string &  matchFormat 
) const

This function returns the bytes of the actual PNG/RVL image (skipping the codec-specific header).

Parameters
[in]compressedThe compressed image.
[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
The contained image bytes.

◆ getCompressionConfig()

compressed_depth_image_transport::ConfigHeader image_transport_codecs::CompressedDepthCodec::getCompressionConfig ( const sensor_msgs::CompressedImage &  compressed) const

Get the depth quantization parameters used by compression.

Parameters
[in]compressedThe compressed image to read the parameters from.
Returns
The depth quantization parameters. If an invalid image (i.e. from a different codec) is passed, the result is undefined.

◆ getTransportName()

std::string image_transport_codecs::CompressedDepthCodec::getTransportName ( ) const
overridevirtual

Get the name of the codec/transport (used e.g. as topic suffix).

Note
This name has to be unique among all defined codecs.
Returns
The transport name.

Implements image_transport_codecs::ImageTransportCodec.

◆ toInvDepth()

cv::Mat image_transport_codecs::CompressedDepthCodec::toInvDepth ( const cv::Mat &  depthImg,
double  depth_max,
double  depth_quantization,
compressed_depth_image_transport::ConfigHeader compressionConfig 
) const

Convert a float direct-coded image to 16UC1 inverse-depth-coded image.

Parameters
[in]depthImgThe raw direct-coded image.
[in]depth_maxMaximum depth value in meters (1-100).
[in]depth_quantizationDepth value at which the sensor accuracy is 1 m (Kinect: >75) (1-150).
[out]compressionConfigThe quantization parameters struct to be written to the beginning of the compressed image.
Returns
The 16UC1 inverse-depth-coded raw image.

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