Go to the documentation of this file.00001
00018 #ifndef IVT_BRIDGE_IVT_IMAGE_H
00019 #define IVT_BRIDGE_IVT_IMAGE_H
00020
00021 #include <sensor_msgs/Image.h>
00022 #include <opencv2/core/core.hpp>
00023 #include <Image/ByteImage.h>
00024 #include <stdexcept>
00025
00026 namespace ivt_bridge {
00027
00028 class Exception: public std::runtime_error {
00029 public:
00030 Exception(const std::string& description) :
00031 std::runtime_error(description) {
00032 }
00033 };
00034
00035 class IvtImage;
00036
00037 typedef boost::shared_ptr<IvtImage> IvtImagePtr;
00038 typedef boost::shared_ptr<IvtImage const> IvtImageConstPtr;
00039
00046 class IvtImage {
00047 public:
00048 std_msgs::Header header;
00049 std::string encoding;
00050 CByteImage *image;
00051
00052 ~IvtImage();
00053
00059 sensor_msgs::ImagePtr toImageMsg() const;
00060
00067 void toImageMsg(sensor_msgs::Image& ros_image) const;
00068
00069 protected:
00070 boost::shared_ptr<void const> tracked_object_;
00071
00073 friend IvtImageConstPtr toIvtShare(const sensor_msgs::Image& source, const boost::shared_ptr<void const>& tracked_object, const std::string& encoding);
00075 };
00076
00089 IvtImagePtr toIvtCopy(const sensor_msgs::ImageConstPtr& source, const std::string& encoding = std::string());
00090
00103 IvtImagePtr toIvtCopy(const sensor_msgs::Image& source, const std::string& encoding = std::string());
00104
00119 IvtImageConstPtr toIvtShare(const sensor_msgs::ImageConstPtr& source, const std::string& encoding = std::string());
00120
00139 IvtImageConstPtr toIvtShare(const sensor_msgs::Image& source, const boost::shared_ptr<void const>& tracked_object, const std::string& encoding = std::string());
00140
00144
00145
00151 int getCvType(const std::string& encoding);
00152
00158 CByteImage::ImageType getIvtType(const std::string& encoding);
00159
00160 }
00161
00162
00163 #endif