image_streamer.h
Go to the documentation of this file.
1 #ifndef IMAGE_STREAMER_H_
2 #define IMAGE_STREAMER_H_
3 
4 #include <ros/ros.h>
6 #include <opencv2/opencv.hpp>
9 
10 namespace web_video_server
11 {
12 
14 {
15 public:
18  ros::NodeHandle& nh);
19 
20  virtual void start() = 0;
21  virtual ~ImageStreamer();
22 
23  bool isInactive()
24  {
25  return inactive_;
26  }
27  ;
28 
32  virtual void restreamFrame(double max_age) = 0;
33 
34  std::string getTopic()
35  {
36  return topic_;
37  }
38  ;
39 protected:
43  bool inactive_;
45  std::string topic_;
46 };
47 
48 
50 {
51 public:
53  ros::NodeHandle& nh);
54  virtual ~ImageTransportImageStreamer();
55  virtual void start();
56 
57 protected:
58  virtual void sendImage(const cv::Mat &, const ros::Time &time) = 0;
59  virtual void restreamFrame(double max_age);
60  virtual void initialize(const cv::Mat &);
61 
65  bool invert_;
66  std::string default_transport_;
67 
70  boost::mutex send_mutex_;
71 
72 private:
75 
76  void imageCallback(const sensor_msgs::ImageConstPtr &msg);
77 };
78 
80 {
81 public:
82  virtual boost::shared_ptr<ImageStreamer> create_streamer(const async_web_server_cpp::HttpRequest &request,
84  ros::NodeHandle& nh) = 0;
85 
86  virtual std::string create_viewer(const async_web_server_cpp::HttpRequest &request) = 0;
87 };
88 
89 }
90 
91 #endif
async_web_server_cpp::HttpConnectionPtr connection_
ROSCONSOLE_DECL void initialize()
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
virtual void restreamFrame(double max_age)=0
async_web_server_cpp::HttpRequest request_
image_transport::ImageTransport it_
ImageStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle &nh)
image_transport::Subscriber image_sub_


web_video_server
Author(s): Mitchell Wills
autogenerated on Tue Mar 1 2022 00:04:38