image_streamer.h
Go to the documentation of this file.
00001 #ifndef IMAGE_STREAMER_H_
00002 #define IMAGE_STREAMER_H_
00003 
00004 #include <ros/ros.h>
00005 #include <image_transport/image_transport.h>
00006 #include <opencv2/opencv.hpp>
00007 #include "async_web_server_cpp/http_server.hpp"
00008 #include "async_web_server_cpp/http_request.hpp"
00009 
00010 namespace web_video_server
00011 {
00012 
00013 class ImageStreamer
00014 {
00015 public:
00016   ImageStreamer(const async_web_server_cpp::HttpRequest &request,
00017                 async_web_server_cpp::HttpConnectionPtr connection,
00018                 ros::NodeHandle& nh);
00019 
00020   virtual void start() = 0;
00021   virtual ~ImageStreamer();
00022 
00023   bool isInactive()
00024   {
00025     return inactive_;
00026   }
00027   ;
00028 
00032   virtual void restreamFrame(double max_age) = 0;
00033 
00034   std::string getTopic()
00035   {
00036     return topic_;
00037   }
00038   ;
00039 protected:
00040   async_web_server_cpp::HttpConnectionPtr connection_;
00041   async_web_server_cpp::HttpRequest request_;
00042   ros::NodeHandle nh_;
00043   bool inactive_;
00044   image_transport::Subscriber image_sub_;
00045   std::string topic_;
00046 };
00047 
00048 
00049 class ImageTransportImageStreamer : public ImageStreamer
00050 {
00051 public:
00052   ImageTransportImageStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection,
00053                               ros::NodeHandle& nh);
00054   virtual ~ImageTransportImageStreamer();
00055   virtual void start();
00056 
00057 protected:
00058   virtual void sendImage(const cv::Mat &, const ros::Time &time) = 0;
00059   virtual void restreamFrame(double max_age);
00060   virtual void initialize(const cv::Mat &);
00061 
00062   image_transport::Subscriber image_sub_;
00063   int output_width_;
00064   int output_height_;
00065   bool invert_;
00066   std::string default_transport_;
00067 
00068   ros::Time last_frame;
00069   cv::Mat output_size_image;
00070   boost::mutex send_mutex_;
00071 
00072 private:
00073   image_transport::ImageTransport it_;
00074   bool initialized_;
00075 
00076   void imageCallback(const sensor_msgs::ImageConstPtr &msg);
00077 };
00078 
00079 class ImageStreamerType
00080 {
00081 public:
00082   virtual boost::shared_ptr<ImageStreamer> create_streamer(const async_web_server_cpp::HttpRequest &request,
00083                                                            async_web_server_cpp::HttpConnectionPtr connection,
00084                                                            ros::NodeHandle& nh) = 0;
00085 
00086   virtual std::string create_viewer(const async_web_server_cpp::HttpRequest &request) = 0;
00087 };
00088 
00089 }
00090 
00091 #endif


web_video_server
Author(s): Mitchell Wills
autogenerated on Thu Jun 6 2019 18:02:48