web_video_server.cpp
Go to the documentation of this file.
1 #include <boost/foreach.hpp>
2 #include <boost/lexical_cast.hpp>
3 #include <boost/algorithm/string/predicate.hpp>
4 #include <vector>
6 #include <opencv2/opencv.hpp>
7 
16 
17 namespace web_video_server
18 {
19 
20 static bool __verbose;
21 
22 static std::string __default_stream_type;
23 
25  const async_web_server_cpp::HttpRequest &request,
26  async_web_server_cpp::HttpConnectionPtr connection, const char* begin,
27  const char* end)
28 {
29  if (__verbose)
30  {
31  ROS_INFO_STREAM("Handling Request: " << request.uri);
32  }
33  try
34  {
35  forward(request, connection, begin, end);
36  return true;
37  }
38  catch (std::exception &e)
39  {
40  ROS_WARN_STREAM("Error Handling Request: " << e.what());
41  return false;
42  }
43  return false;
44 }
45 
47  nh_(nh), handler_group_(
48  async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::not_found))
49 {
50 #if ROS_HAS_STEADYTIMER || defined USE_STEADY_TIMER
52 #else
54 #endif
55 
56  private_nh.param("port", port_, 8080);
57  private_nh.param("verbose", __verbose, true);
58 
59  private_nh.param<std::string>("address", address_, "0.0.0.0");
60 
61  int server_threads;
62  private_nh.param("server_threads", server_threads, 1);
63 
64  private_nh.param("ros_threads", ros_threads_, 2);
65  private_nh.param("publish_rate", publish_rate_, -1.0);
66 
67  private_nh.param<std::string>("default_stream_type", __default_stream_type, "mjpeg");
68 
75 
76  handler_group_.addHandlerForPath("/", boost::bind(&WebVideoServer::handle_list_streams, this, _1, _2, _3, _4));
77  handler_group_.addHandlerForPath("/stream", boost::bind(&WebVideoServer::handle_stream, this, _1, _2, _3, _4));
78  handler_group_.addHandlerForPath("/stream_viewer",
79  boost::bind(&WebVideoServer::handle_stream_viewer, this, _1, _2, _3, _4));
80  handler_group_.addHandlerForPath("/snapshot", boost::bind(&WebVideoServer::handle_snapshot, this, _1, _2, _3, _4));
81 
82  try
83  {
84  server_.reset(
85  new async_web_server_cpp::HttpServer(address_, boost::lexical_cast<std::string>(port_),
86  boost::bind(ros_connection_logger, handler_group_, _1, _2, _3, _4),
87  server_threads));
88  }
89  catch(boost::exception& e)
90  {
91  ROS_ERROR("Exception when creating the web server! %s:%d", address_.c_str(), port_);
92  throw;
93  }
94 }
95 
97 {
98 }
99 
101 {
102  server_->run();
103  ROS_INFO_STREAM("Waiting For connections on " << address_ << ":" << port_);
104 
106  spinner.start();
107 
108  if ( publish_rate_ > 0 ) {
110 
111  while( ros::ok() ) {
112  this->restreamFrames( 1.0 / publish_rate_ );
113  r.sleep();
114  }
115  } else {
117  }
118 
119  server_->stop();
120 }
121 
122 void WebVideoServer::restreamFrames( double max_age )
123 {
124  boost::mutex::scoped_lock lock(subscriber_mutex_);
125 
126  typedef std::vector<boost::shared_ptr<ImageStreamer> >::iterator itr_type;
127 
128  for (itr_type itr = image_subscribers_.begin(); itr < image_subscribers_.end(); ++itr)
129  {
130  (*itr)->restreamFrame( max_age );
131  }
132 }
133 
135 {
136  boost::mutex::scoped_lock lock(subscriber_mutex_, boost::try_to_lock);
137  if (lock)
138  {
139  typedef std::vector<boost::shared_ptr<ImageStreamer> >::iterator itr_type;
140  itr_type new_end = std::partition(image_subscribers_.begin(), image_subscribers_.end(),
141  !boost::bind(&ImageStreamer::isInactive, _1));
142  if (__verbose)
143  {
144  for (itr_type itr = new_end; itr < image_subscribers_.end(); ++itr)
145  {
146  ROS_INFO_STREAM("Removed Stream: " << (*itr)->getTopic());
147  }
148  }
149  image_subscribers_.erase(new_end, image_subscribers_.end());
150  }
151 }
152 
154  async_web_server_cpp::HttpConnectionPtr connection, const char* begin,
155  const char* end)
156 {
157  std::string type = request.get_query_param_value_or_default("type", __default_stream_type);
158  if (stream_types_.find(type) != stream_types_.end())
159  {
160  std::string topic = request.get_query_param_value_or_default("topic", "");
161  // Fallback for topics without corresponding compressed topics
162  if (type == std::string("ros_compressed"))
163  {
164  std::string compressed_topic_name = topic + "/compressed";
166  ros::master::getTopics(topics);
167  bool did_find_compressed_topic = false;
168  for(ros::master::V_TopicInfo::iterator it = topics.begin(); it != topics.end(); ++it)
169  {
170  if (it->name == compressed_topic_name)
171  {
172  did_find_compressed_topic = true;
173  break;
174  }
175  }
176  if (!did_find_compressed_topic)
177  {
178  ROS_WARN_STREAM("Could not find compressed image topic for " << topic << ", falling back to mjpeg");
179  type = "mjpeg";
180  }
181  }
182  boost::shared_ptr<ImageStreamer> streamer = stream_types_[type]->create_streamer(request, connection, nh_);
183  streamer->start();
184  boost::mutex::scoped_lock lock(subscriber_mutex_);
185  image_subscribers_.push_back(streamer);
186  }
187  else
188  {
190  end);
191  }
192  return true;
193 }
194 
196  async_web_server_cpp::HttpConnectionPtr connection, const char* begin,
197  const char* end)
198 {
199  boost::shared_ptr<ImageStreamer> streamer(new JpegSnapshotStreamer(request, connection, nh_));
200  streamer->start();
201 
202  boost::mutex::scoped_lock lock(subscriber_mutex_);
203  image_subscribers_.push_back(streamer);
204  return true;
205 }
206 
208  async_web_server_cpp::HttpConnectionPtr connection, const char* begin,
209  const char* end)
210 {
211  std::string type = request.get_query_param_value_or_default("type", __default_stream_type);
212  if (stream_types_.find(type) != stream_types_.end())
213  {
214  std::string topic = request.get_query_param_value_or_default("topic", "");
215  // Fallback for topics without corresponding compressed topics
216  if (type == std::string("ros_compressed"))
217  {
218 
219  std::string compressed_topic_name = topic + "/compressed";
221  ros::master::getTopics(topics);
222  bool did_find_compressed_topic = false;
223  for(ros::master::V_TopicInfo::iterator it = topics.begin(); it != topics.end(); ++it)
224  {
225  if (it->name == compressed_topic_name)
226  {
227  did_find_compressed_topic = true;
228  break;
229  }
230  }
231  if (!did_find_compressed_topic)
232  {
233  ROS_WARN_STREAM("Could not find compressed image topic for " << topic << ", falling back to mjpeg");
234  type = "mjpeg";
235  }
236  }
237 
239  "Server", "web_video_server").header("Content-type", "text/html;").write(connection);
240 
241  std::stringstream ss;
242  ss << "<html><head><title>" << topic << "</title></head><body>";
243  ss << "<h1>" << topic << "</h1>";
244  ss << stream_types_[type]->create_viewer(request);
245  ss << "</body></html>";
246  connection->write(ss.str());
247  }
248  else
249  {
251  end);
252  }
253  return true;
254 }
255 
257  async_web_server_cpp::HttpConnectionPtr connection, const char* begin,
258  const char* end)
259 {
260  std::string image_message_type = ros::message_traits::datatype<sensor_msgs::Image>();
261  std::string camera_info_message_type = ros::message_traits::datatype<sensor_msgs::CameraInfo>();
262 
264  ros::master::getTopics(topics);
265  ros::master::V_TopicInfo::iterator it;
266  std::vector<std::string> image_topics;
267  std::vector<std::string> camera_info_topics;
268  for (it = topics.begin(); it != topics.end(); ++it)
269  {
270  const ros::master::TopicInfo &topic = *it;
271  if (topic.datatype == image_message_type)
272  {
273  image_topics.push_back(topic.name);
274  }
275  else if (topic.datatype == camera_info_message_type)
276  {
277  camera_info_topics.push_back(topic.name);
278  }
279  }
280 
282  "Server", "web_video_server").header("Cache-Control",
283  "no-cache, no-store, must-revalidate, pre-check=0, post-check=0, max-age=0").header(
284  "Pragma", "no-cache").header("Content-type", "text/html;").write(connection);
285 
286  connection->write("<html>"
287  "<head><title>ROS Image Topic List</title></head>"
288  "<body><h1>Available ROS Image Topics:</h1>");
289  connection->write("<ul>");
290  BOOST_FOREACH(std::string & camera_info_topic, camera_info_topics)
291  {
292  if (boost::algorithm::ends_with(camera_info_topic, "/camera_info"))
293  {
294  std::string base_topic = camera_info_topic.substr(0, camera_info_topic.size() - strlen("camera_info"));
295  connection->write("<li>");
296  connection->write(base_topic);
297  connection->write("<ul>");
298  std::vector<std::string>::iterator image_topic_itr = image_topics.begin();
299  for (; image_topic_itr != image_topics.end();)
300  {
301  if (boost::starts_with(*image_topic_itr, base_topic))
302  {
303  connection->write("<li><a href=\"/stream_viewer?topic=");
304  connection->write(*image_topic_itr);
305  connection->write("\">");
306  connection->write(image_topic_itr->substr(base_topic.size()));
307  connection->write("</a> (");
308  connection->write("<a href=\"/snapshot?topic=");
309  connection->write(*image_topic_itr);
310  connection->write("\">Snapshot</a>)");
311  connection->write("</li>");
312 
313  image_topic_itr = image_topics.erase(image_topic_itr);
314  }
315  else
316  {
317  ++image_topic_itr;
318  }
319  }
320  connection->write("</ul>");
321  }
322  connection->write("</li>");
323  }
324  connection->write("</ul>");
325  // Add the rest of the image topics that don't have camera_info.
326  connection->write("<ul>");
327  std::vector<std::string>::iterator image_topic_itr = image_topics.begin();
328  for (; image_topic_itr != image_topics.end();) {
329  connection->write("<li><a href=\"/stream_viewer?topic=");
330  connection->write(*image_topic_itr);
331  connection->write("\">");
332  connection->write(*image_topic_itr);
333  connection->write("</a> (");
334  connection->write("<a href=\"/snapshot?topic=");
335  connection->write(*image_topic_itr);
336  connection->write("\">Snapshot</a>)");
337  connection->write("</li>");
338 
339  image_topic_itr = image_topics.erase(image_topic_itr);
340  }
341  connection->write("</ul></body></html>");
342  return true;
343 }
344 
345 }
346 
347 int main(int argc, char **argv)
348 {
349  ros::init(argc, argv, "web_video_server");
350 
351  ros::NodeHandle nh;
352  ros::NodeHandle private_nh("~");
353 
354  web_video_server::WebVideoServer server(nh, private_nh);
355  server.spin();
356 
357  return (0);
358 }
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
ros_compressed_streamer.h
http_reply.hpp
web_video_server::PngStreamerType
Definition: png_streamers.h:27
web_video_server::WebVideoServer::cleanup_inactive_streams
void cleanup_inactive_streams()
Definition: web_video_server.cpp:134
image_encodings.h
web_video_server::RosCompressedStreamerType
Definition: ros_compressed_streamer.h:35
boost::shared_ptr< HttpConnection >
not_found
const char not_found[]
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros::AsyncSpinner::start
void start()
web_video_server::ImageStreamer::isInactive
bool isInactive()
Definition: image_streamer.h:23
vp9_streamer.h
ros::AsyncSpinner
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::HttpServerRequestHandler
boost::function< bool(const HttpRequest &, boost::shared_ptr< HttpConnection >, const char *begin, const char *end)> HttpServerRequestHandler
web_video_server.h
ros::master::getTopics
ROSCPP_DECL bool getTopics(V_TopicInfo &topics)
async_web_server_cpp::HttpServer
ros::ok
ROSCPP_DECL bool ok()
web_video_server::WebVideoServer
Definition: web_video_server.h:21
async_web_server_cpp
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
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
web_video_server::__default_stream_type
static std::string __default_stream_type
Definition: web_video_server.cpp:22
async_web_server_cpp::HttpReply::stock_reply
static HttpServerRequestHandler stock_reply(status_type status)
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
png_streamers.h
main
int main(int argc, char **argv)
Definition: web_video_server.cpp:347
web_video_server::WebVideoServer::WebVideoServer
WebVideoServer(ros::NodeHandle &nh, ros::NodeHandle &private_nh)
Constructor.
Definition: web_video_server.cpp:46
ros::master::V_TopicInfo
std::vector< TopicInfo > V_TopicInfo
web_video_server::MjpegStreamerType
Definition: jpeg_streamers.h:27
async_web_server_cpp::HttpRequest
async_web_server_cpp::ReplyBuilder::header
ReplyBuilder & header(const HttpHeader &header)
async_web_server_cpp::HttpRequest::get_query_param_value_or_default
std::string get_query_param_value_or_default(const std::string &name, const std::string &default_value) const
web_video_server::WebVideoServer::image_subscribers_
std::vector< boost::shared_ptr< ImageStreamer > > image_subscribers_
Definition: web_video_server.h:69
web_video_server::Vp8StreamerType
Definition: vp8_streamer.h:94
web_video_server::ros_connection_logger
static bool ros_connection_logger(async_web_server_cpp::HttpServerRequestHandler forward, const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, const char *begin, const char *end)
Definition: web_video_server.cpp:24
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
jpeg_streamers.h
web_video_server::WebVideoServer::cleanup_timer_
ros::Timer cleanup_timer_
Definition: web_video_server.h:60
web_video_server
Definition: h264_streamer.h:9
ros::Rate::sleep
bool sleep()
web_video_server::WebVideoServer::port_
int port_
Definition: web_video_server.h:64
web_video_server::H264StreamerType
Definition: h264_streamer.h:23
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
ros::NodeHandle::createSteadyTimer
SteadyTimer createSteadyTimer(SteadyTimerOptions &ops) const
vp8_streamer.h
async_web_server_cpp::HttpRequest::uri
std::string uri
ros::waitForShutdown
ROSCPP_DECL void waitForShutdown()
async_web_server_cpp::HttpReply::builder
static ReplyBuilder builder(status_type status)
web_video_server::WebVideoServer::stream_types_
std::map< std::string, boost::shared_ptr< ImageStreamerType > > stream_types_
Definition: web_video_server.h:70
ros::master::TopicInfo::datatype
std::string datatype
ROS_ERROR
#define ROS_ERROR(...)
web_video_server::Vp9StreamerType
Definition: vp9_streamer.h:22
async_web_server_cpp::ReplyBuilder::write
void write(HttpConnectionPtr connection)
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
async_web_server_cpp::HttpRequestHandlerGroup::addHandlerForPath
void addHandlerForPath(const std::string &path_regex, HttpServerRequestHandler handler)
ros::Rate
web_video_server::JpegSnapshotStreamer
Definition: jpeg_streamers.h:36
web_video_server::WebVideoServer::publish_rate_
double publish_rate_
Definition: web_video_server.h:63
ros::WallDuration
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
ros::master::TopicInfo
web_video_server::WebVideoServer::ros_threads_
int ros_threads_
Definition: web_video_server.h:62
async_web_server_cpp::HttpReply::not_found
not_found
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
web_video_server::WebVideoServer::handler_group_
async_web_server_cpp::HttpRequestHandlerGroup handler_group_
Definition: web_video_server.h:67
ros::Duration
web_video_server::__verbose
static bool __verbose
Definition: web_video_server.cpp:20
async_web_server_cpp::HttpReply::ok
ok
h264_streamer.h
ros::NodeHandle
ros::master::TopicInfo::name
std::string name


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