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. | |
CvImage (const std_msgs::Header &header, const std::string &encoding, const cv::Mat &image=cv::Mat()) | |
Constructor. | |
sensor_msgs::ImagePtr | toImageMsg () const |
Convert this message to a ROS sensor_msgs::Image message. | |
void | toImageMsg (sensor_msgs::Image &ros_image) const |
Copy the message data to a ROS sensor_msgs::Image message. | |
Public Attributes | |
std::string | encoding |
Image encoding ("mono8", "bgr8", etc.) | |
std_msgs::Header | header |
ROS header. | |
cv::Mat | image |
Image data for use with OpenCV. | |
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 60 of file cv_bridge.h.
typedef boost::shared_ptr<CvImage const> cv_bridge::CvImage::ConstPtr |
Definition at line 97 of file cv_bridge.h.
typedef boost::shared_ptr<CvImage> cv_bridge::CvImage::Ptr |
Definition at line 96 of file cv_bridge.h.
cv_bridge::CvImage::CvImage | ( | ) | [inline] |
Empty constructor.
Definition at line 70 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 75 of file cv_bridge.h.
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 317 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 324 of file cv_bridge.cpp.
std::string cv_bridge::CvImage::encoding |
Image encoding ("mono8", "bgr8", etc.)
Definition at line 64 of file cv_bridge.h.
ROS header.
Definition at line 63 of file cv_bridge.h.
cv::Mat cv_bridge::CvImage::image |
Image data for use with OpenCV.
Definition at line 65 of file cv_bridge.h.
boost::shared_ptr<void const> cv_bridge::CvImage::tracked_object_ [protected] |
Definition at line 100 of file cv_bridge.h.