Namespaces | Classes | Typedefs | Enumerations | Functions
cv_bridge Namespace Reference

Namespaces

namespace  rgb_colors

Classes

class  CvImage
 Image message class that is interoperable with sensor_msgs/Image but uses a more convenient cv::Mat representation for the image data. More...
struct  CvtColorForDisplayOptions
class  Exception

Typedefs

typedef boost::shared_ptr
< CvImage const > 
CvImageConstPtr
typedef boost::shared_ptr
< CvImage
CvImagePtr

Enumerations

enum  Format {
  BMP, DIB, JPG, JPEG,
  JPE, JP2, PNG, PBM,
  PGM, PPM, SR, RAS,
  TIFF, TIF
}

Functions

CvImagePtr cvtColor (const CvImageConstPtr &source, const std::string &encoding)
 Convert a CvImage to another encoding using the same rules as toCvCopy.
CvImageConstPtr cvtColorForDisplay (const CvImageConstPtr &source, const std::string &encoding=std::string(), const CvtColorForDisplayOptions options=CvtColorForDisplayOptions())
 Converts an immutable sensor_msgs::Image message to another CvImage for display purposes, using practical conversion rules if needed.
static int depthStrToInt (const std::string depth)
int getCvType (const std::string &encoding)
 Get the OpenCV type enum corresponding to the encoding.
std::string getFormat (Format format)
CvImagePtr toCvCopy (const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
 Convert a sensor_msgs::Image message to an OpenCV-compatible CvImage, copying the image data.
CvImagePtr toCvCopy (const sensor_msgs::CompressedImageConstPtr &source, const std::string &encoding=std::string())
CvImagePtr toCvCopy (const sensor_msgs::Image &source, const std::string &encoding=std::string())
 Convert a sensor_msgs::Image message to an OpenCV-compatible CvImage, copying the image data.
CvImagePtr toCvCopy (const sensor_msgs::CompressedImage &source, const std::string &encoding=std::string())
CvImageConstPtr toCvShare (const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
 Convert an immutable sensor_msgs::Image message to an OpenCV-compatible CvImage, sharing the image data if possible.
CvImageConstPtr toCvShare (const sensor_msgs::Image &source, const boost::shared_ptr< void const > &tracked_object, const std::string &encoding=std::string())
 Convert an immutable sensor_msgs::Image message to an OpenCV-compatible CvImage, sharing the image data if possible.

Typedef Documentation

typedef boost::shared_ptr<CvImage const> cv_bridge::CvImageConstPtr

Definition at line 59 of file cv_bridge.h.

typedef boost::shared_ptr<CvImage> cv_bridge::CvImagePtr

Definition at line 56 of file cv_bridge.h.


Enumeration Type Documentation

Enumerator:
BMP 
DIB 
JPG 
JPEG 
JPE 
JP2 
PNG 
PBM 
PGM 
PPM 
SR 
RAS 
TIFF 
TIF 

Definition at line 62 of file cv_bridge.h.


Function Documentation

CvImagePtr cv_bridge::cvtColor ( const CvImageConstPtr &  source,
const std::string &  encoding 
)

Convert a CvImage to another encoding using the same rules as toCvCopy.

Definition at line 430 of file cv_bridge.cpp.

CvImageConstPtr cv_bridge::cvtColorForDisplay ( const CvImageConstPtr &  source,
const std::string &  encoding = std::string(),
const CvtColorForDisplayOptions  options = CvtColorForDisplayOptions() 
)

Converts an immutable sensor_msgs::Image message to another CvImage for display purposes, using practical conversion rules if needed.

Data will be shared between input and output if possible.

Recall: sensor_msgs::image_encodings::isColor and isMono tell whether an image contains R,G,B,A, mono (or any combination/subset) with 8 or 16 bit depth.

The following rules apply:

  • if the output encoding is empty, the fact that the input image is mono or multiple-channel is preserved in the ouput image. The bit depth will be 8. it tries to convert to BGR no matter what encoding image is passed.
  • if the output encoding is not empty, it must have sensor_msgs::image_encodings::isColor and isMono return true. It must also be 8 bit in depth
  • if the input encoding is an OpenCV format (e.g. 8UC1), and if we have 1,3 or 4 channels, it is respectively converted to mono, BGR or BGRA.
  • if the input encoding is 32SC1, this estimate that image as label image and will convert it as bgr image with different colors for each label.
Parameters:
sourceA shared_ptr to a sensor_msgs::Image message
encodingEither an encoding string that returns true in sensor_msgs::image_encodings::isColor isMono or the empty string as explained above.
options(cv_bridge::CvtColorForDisplayOptions) Options to convert the source image with.
  • do_dynamic_scaling If true, the image is dynamically scaled between its minimum and maximum value before being converted to its final encoding.
  • min_image_value Independently from do_dynamic_scaling, if min_image_value and max_image_value are different, the image is scaled between these two values before being converted to its final encoding.
  • max_image_value Maximum image value
  • colormap Colormap which the source image converted with.

Definition at line 539 of file cv_bridge.cpp.

static int cv_bridge::depthStrToInt ( const std::string  depth) [static]

Definition at line 56 of file cv_bridge.cpp.

int cv_bridge::getCvType ( const std::string &  encoding)

Get the OpenCV type enum corresponding to the encoding.

For example, "bgr8" -> CV_8UC3.

Definition at line 73 of file cv_bridge.cpp.

std::string cv_bridge::getFormat ( Format  format)

Definition at line 445 of file cv_bridge.cpp.

CvImagePtr cv_bridge::toCvCopy ( const sensor_msgs::ImageConstPtr &  source,
const std::string &  encoding = std::string() 
)

Convert a sensor_msgs::Image message to an OpenCV-compatible CvImage, copying the image data.

Parameters:
sourceA shared_ptr to a sensor_msgs::Image message
encodingThe desired encoding of the image data, one of the following strings:
  • "mono8"
  • "bgr8"
  • "bgra8"
  • "rgb8"
  • "rgba8"
  • "mono16"

If encoding is the empty string (the default), the returned CvImage has the same encoding as source.

Definition at line 393 of file cv_bridge.cpp.

CvImagePtr cv_bridge::toCvCopy ( const sensor_msgs::CompressedImageConstPtr &  source,
const std::string &  encoding = std::string() 
)

Definition at line 510 of file cv_bridge.cpp.

CvImagePtr cv_bridge::toCvCopy ( const sensor_msgs::Image &  source,
const std::string &  encoding = std::string() 
)

Convert a sensor_msgs::Image message to an OpenCV-compatible CvImage, copying the image data.

Parameters:
sourceA sensor_msgs::Image message
encodingThe desired encoding of the image data, one of the following strings:
  • "mono8"
  • "bgr8"
  • "bgra8"
  • "rgb8"
  • "rgba8"
  • "mono16"

If encoding is the empty string (the default), the returned CvImage has the same encoding as source. If the source is 8bit and the encoding 16 or vice-versa, a scaling is applied (65535/255 and 255/65535 respectively). Otherwise, no scaling is applied and the rules from the convertTo OpenCV function are applied (capping): http://docs.opencv.org/modules/core/doc/basic_structures.html#mat-convertto

Definition at line 399 of file cv_bridge.cpp.

CvImagePtr cv_bridge::toCvCopy ( const sensor_msgs::CompressedImage &  source,
const std::string &  encoding = std::string() 
)

Definition at line 516 of file cv_bridge.cpp.

CvImageConstPtr cv_bridge::toCvShare ( const sensor_msgs::ImageConstPtr &  source,
const std::string &  encoding = std::string() 
)

Convert an immutable sensor_msgs::Image message to an OpenCV-compatible CvImage, sharing the image data if possible.

If the source encoding and desired encoding are the same, the returned CvImage will share the image data with source without copying it. The returned CvImage cannot be modified, as that could modify the source data.

Parameters:
sourceA shared_ptr to a sensor_msgs::Image message
encodingThe desired encoding of the image data, one of the following strings:
  • "mono8"
  • "bgr8"
  • "bgra8"
  • "rgb8"
  • "rgba8"
  • "mono16"

If encoding is the empty string (the default), the returned CvImage has the same encoding as source.

Definition at line 407 of file cv_bridge.cpp.

CvImageConstPtr cv_bridge::toCvShare ( const sensor_msgs::Image &  source,
const boost::shared_ptr< void const > &  tracked_object,
const std::string &  encoding = std::string() 
)

Convert an immutable sensor_msgs::Image message to an OpenCV-compatible CvImage, sharing the image data if possible.

If the source encoding and desired encoding are the same, the returned CvImage will share the image data with source without copying it. The returned CvImage cannot be modified, as that could modify the source data.

This overload is useful when you have a shared_ptr to a message that contains a sensor_msgs::Image, and wish to share ownership with the containing message.

Parameters:
sourceThe sensor_msgs::Image message
tracked_objectA shared_ptr to an object owning the sensor_msgs::Image
encodingThe desired encoding of the image data, one of the following strings:
  • "mono8"
  • "bgr8"
  • "bgra8"
  • "rgb8"
  • "rgba8"
  • "mono16"

If encoding is the empty string (the default), the returned CvImage has the same encoding as source.

Definition at line 413 of file cv_bridge.cpp.



cv_bridge
Author(s): Patrick Mihelich, James Bowman
autogenerated on Thu Jun 6 2019 21:23:27