web_video_server.h
Go to the documentation of this file.
00001 #ifndef WEB_VIDEO_SERVER_H_
00002 #define WEB_VIDEO_SERVER_H_
00003 
00004 #include <ros/ros.h>
00005 #include <cv_bridge/cv_bridge.h>
00006 #include <vector>
00007 #include "web_video_server/image_streamer.h"
00008 #include "async_web_server_cpp/http_server.hpp"
00009 #include "async_web_server_cpp/http_request.hpp"
00010 #include "async_web_server_cpp/http_connection.hpp"
00011 
00012 namespace web_video_server
00013 {
00014 
00019 class WebVideoServer
00020 {
00021 public:
00026   WebVideoServer(ros::NodeHandle &nh, ros::NodeHandle &private_nh);
00027 
00031   virtual ~WebVideoServer();
00032 
00036   void spin();
00037 
00038   bool handle_stream(const async_web_server_cpp::HttpRequest &request,
00039                      async_web_server_cpp::HttpConnectionPtr connection, const char* begin, const char* end);
00040 
00041   bool handle_stream_viewer(const async_web_server_cpp::HttpRequest &request,
00042                             async_web_server_cpp::HttpConnectionPtr connection, const char* begin, const char* end);
00043 
00044   bool handle_snapshot(const async_web_server_cpp::HttpRequest &request,
00045                        async_web_server_cpp::HttpConnectionPtr connection, const char* begin, const char* end);
00046 
00047   bool handle_list_streams(const async_web_server_cpp::HttpRequest &request,
00048                            async_web_server_cpp::HttpConnectionPtr connection, const char* begin, const char* end);
00049 
00050 private:
00051   void cleanup_inactive_streams();
00052 
00053   ros::NodeHandle nh_;
00054   ros::Timer cleanup_timer_;
00055   int ros_threads_;
00056   int port_;
00057   std::string address_;
00058   boost::shared_ptr<async_web_server_cpp::HttpServer> server_;
00059   async_web_server_cpp::HttpRequestHandlerGroup handler_group_;
00060 
00061   std::vector<boost::shared_ptr<ImageStreamer> > image_subscribers_;
00062   std::map<std::string, boost::shared_ptr<ImageStreamerType> > stream_types_;
00063   boost::mutex subscriber_mutex_;
00064 };
00065 
00066 }
00067 
00068 #endif


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