cv_bridge¶
cv_bridge contains a single class CvBridge that converts ROS Image messages to
OpenCV images.
- 
class 
cv_bridge.CvBridge¶ The CvBridge is an object that converts between OpenCV Images and ROS Image messages.
>>> import cv2 >>> import numpy as np >>> from cv_bridge import CvBridge >>> br = CvBridge() >>> dtype, n_channels = br.encoding_as_cvtype2('8UC3') >>> im = np.ndarray(shape=(480, 640, n_channels), dtype=dtype) >>> msg = br.cv2_to_imgmsg(im) # Convert the image to a message >>> im2 = br.imgmsg_to_cv2(msg) # Convert the message to a new image >>> cmprsmsg = br.cv2_to_compressed_imgmsg(im) # Convert the image to a compress message >>> im22 = br.compressed_imgmsg_to_cv2(msg) # Convert the compress message to a new image >>> cv2.imwrite("this_was_a_message_briefly.png", im2)
- 
compressed_imgmsg_to_cv2(cmprs_img_msg, desired_encoding='passthrough')¶ Convert a sensor_msgs::CompressedImage message to an OpenCV
cv::Mat.Parameters: - cmprs_img_msg – A 
sensor_msgs::CompressedImagemessage - desired_encoding – 
The encoding of the image data, one of the following strings:
"passthrough"- one of the standard strings in sensor_msgs/image_encodings.h
 
 
Return type: cv::MatRaises: 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 encodingsThis function returns an OpenCV
cv::Matmessage on success, or raisescv_bridge.CvBridgeErroron failure.If the image only has one channel, the shape has size 2 (width and height)
- cmprs_img_msg – A 
 
- 
cv2_to_compressed_imgmsg(cvim, dst_format='jpg')¶ Convert an OpenCV
cv::Mattype to a ROS sensor_msgs::CompressedImage message.Parameters: - cvim – An OpenCV 
cv::Mat - dst_format – 
The format of the image data, one of the following strings:
- from http://docs.opencv.org/2.4/modules/highgui/doc/reading_and_writing_images_and_video.html
 - from http://docs.opencv.org/2.4/modules/highgui/doc/reading_and_writing_images_and_video.html#Mat imread(const string& filename, int flags)
 - bmp, dib
 - jpeg, jpg, jpe
 - jp2
 - png
 - pbm, pgm, ppm
 - sr, ras
 - tiff, tif
 
 
Return type: A sensor_msgs.msg.CompressedImage message
Raises: CvBridgeError – when the
cvimhas a type that is incompatible withformatThis function returns a sensor_msgs::Image message on success, or raises
cv_bridge.CvBridgeErroron failure.- cvim – An OpenCV 
 
- 
cv2_to_imgmsg(cvim, encoding='passthrough')¶ Convert an OpenCV
cv::Mattype to a ROS sensor_msgs::Image message.Parameters: - cvim – An OpenCV 
cv::Mat - encoding – 
The encoding of the image data, one of the following strings:
"passthrough"- one of the standard strings in sensor_msgs/image_encodings.h
 
 
Return type: A sensor_msgs.msg.Image message
Raises: CvBridgeError – when the
cvimhas a type that is incompatible withencodingIf 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 encodingsThis function returns a sensor_msgs::Image message on success, or raises
cv_bridge.CvBridgeErroron failure.- cvim – An OpenCV 
 
- 
imgmsg_to_cv2(img_msg, desired_encoding='passthrough')¶ Convert a sensor_msgs::Image message to an OpenCV
cv::Mat.Parameters: - img_msg – A 
sensor_msgs::Imagemessage - desired_encoding – 
The encoding of the image data, one of the following strings:
"passthrough"- one of the standard strings in sensor_msgs/image_encodings.h
 
 
Return type: cv::MatRaises: 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 encodingsThis function returns an OpenCV
cv::Matmessage on success, or raisescv_bridge.CvBridgeErroron failure.If the image only has one channel, the shape has size 2 (width and height)
- img_msg – A 
 
- 
 
- 
class 
cv_bridge.CvBridgeError¶ This is the error raised by
cv_bridge.CvBridgemethods when they fail.