cv_bridge contains a single class CvBridge that converts ROS Image messages to OpenCV images.
The CvBridge is an object that converts between OpenCV Images and ROS Image messages.
>>> import cv >>> from cv_bridge import CvBridge >>> im = cv.CreateImage((640, 480), 8, 3) >>> br = CvBridge() >>> msg = br.cv_to_imgmsg(im) # Convert the image to a message >>> im2 = br.imgmsg_to_cv(msg) # Convert the message to a new image >>> cv.SaveImage("this_was_a_message_briefly.png", im2)
Convert an OpenCV cv::Mat type to a ROS sensor_msgs::Image message.
Parameters: |
|
---|---|
Return type: | A sensor_msgs.msg.Image message |
Raises CvBridgeError: | |
when the cvim has a type that is incompatible with encoding |
If encoding is "passthrough", then the message has the same encoding as the image’s OpenCV type. Otherwise desired_encoding must be one of the standard image encodings
This function returns a sensor_msgs::Image message on success, or raises cv_bridge.CvBridgeError on failure.
Convert an OpenCV CvArr type (that is, an IplImage or CvMat) to a ROS sensor_msgs::Image message.
Parameters: |
|
---|---|
Return type: | A sensor_msgs.msg.Image message |
Raises CvBridgeError: | |
when the cvim has a type that is incompatible with encoding |
If encoding is "passthrough", then the message has the same encoding as the image’s OpenCV type. Otherwise desired_encoding must be one of the standard image encodings
This function returns a sensor_msgs::Image message on success, or raises opencv_latest.cv_bridge.CvBridgeError on failure.
Convert a sensor_msgs::Image message to an OpenCV IplImage.
Parameters: |
|
---|---|
Return type: | IplImage |
Raises CvBridgeError: | |
when conversion is not possible. |
If desired_encoding is "passthrough", then the returned image has the same format as img_msg. Otherwise desired_encoding must be one of the standard image encodings
This function returns an OpenCV IplImage message on success, or raises cv_bridge.CvBridgeError on failure.
Convert a sensor_msgs::Image message to an OpenCV cv::Mat.
Parameters: |
|
---|---|
Return type: | cv::Mat |
Raises CvBridgeError: | |
when conversion is not possible. |
If desired_encoding is "passthrough", then the returned image has the same format as img_msg. Otherwise desired_encoding must be one of the standard image encodings
This function returns an OpenCV cv::Mat message on success, or raises cv_bridge.CvBridgeError on failure.
This is the error raised by cv_bridge.CvBridge methods when they fail.