18 #ifndef IVT_BRIDGE_IVT_IMAGE_H    19 #define IVT_BRIDGE_IVT_IMAGE_H    21 #include <sensor_msgs/Image.h>    22 #include <opencv2/core/core.hpp>    23 #include <Image/ByteImage.h>    31                 std::runtime_error(description) {
    59         sensor_msgs::ImagePtr toImageMsg() 
const;
    67         void toImageMsg(sensor_msgs::Image& ros_image) 
const;
    89 IvtImagePtr 
toIvtCopy(
const sensor_msgs::ImageConstPtr& source, 
const std::string& encoding = std::string());
   103 IvtImagePtr 
toIvtCopy(
const sensor_msgs::Image& source, 
const std::string& encoding = std::string());
   119 IvtImageConstPtr 
toIvtShare(
const sensor_msgs::ImageConstPtr& source, 
const std::string& encoding = std::string());
   151 int getCvType(
const std::string& encoding);
   158 CByteImage::ImageType 
getIvtType(
const std::string& encoding);
 
boost::shared_ptr< IvtImage > IvtImagePtr
std::string encoding
Image encoding ("mono8", "bgr8", etc.) 
CByteImage::ImageType getIvtType(const std::string &encoding)
Get the CByteImage type enum corresponding to the encoding. 
boost::shared_ptr< IvtImage const  > IvtImageConstPtr
IvtImagePtr toIvtCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
Convert a sensor_msgs::Image message to an Ivt-compatible CByteImage, copying the image data...
int getCvType(const std::string &encoding)
Convert a IvtImage to another encoding. 
Image message class that is interoperable with sensor_msgs/Image but uses a CByteImage representation...
boost::shared_ptr< void const  > tracked_object_
IvtImageConstPtr toIvtShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
Convert an immutable sensor_msgs::Image message to an Ivt-compatible CByteImage, sharing the image da...
CByteImage * image
Image data for use with Ivt. 
std_msgs::Header header
ROS header. 
Exception(const std::string &description)