ivt_image.h
Go to the documentation of this file.
1 
18 #ifndef IVT_BRIDGE_IVT_IMAGE_H
19 #define IVT_BRIDGE_IVT_IMAGE_H
20 
21 #include <sensor_msgs/Image.h>
22 #include <opencv2/core/core.hpp>
23 #include <Image/ByteImage.h>
24 #include <stdexcept>
25 
26 namespace ivt_bridge {
27 
28 class Exception: public std::runtime_error {
29 public:
30  Exception(const std::string& description) :
31  std::runtime_error(description) {
32  }
33 };
34 
35 class IvtImage;
36 
39 
46 class IvtImage {
47 public:
48  std_msgs::Header header;
49  std::string encoding;
50  CByteImage *image;
51 
52  ~IvtImage();
53 
59  sensor_msgs::ImagePtr toImageMsg() const;
60 
67  void toImageMsg(sensor_msgs::Image& ros_image) const;
68 
69 protected:
70  boost::shared_ptr<void const> tracked_object_; // for sharing ownership, hold on to image message so it doesn't get released
71 
73  friend IvtImageConstPtr toIvtShare(const sensor_msgs::Image& source, const boost::shared_ptr<void const>& tracked_object, const std::string& encoding);
75 };
76 
89 IvtImagePtr toIvtCopy(const sensor_msgs::ImageConstPtr& source, const std::string& encoding = std::string());
90 
103 IvtImagePtr toIvtCopy(const sensor_msgs::Image& source, const std::string& encoding = std::string());
104 
119 IvtImageConstPtr toIvtShare(const sensor_msgs::ImageConstPtr& source, const std::string& encoding = std::string());
120 
139 IvtImageConstPtr toIvtShare(const sensor_msgs::Image& source, const boost::shared_ptr<void const>& tracked_object, const std::string& encoding = std::string());
140 
144 //IvtImagePtr cvtColor(const IvtImageConstPtr& source, const std::string& encoding);
145 
151 int getCvType(const std::string& encoding);
152 
158 CByteImage::ImageType getIvtType(const std::string& encoding);
159 
160 } // namespace ivt_bridge
161 
162 
163 #endif
boost::shared_ptr< IvtImage > IvtImagePtr
Definition: ivt_image.h:35
std::string encoding
Image encoding ("mono8", "bgr8", etc.)
Definition: ivt_image.h:49
CByteImage::ImageType getIvtType(const std::string &encoding)
Get the CByteImage type enum corresponding to the encoding.
Definition: ivt_image.cpp:76
boost::shared_ptr< IvtImage const > IvtImageConstPtr
Definition: ivt_image.h:38
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...
Definition: ivt_image.cpp:203
int getCvType(const std::string &encoding)
Convert a IvtImage to another encoding.
Definition: ivt_image.cpp:28
Image message class that is interoperable with sensor_msgs/Image but uses a CByteImage representation...
Definition: ivt_image.h:46
boost::shared_ptr< void const > tracked_object_
Definition: ivt_image.h:70
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...
Definition: ivt_image.cpp:217
CByteImage * image
Image data for use with Ivt.
Definition: ivt_image.h:50
std_msgs::Header header
ROS header.
Definition: ivt_image.h:48
Exception(const std::string &description)
Definition: ivt_image.h:30


asr_ivt_bridge
Author(s): Hutmacher Robin, Kleinert Daniel, Meißner Pascal
autogenerated on Mon Jun 10 2019 12:39:24