web_video_server.h
Go to the documentation of this file.
1 #ifndef WEB_VIDEO_SERVER_H_
2 #define WEB_VIDEO_SERVER_H_
3 
4 #include <ros/ros.h>
5 #include <cv_bridge/cv_bridge.h>
6 #include <vector>
8 #include "async_web_server_cpp/http_server.hpp"
9 #include "async_web_server_cpp/http_request.hpp"
10 #include "async_web_server_cpp/http_connection.hpp"
11 
12 #define ROS_HAS_STEADYTIMER (ROS_VERSION_MINIMUM(1, 13, 1) || ((ROS_VERSION_MINOR == 12) && (ROS_VERSION_PATCH >= 8)))
13 
14 namespace web_video_server
15 {
16 
22 {
23 public:
29 
33  virtual ~WebVideoServer();
34 
38  void spin();
39 
40  bool handle_stream(const async_web_server_cpp::HttpRequest &request,
41  async_web_server_cpp::HttpConnectionPtr connection, const char* begin, const char* end);
42 
43  bool handle_stream_viewer(const async_web_server_cpp::HttpRequest &request,
44  async_web_server_cpp::HttpConnectionPtr connection, const char* begin, const char* end);
45 
46  bool handle_snapshot(const async_web_server_cpp::HttpRequest &request,
47  async_web_server_cpp::HttpConnectionPtr connection, const char* begin, const char* end);
48 
49  bool handle_list_streams(const async_web_server_cpp::HttpRequest &request,
50  async_web_server_cpp::HttpConnectionPtr connection, const char* begin, const char* end);
51 
52 private:
53  void restreamFrames(double max_age);
55 
57 #if ROS_HAS_STEADYTIMER || defined USE_STEADY_TIMER
59 #else
61 #endif
63  double publish_rate_;
64  int port_;
65  std::string address_;
67  async_web_server_cpp::HttpRequestHandlerGroup handler_group_;
68 
69  std::vector<boost::shared_ptr<ImageStreamer> > image_subscribers_;
70  std::map<std::string, boost::shared_ptr<ImageStreamerType> > stream_types_;
71  boost::mutex subscriber_mutex_;
72 };
73 
74 }
75 
76 #endif
bool handle_stream_viewer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, const char *begin, const char *end)
std::map< std::string, boost::shared_ptr< ImageStreamerType > > stream_types_
bool handle_list_streams(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, const char *begin, const char *end)
virtual ~WebVideoServer()
Destructor - Cleans up.
std::vector< boost::shared_ptr< ImageStreamer > > image_subscribers_
async_web_server_cpp::HttpRequestHandlerGroup handler_group_
bool handle_snapshot(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, const char *begin, const char *end)
bool handle_stream(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, const char *begin, const char *end)
boost::shared_ptr< async_web_server_cpp::HttpServer > server_
void spin()
Starts the server and spins.
WebVideoServer(ros::NodeHandle &nh, ros::NodeHandle &private_nh)
Constructor.


web_video_server
Author(s): Mitchell Wills
autogenerated on Wed Jun 5 2019 20:38:04