Image transport codec corresponding to compressed_depth_image_transport. More...
#include <compressed_depth_codec.h>
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 ImageTransportCodec > | ConstPtr |
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< ImageTransportCodec > | Ptr |
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 ¶m) 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 ¶m) 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 |
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.
Definition at line 58 of file compressed_depth_codec.h.
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.
|
explicit |
Create an instance of the codec.
[in] | logHelper | The logger to use for error messages not directly related to the currently processed image. |
|
override |
ImageTransportCodec::DecodeResult image_transport_codecs::CompressedDepthCodec::decode | ( | const sensor_msgs::CompressedImage & | compressed | ) | const |
Decode the given compressed image.
[in] | compressed | The image to decode. |
compressedDepthCodecDecode()
.
|
overridevirtual |
Decode the given compressed image into a raw image.
[in] | compressed | The shapeshifter of the compressed image to be decoded. |
[in] | config | Config of the decompression (if it has any parameters). |
Implements image_transport_codecs::ImageTransportCodec.
ImageTransportCodec::DecodeResult image_transport_codecs::CompressedDepthCodec::decodeCompressedDepthImage | ( | const sensor_msgs::CompressedImage & | compressed | ) | const |
Decode the given compressed image.
[in] | compressed | The image to decode. |
cv::Mat image_transport_codecs::CompressedDepthCodec::decodeRVL | ( | const std::vector< uint8_t > & | compressed | ) | const |
Decode a RVL-encoded image into a 16UC1 cv::Mat
.
[in] | compressed | Bytes of a RVL-encoded image. |
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.
[in] | raw | The raw image to encode. |
[in] | config | Configuration of the encoder (corresponds to the dynamic_reconfigure parameters of publisher). |
compressedDepthCodecEncode()
.
|
overridevirtual |
Encode the given raw image into the given shapeshifter object.
[in] | raw | The input raw image. |
[in] | config | Config of the compression (if it has any parameters). |
Implements image_transport_codecs::ImageTransportCodec.
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.
[in] | raw | The raw image to encode. |
[in] | compression_format | The compression format (png or rvl). |
[in] | depth_max | Maximum depth value in meters (1-100). |
[in] | depth_quantization | Depth value at which the sensor accuracy is 1 m (Kinect: >75) (1-150). |
[in] | png_level | PNG compression level (if PNG is used) (1-9). |
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.
[in] | depthImg16UC1 | 2D cv::Mat with the image in inverse depth coding. |
[out] | compressed | Bytes of the compressed image. |
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.
[in] | invDepthImg | The raw image coded with inverse depth. |
[in] | compressionConfig | Quantization settings. |
|
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.
[in] | compressed | The compressed image. |
[in] | matchFormat | If nonempty, the image data is only returned if their format field would match the given one. The matching should be case-insensitive. |
Implements image_transport_codecs::ImageTransportCodec.
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).
[in] | compressed | The compressed image. |
[in] | matchFormat | If nonempty, the image data is only returned if their format field would match the given one. The matching should be case-insensitive. |
compressed_depth_image_transport::ConfigHeader image_transport_codecs::CompressedDepthCodec::getCompressionConfig | ( | const sensor_msgs::CompressedImage & | compressed | ) | const |
Get the depth quantization parameters used by compression.
[in] | compressed | The compressed image to read the parameters from. |
|
overridevirtual |
Get the name of the codec/transport (used e.g. as topic suffix).
Implements image_transport_codecs::ImageTransportCodec.
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.
[in] | depthImg | The raw direct-coded image. |
[in] | depth_max | Maximum depth value in meters (1-100). |
[in] | depth_quantization | Depth value at which the sensor accuracy is 1 m (Kinect: >75) (1-150). |
[out] | compressionConfig | The quantization parameters struct to be written to the beginning of the compressed image. |