Public Types | Public Member Functions | Public Attributes | Protected Attributes | List of all members
cv_bridge::CvImage Class Reference

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< CvImagePtr
 

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_
 

Detailed Description

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 76 of file cv_bridge.h.

Member Typedef Documentation

Definition at line 132 of file cv_bridge.h.

Definition at line 131 of file cv_bridge.h.

Constructor & Destructor Documentation

cv_bridge::CvImage::CvImage ( )
inline

Empty constructor.

Definition at line 86 of file cv_bridge.h.

cv_bridge::CvImage::CvImage ( const std_msgs::Header header,
const std::string &  encoding,
const cv::Mat &  image = cv::Mat() 
)
inline

Constructor.

Definition at line 91 of file cv_bridge.h.

Member Function Documentation

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 437 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 480 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 355 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 362 of file cv_bridge.cpp.

Member Data Documentation

std::string cv_bridge::CvImage::encoding

Image encoding ("mono8", "bgr8", etc.)

Definition at line 80 of file cv_bridge.h.

std_msgs::Header cv_bridge::CvImage::header

ROS header.

Definition at line 79 of file cv_bridge.h.

cv::Mat cv_bridge::CvImage::image

Image data for use with OpenCV.

Definition at line 81 of file cv_bridge.h.

boost::shared_ptr<void const> cv_bridge::CvImage::tracked_object_
protected

Definition at line 135 of file cv_bridge.h.


The documentation for this class was generated from the following files:


cv_bridge
Author(s): Patrick Mihelich, James Bowman
autogenerated on Thu Dec 12 2019 03:52:01