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 #define ROS_HAS_STEADYTIMER (ROS_VERSION_MINIMUM(1, 13, 1) || ((ROS_VERSION_MINOR == 12) && (ROS_VERSION_PATCH >= 8)))
00013 
00014 namespace web_video_server
00015 {
00016 
00021 class WebVideoServer
00022 {
00023 public:
00028   WebVideoServer(ros::NodeHandle &nh, ros::NodeHandle &private_nh);
00029 
00033   virtual ~WebVideoServer();
00034 
00038   void spin();
00039 
00040   bool handle_stream(const async_web_server_cpp::HttpRequest &request,
00041                      async_web_server_cpp::HttpConnectionPtr connection, const char* begin, const char* end);
00042 
00043   bool handle_stream_viewer(const async_web_server_cpp::HttpRequest &request,
00044                             async_web_server_cpp::HttpConnectionPtr connection, const char* begin, const char* end);
00045 
00046   bool handle_snapshot(const async_web_server_cpp::HttpRequest &request,
00047                        async_web_server_cpp::HttpConnectionPtr connection, const char* begin, const char* end);
00048 
00049   bool handle_list_streams(const async_web_server_cpp::HttpRequest &request,
00050                            async_web_server_cpp::HttpConnectionPtr connection, const char* begin, const char* end);
00051 
00052 private:
00053   void restreamFrames(double max_age);
00054   void cleanup_inactive_streams();
00055 
00056   ros::NodeHandle nh_;
00057 #if ROS_HAS_STEADYTIMER || defined USE_STEADY_TIMER
00058   ros::SteadyTimer cleanup_timer_;
00059 #else
00060   ros::Timer cleanup_timer_;
00061 #endif
00062   int ros_threads_;
00063   double publish_rate_;
00064   int port_;
00065   std::string address_;
00066   boost::shared_ptr<async_web_server_cpp::HttpServer> server_;
00067   async_web_server_cpp::HttpRequestHandlerGroup handler_group_;
00068 
00069   std::vector<boost::shared_ptr<ImageStreamer> > image_subscribers_;
00070   std::map<std::string, boost::shared_ptr<ImageStreamerType> > stream_types_;
00071   boost::mutex subscriber_mutex_;
00072 };
00073 
00074 }
00075 
00076 #endif


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