Image message class that is interoperable with sensor_msgs/Image but uses a more convenient cv::Mat representation for the image data. More...
#include <cv_bridge.h>
Public Types | |
typedef boost::shared_ptr< CvImage const > | ConstPtr |
typedef boost::shared_ptr< CvImage > | Ptr |
Public Member Functions | |
CvImage () | |
Empty constructor. More... | |
CvImage (const std_msgs::Header &header, const std::string &encoding, const cv::Mat &image=cv::Mat()) | |
Constructor. More... | |
sensor_msgs::CompressedImagePtr | toCompressedImageMsg (const Format dst_format=JPG) const |
void | toCompressedImageMsg (sensor_msgs::CompressedImage &ros_image, const Format dst_format=JPG) const |
sensor_msgs::ImagePtr | toImageMsg () const |
Convert this message to a ROS sensor_msgs::Image message. More... | |
void | toImageMsg (sensor_msgs::Image &ros_image) const |
Copy the message data to a ROS sensor_msgs::Image message. More... | |
Public Attributes | |
std::string | encoding |
Image encoding ("mono8", "bgr8", etc.) More... | |
std_msgs::Header | header |
ROS header. More... | |
cv::Mat | image |
Image data for use with OpenCV. More... | |
Protected Attributes | |
boost::shared_ptr< void const > | tracked_object_ |
Image message class that is interoperable with sensor_msgs/Image but uses a more convenient cv::Mat representation for the image data.
Definition at line 109 of file cv_bridge.h.
typedef boost::shared_ptr<CvImage const> cv_bridge::CvImage::ConstPtr |
Definition at line 165 of file cv_bridge.h.
Definition at line 164 of file cv_bridge.h.
|
inline |
Empty constructor.
Definition at line 119 of file cv_bridge.h.
|
inline |
Constructor.
Definition at line 124 of file cv_bridge.h.
sensor_msgs::CompressedImagePtr cv_bridge::CvImage::toCompressedImageMsg | ( | const Format | dst_format = JPG | ) | const |
dst_format is compress the image to desire format. Default value is empty string that will convert to jpg format. can be: jpg, jp2, bmp, png, tif at the moment support this format from opencv: http://docs.opencv.org/modules/highgui/doc/reading_and_writing_images_and_video.html#Mat imread(const string& filename, int flags)
Definition at line 470 of file cv_bridge.cpp.
void cv_bridge::CvImage::toCompressedImageMsg | ( | sensor_msgs::CompressedImage & | ros_image, |
const Format | dst_format = JPG |
||
) | const |
dst_format is compress the image to desire format. Default value is empty string that will convert to jpg format. can be: jpg, jp2, bmp, png, tif at the moment support this format from opencv: http://docs.opencv.org/modules/highgui/doc/reading_and_writing_images_and_video.html#Mat imread(const string& filename, int flags)
Definition at line 513 of file cv_bridge.cpp.
sensor_msgs::ImagePtr cv_bridge::CvImage::toImageMsg | ( | ) | const |
Convert this message to a ROS sensor_msgs::Image message.
The returned sensor_msgs::Image message contains a copy of the image data.
Definition at line 388 of file cv_bridge.cpp.
void cv_bridge::CvImage::toImageMsg | ( | sensor_msgs::Image & | ros_image | ) | const |
Copy the message data to a ROS sensor_msgs::Image message.
This overload is intended mainly for aggregate messages such as stereo_msgs::DisparityImage, which contains a sensor_msgs::Image as a data member.
Definition at line 395 of file cv_bridge.cpp.
std::string cv_bridge::CvImage::encoding |
Image encoding ("mono8", "bgr8", etc.)
Definition at line 113 of file cv_bridge.h.
std_msgs::Header cv_bridge::CvImage::header |
ROS header.
Definition at line 112 of file cv_bridge.h.
cv::Mat cv_bridge::CvImage::image |
Image data for use with OpenCV.
Definition at line 114 of file cv_bridge.h.
|
protected |
Definition at line 168 of file cv_bridge.h.