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>
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 
41  async_web_server_cpp::HttpConnectionPtr connection, const char* begin, const char* end);
42 
44  async_web_server_cpp::HttpConnectionPtr connection, const char* begin, const char* end);
45 
47  async_web_server_cpp::HttpConnectionPtr connection, const char* begin, const char* end);
48 
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_;
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
web_video_server::WebVideoServer::handle_stream_viewer
bool handle_stream_viewer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, const char *begin, const char *end)
Definition: web_video_server.cpp:207
web_video_server::WebVideoServer::cleanup_inactive_streams
void cleanup_inactive_streams()
Definition: web_video_server.cpp:134
boost::shared_ptr< HttpConnection >
image_streamer.h
ros.h
web_video_server::WebVideoServer::subscriber_mutex_
boost::mutex subscriber_mutex_
Definition: web_video_server.h:71
web_video_server::WebVideoServer::~WebVideoServer
virtual ~WebVideoServer()
Destructor - Cleans up.
Definition: web_video_server.cpp:96
web_video_server::WebVideoServer::server_
boost::shared_ptr< async_web_server_cpp::HttpServer > server_
Definition: web_video_server.h:66
async_web_server_cpp::HttpRequestHandlerGroup
web_video_server::WebVideoServer
Definition: web_video_server.h:21
web_video_server::WebVideoServer::handle_list_streams
bool handle_list_streams(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, const char *begin, const char *end)
Definition: web_video_server.cpp:256
web_video_server::WebVideoServer::handle_stream
bool handle_stream(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, const char *begin, const char *end)
Definition: web_video_server.cpp:153
http_server.hpp
ros::SteadyTimer
web_video_server::WebVideoServer::WebVideoServer
WebVideoServer(ros::NodeHandle &nh, ros::NodeHandle &private_nh)
Constructor.
Definition: web_video_server.cpp:46
async_web_server_cpp::HttpRequest
web_video_server::WebVideoServer::image_subscribers_
std::vector< boost::shared_ptr< ImageStreamer > > image_subscribers_
Definition: web_video_server.h:69
web_video_server::WebVideoServer::cleanup_timer_
ros::Timer cleanup_timer_
Definition: web_video_server.h:60
http_connection.hpp
web_video_server
Definition: h264_streamer.h:9
web_video_server::WebVideoServer::port_
int port_
Definition: web_video_server.h:64
web_video_server::WebVideoServer::spin
void spin()
Starts the server and spins.
Definition: web_video_server.cpp:100
web_video_server::WebVideoServer::nh_
ros::NodeHandle nh_
Definition: web_video_server.h:56
web_video_server::WebVideoServer::address_
std::string address_
Definition: web_video_server.h:65
web_video_server::WebVideoServer::stream_types_
std::map< std::string, boost::shared_ptr< ImageStreamerType > > stream_types_
Definition: web_video_server.h:70
cv_bridge.h
http_request.hpp
web_video_server::WebVideoServer::publish_rate_
double publish_rate_
Definition: web_video_server.h:63
web_video_server::WebVideoServer::restreamFrames
void restreamFrames(double max_age)
Definition: web_video_server.cpp:122
web_video_server::WebVideoServer::handle_snapshot
bool handle_snapshot(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, const char *begin, const char *end)
Definition: web_video_server.cpp:195
web_video_server::WebVideoServer::ros_threads_
int ros_threads_
Definition: web_video_server.h:62
web_video_server::WebVideoServer::handler_group_
async_web_server_cpp::HttpRequestHandlerGroup handler_group_
Definition: web_video_server.h:67
ros::Timer
ros::NodeHandle


web_video_server
Author(s): Mitchell Wills
autogenerated on Wed Mar 2 2022 01:13:36