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 
00022   bool isInactive()
00023   {
00024     return inactive_;
00025   }
00026   ;
00027 
00028   std::string getTopic()
00029   {
00030     return topic_;
00031   }
00032   ;
00033 protected:
00034   async_web_server_cpp::HttpConnectionPtr connection_;
00035   async_web_server_cpp::HttpRequest request_;
00036   ros::NodeHandle nh_;
00037   bool inactive_;
00038   image_transport::Subscriber image_sub_;
00039   std::string topic_;
00040 };
00041 
00042 
00043 class ImageTransportImageStreamer : public ImageStreamer
00044 {
00045 public:
00046   ImageTransportImageStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection,
00047                               ros::NodeHandle& nh);
00048 
00049   virtual void start();
00050 
00051 protected:
00052   virtual void sendImage(const cv::Mat &, const ros::Time &time) = 0;
00053 
00054   virtual void initialize(const cv::Mat &);
00055 
00056   image_transport::Subscriber image_sub_;
00057   int output_width_;
00058   int output_height_;
00059   bool invert_;
00060   std::string default_transport_;
00061 private:
00062   image_transport::ImageTransport it_;
00063   bool initialized_;
00064 
00065   void imageCallback(const sensor_msgs::ImageConstPtr &msg);
00066 };
00067 
00068 class ImageStreamerType
00069 {
00070 public:
00071   virtual boost::shared_ptr<ImageStreamer> create_streamer(const async_web_server_cpp::HttpRequest &request,
00072                                                            async_web_server_cpp::HttpConnectionPtr connection,
00073                                                            ros::NodeHandle& nh) = 0;
00074 
00075   virtual std::string create_viewer(const async_web_server_cpp::HttpRequest &request) = 0;
00076 };
00077 
00078 }
00079 
00080 #endif


web_video_server
Author(s): Mitchell Wills
autogenerated on Thu Aug 27 2015 15:42:12