#include <sensor_msgs/Image.h>#include <string>#include <vector>#include <ostream>#include <stdint.h>#include <iostream>#include <cmath>#include <stdexcept>#include "duration.h"#include <sys/time.h>#include "serialized_message.h"#include "message_forward.h"#include <ros/time.h>#include <boost/utility/enable_if.hpp>#include <boost/type_traits/remove_const.hpp>#include <boost/type_traits/remove_reference.hpp>#include "message_traits.h"#include "ros/exception.h"#include <boost/array.hpp>#include <boost/call_traits.hpp>#include <boost/mpl/and.hpp>#include <boost/mpl/or.hpp>#include <boost/mpl/not.hpp>#include <cstring>#include "ros/builtin_message_traits.h"#include "ros/macros.h"#include <cstdio>#include <sstream>#include <log4cxx/logger.h>#include <boost/static_assert.hpp>#include <cassert>#include <string.h>#include <boost/shared_ptr.hpp>#include "ros/serialization.h"#include "ros/message_operations.h"#include "ros/message.h"#include <assert.h>#include <stdlib.h>#include <float.h>#include <math.h>#include <limits.h>

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... | |
| class | cv_bridge::Exception |
Namespaces | |
| namespace | cv_bridge |
Typedefs | |
| typedef boost::shared_ptr < CvImage const > | cv_bridge::CvImageConstPtr |
| typedef boost::shared_ptr < CvImage > | cv_bridge::CvImagePtr |
Functions | |
| CvImagePtr | cv_bridge::cvtColor (const CvImageConstPtr &source, const std::string &encoding) |
| Convert a CvImage to another encoding. | |
| int | cv_bridge::getCvType (const std::string &encoding) |
| Get the OpenCV type enum corresponding to the encoding. | |
| 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. | |
| 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. | |
| 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. | |
| 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. | |