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... | |
class | Exception |
Typedefs | |
typedef boost::shared_ptr < CvImage const > | CvImageConstPtr |
typedef boost::shared_ptr < CvImage > | CvImagePtr |
Functions | |
CvImagePtr | cvtColor (const CvImageConstPtr &source, const std::string &encoding) |
Convert a CvImage to another encoding using the same rules as toCvCopy. | |
int | getCvType (const std::string &encoding) |
Get the OpenCV type enum corresponding to the encoding. | |
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::Image &source, const std::string &encoding=std::string()) |
Convert a sensor_msgs::Image message to an OpenCV-compatible CvImage, copying the image data. | |
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 boost::shared_ptr<CvImage const> cv_bridge::CvImageConstPtr |
Definition at line 54 of file cv_bridge.h.
typedef boost::shared_ptr<CvImage> cv_bridge::CvImagePtr |
Definition at line 51 of file cv_bridge.h.
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 389 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 49 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.
source | A shared_ptr to a sensor_msgs::Image message |
encoding | The desired encoding of the image data, one of the following strings:
|
If encoding is the empty string (the default), the returned CvImage has the same encoding as source.
Definition at line 354 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.
source | A sensor_msgs::Image message |
encoding | The desired encoding of the image data, one of the following strings:
|
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 360 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.
source | A shared_ptr to a sensor_msgs::Image message |
encoding | The desired encoding of the image data, one of the following strings:
|
If encoding is the empty string (the default), the returned CvImage has the same encoding as source.
Definition at line 368 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.
source | The sensor_msgs::Image message |
tracked_object | A shared_ptr to an object owning the sensor_msgs::Image |
encoding | The desired encoding of the image data, one of the following strings:
|
If encoding is the empty string (the default), the returned CvImage has the same encoding as source.
Definition at line 374 of file cv_bridge.cpp.