Old C++ API. Use cv_bridge::CvImage, toCvCopy(), toCvShare() instead. More...
#include <CvBridge.h>
Public Member Functions | |
| bool | fromImage (const Image &rosimg, std::string desired_encoding="passthrough") |
| IplImage * | imgMsgToCv (sensor_msgs::Image::ConstPtr rosimg, std::string desired_encoding="passthrough") |
| IplImage * | toIpl () |
Static Public Member Functions | |
| static ROS_DEPRECATED sensor_msgs::Image::Ptr | cvToImgMsg (const IplImage *source, std::string encoding="passthrough") |
| static ROS_DEPRECATED bool | fromIpltoRosImage (const IplImage *source, sensor_msgs::Image &dest, std::string encoding="passthrough") |
Old C++ API. Use cv_bridge::CvImage, toCvCopy(), toCvShare() instead.
Definition at line 52 of file CvBridge.h.
| static ROS_DEPRECATED sensor_msgs::Image::Ptr sensor_msgs::CvBridge::cvToImgMsg | ( | const IplImage * | source, | |
| std::string | encoding = "passthrough" | |||
| ) | [inline, static] |
Convert an OpenCV CvArr type (that is, an IplImage or CvMat) to a ROS sensor_msgs::Image message.
| source | An OpenCV IplImage or CvMat | |
| encoding | The encoding of the image data, one of the following strings:
|
If encoding is "passthrough", then the message has the same encoding as the image's OpenCV type. Otherwise encoding must be one of the strings "rgb8", "bgr8", "rgba8", "bgra8", "mono8" or "mono16", in which case the OpenCV image must have the appropriate type:
CV_8UC3 (for "rgb8", "bgr8"),CV_8UC4 (for "rgba8", "bgra8"),CV_8UC1 (for "mono8"), orCV_16UC1 (for "mono16")This function returns a sensor_msgs::Image message on success, or raises CvBridgeException on failure.
Definition at line 403 of file CvBridge.h.
| bool sensor_msgs::CvBridge::fromImage | ( | const Image & | rosimg, | |
| std::string | desired_encoding = "passthrough" | |||
| ) | [inline] |
Converts a ROS Image into an OpenCV IPL Image.
This method will be deprecated and removed in a future release. Use method imgMsgToCv instead.
| rosimg | The ROS Image message | |
| desired_encoding | image encoding. See method imgMsgToCv for details. |
Definition at line 188 of file CvBridge.h.
| static ROS_DEPRECATED bool sensor_msgs::CvBridge::fromIpltoRosImage | ( | const IplImage * | source, | |
| sensor_msgs::Image & | dest, | |||
| std::string | encoding = "passthrough" | |||
| ) | [inline, static] |
Converts an OpenCV IPL Image into a ROS Image that can be sent 'over the wire'.
| source | The original Ipl Image that we want to copy from | |
| dest | The ROS Image message that we want to copy to | |
| encoding | image encoding. See method cvToImgMsg for details. |
Definition at line 305 of file CvBridge.h.
| IplImage* sensor_msgs::CvBridge::imgMsgToCv | ( | sensor_msgs::Image::ConstPtr | rosimg, | |
| std::string | desired_encoding = "passthrough" | |||
| ) | [inline] |
Convert a sensor_msgs::Image message to an OpenCV IplImage.
| rosimg | A sensor_msgs::Image message | |
| desired_encoding | The encoding of the image data, one of the following strings:
|
If desired_encoding is "passthrough", then the returned image has the same format as img_msg. Otherwise desired_encoding must be one of the strings "rgb8", "bgr8", "rgba8", "bgra8", "mono8" or "mono16", in which case this method converts the image using cvCvtColor (http://opencv.willowgarage.com/documentation/image_processing.html#cvCvtColor) (if necessary) and the returned image has a type as follows:
CV_8UC3 (for "rgb8", "bgr8"),CV_8UC4 (for "rgba8", "bgra8"),CV_8UC1 (for "mono8"), orCV_16UC1 (for "mono16")This function returns an OpenCV IplImage on success, or raises CvBridgeException on failure.
Definition at line 438 of file CvBridge.h.
| IplImage* sensor_msgs::CvBridge::toIpl | ( | ) | [inline] |
Returns the OpenCV IPL Image created by method fromImage.
This method will be deprecated and removed in a future release. Use method imgMsgToCv instead.
Definition at line 175 of file CvBridge.h.