Classes | Namespaces | Typedefs | Enumerations | Functions
cv_bridge.h File Reference
#include <sensor_msgs/Image.h>
#include <sensor_msgs/CompressedImage.h>
#include <sensor_msgs/image_encodings.h>
#include <ros/static_assert.h>
#include <opencv2/core/core.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include <opencv2/imgproc/types_c.h>
#include <stdexcept>
Include dependency graph for cv_bridge.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  cv_bridge::CvImage
 Image message class that is interoperable with sensor_msgs/Image but uses a more convenient cv::Mat representation for the image data. More...
 
struct  cv_bridge::CvtColorForDisplayOptions
 
class  cv_bridge::Exception
 

Namespaces

 cv_bridge
 

Typedefs

typedef boost::shared_ptr< CvImage const > cv_bridge::CvImageConstPtr
 
typedef boost::shared_ptr< CvImage > cv_bridge::CvImagePtr
 

Enumerations

enum  cv_bridge::Format {
  cv_bridge::BMP, cv_bridge::DIB, cv_bridge::JPG, cv_bridge::JPEG,
  cv_bridge::JPE, cv_bridge::JP2, cv_bridge::PNG, cv_bridge::PBM,
  cv_bridge::PGM, cv_bridge::PPM, cv_bridge::SR, cv_bridge::RAS,
  cv_bridge::TIFF, cv_bridge::TIF
}
 

Functions

CvImagePtr cv_bridge::cvtColor (const CvImageConstPtr &source, const std::string &encoding)
 Convert a CvImage to another encoding using the same rules as toCvCopy. More...
 
CvImageConstPtr cv_bridge::cvtColorForDisplay (const CvImageConstPtr &source, const std::string &encoding=std::string(), const CvtColorForDisplayOptions options=CvtColorForDisplayOptions())
 Converts an immutable sensor_msgs::Image message to another CvImage for display purposes, using practical conversion rules if needed. More...
 
int cv_bridge::getCvType (const std::string &encoding)
 Get the OpenCV type enum corresponding to the encoding. More...
 
CvImagePtr cv_bridge::toCvCopy (const sensor_msgs::CompressedImage &source, const std::string &encoding=std::string())
 
CvImagePtr cv_bridge::toCvCopy (const sensor_msgs::CompressedImageConstPtr &source, const std::string &encoding=std::string())
 
CvImagePtr cv_bridge::toCvCopy (const sensor_msgs::Image &source, const std::string &encoding=std::string())
 Convert a sensor_msgs::Image message to an OpenCV-compatible CvImage, copying the image data. More...
 
CvImagePtr cv_bridge::toCvCopy (const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
 Convert a sensor_msgs::Image message to an OpenCV-compatible CvImage, copying the image data. More...
 
CvImageConstPtr cv_bridge::toCvShare (const sensor_msgs::Image &source, const boost::shared_ptr< void const > &tracked_object, const std::string &encoding=std::string())
 Convert an immutable sensor_msgs::Image message to an OpenCV-compatible CvImage, sharing the image data if possible. More...
 
CvImageConstPtr cv_bridge::toCvShare (const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
 Convert an immutable sensor_msgs::Image message to an OpenCV-compatible CvImage, sharing the image data if possible. More...
 


cv_bridge
Author(s): Patrick Mihelich, James Bowman
autogenerated on Mon Oct 3 2022 02:45:56