web_video_server.cpp
Go to the documentation of this file.
00001 #include <boost/foreach.hpp>
00002 #include <boost/lexical_cast.hpp>
00003 #include <boost/algorithm/string/predicate.hpp>
00004 #include <vector>
00005 #include <sensor_msgs/image_encodings.h>
00006 #include <opencv2/opencv.hpp>
00007 
00008 #include "web_video_server/web_video_server.h"
00009 #include "web_video_server/ros_compressed_streamer.h"
00010 #include "web_video_server/jpeg_streamers.h"
00011 #include "web_video_server/vp8_streamer.h"
00012 #include "async_web_server_cpp/http_reply.hpp"
00013 
00014 namespace web_video_server
00015 {
00016 
00017 static bool __verbose;
00018 
00019 static bool ros_connection_logger(async_web_server_cpp::HttpServerRequestHandler forward,
00020                                   const async_web_server_cpp::HttpRequest &request,
00021                                   async_web_server_cpp::HttpConnectionPtr connection, const char* begin,
00022                                   const char* end)
00023 {
00024   if (__verbose)
00025   {
00026     ROS_INFO_STREAM("Handling Request: " << request.uri);
00027   }
00028   try
00029   {
00030     forward(request, connection, begin, end);
00031   }
00032   catch (std::exception &e)
00033   {
00034     ROS_WARN_STREAM("Error Handling Request: " << e.what());
00035   }
00036 }
00037 
00038 WebVideoServer::WebVideoServer(ros::NodeHandle &nh, ros::NodeHandle &private_nh) :
00039     nh_(nh), handler_group_(
00040         async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::not_found))
00041 {
00042   cleanup_timer_ = nh.createTimer(ros::Duration(0.5), boost::bind(&WebVideoServer::cleanup_inactive_streams, this));
00043 
00044   private_nh.param("port", port_, 8080);
00045   private_nh.param("verbose", __verbose, true);
00046 
00047   private_nh.param<std::string>("address", address_, "0.0.0.0");
00048 
00049   int server_threads;
00050   private_nh.param("server_threads", server_threads, 1);
00051 
00052   private_nh.param("ros_threads", ros_threads_, 2);
00053 
00054   stream_types_["mjpeg"] = boost::shared_ptr<ImageStreamerType>(new MjpegStreamerType());
00055   stream_types_["ros_compressed"] = boost::shared_ptr<ImageStreamerType>(new RosCompressedStreamerType());
00056   stream_types_["vp8"] = boost::shared_ptr<ImageStreamerType>(new Vp8StreamerType());
00057 
00058   handler_group_.addHandlerForPath("/", boost::bind(&WebVideoServer::handle_list_streams, this, _1, _2, _3, _4));
00059   handler_group_.addHandlerForPath("/stream", boost::bind(&WebVideoServer::handle_stream, this, _1, _2, _3, _4));
00060   handler_group_.addHandlerForPath("/stream_viewer",
00061                                    boost::bind(&WebVideoServer::handle_stream_viewer, this, _1, _2, _3, _4));
00062   handler_group_.addHandlerForPath("/snapshot", boost::bind(&WebVideoServer::handle_snapshot, this, _1, _2, _3, _4));
00063 
00064   try
00065   {
00066     server_.reset(
00067         new async_web_server_cpp::HttpServer(address_, boost::lexical_cast<std::string>(port_),
00068                                              boost::bind(ros_connection_logger, handler_group_, _1, _2, _3, _4),
00069                                              server_threads));
00070   }
00071   catch(boost::exception& e)
00072   {
00073     ROS_ERROR("Exception when creating the web server! %s:%d", address_.c_str(), port_);
00074     throw;
00075   }
00076 }
00077 
00078 WebVideoServer::~WebVideoServer()
00079 {
00080 }
00081 
00082 void WebVideoServer::spin()
00083 {
00084   server_->run();
00085   ROS_INFO_STREAM("Waiting For connections on " << address_ << ":" << port_);
00086   ros::MultiThreadedSpinner spinner(ros_threads_);
00087   spinner.spin();
00088   server_->stop();
00089 }
00090 
00091 void WebVideoServer::cleanup_inactive_streams()
00092 {
00093   boost::mutex::scoped_lock lock(subscriber_mutex_, boost::try_to_lock);
00094   if (lock)
00095   {
00096     typedef std::vector<boost::shared_ptr<ImageStreamer> >::iterator itr_type;
00097     itr_type new_end = std::remove_if(image_subscribers_.begin(), image_subscribers_.end(),
00098                                       boost::bind(&ImageStreamer::isInactive, _1));
00099     if (__verbose)
00100     {
00101       for (itr_type itr = new_end; itr < image_subscribers_.end(); ++itr)
00102       {
00103         ROS_INFO_STREAM("Removed Stream: " << (*itr)->getTopic());
00104       }
00105     }
00106     image_subscribers_.erase(new_end, image_subscribers_.end());
00107   }
00108 }
00109 
00110 bool WebVideoServer::handle_stream(const async_web_server_cpp::HttpRequest &request,
00111                                    async_web_server_cpp::HttpConnectionPtr connection, const char* begin,
00112                                    const char* end)
00113 {
00114   std::string type = request.get_query_param_value_or_default("type", "mjpeg");
00115   if (stream_types_.find(type) != stream_types_.end())
00116   {
00117     boost::shared_ptr<ImageStreamer> streamer = stream_types_[type]->create_streamer(request, connection, nh_);
00118     streamer->start();
00119     boost::mutex::scoped_lock lock(subscriber_mutex_);
00120     image_subscribers_.push_back(streamer);
00121   }
00122   else
00123   {
00124     async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::not_found)(request, connection, begin,
00125                                                                                              end);
00126   }
00127   return true;
00128 }
00129 
00130 bool WebVideoServer::handle_snapshot(const async_web_server_cpp::HttpRequest &request,
00131                                      async_web_server_cpp::HttpConnectionPtr connection, const char* begin,
00132                                      const char* end)
00133 {
00134   boost::shared_ptr<ImageStreamer> streamer(new JpegSnapshotStreamer(request, connection, nh_));
00135   streamer->start();
00136 
00137   boost::mutex::scoped_lock lock(subscriber_mutex_);
00138   image_subscribers_.push_back(streamer);
00139   return true;
00140 }
00141 
00142 bool WebVideoServer::handle_stream_viewer(const async_web_server_cpp::HttpRequest &request,
00143                                           async_web_server_cpp::HttpConnectionPtr connection, const char* begin,
00144                                           const char* end)
00145 {
00146   std::string type = request.get_query_param_value_or_default("type", "mjpeg");
00147   if (stream_types_.find(type) != stream_types_.end())
00148   {
00149     std::string topic = request.get_query_param_value_or_default("topic", "");
00150 
00151     async_web_server_cpp::HttpReply::builder(async_web_server_cpp::HttpReply::ok).header("Connection", "close").header(
00152         "Server", "web_video_server").header("Content-type", "text/html;").write(connection);
00153 
00154     std::stringstream ss;
00155     ss << "<html><head><title>" << topic << "</title></head><body>";
00156     ss << "<h1>" << topic << "</h1>";
00157     ss << stream_types_[type]->create_viewer(request);
00158     ss << "</body></html>";
00159     connection->write(ss.str());
00160   }
00161   else
00162   {
00163     async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::not_found)(request, connection, begin,
00164                                                                                              end);
00165   }
00166   return true;
00167 }
00168 
00169 bool WebVideoServer::handle_list_streams(const async_web_server_cpp::HttpRequest &request,
00170                                          async_web_server_cpp::HttpConnectionPtr connection, const char* begin,
00171                                          const char* end)
00172 {
00173   std::string image_message_type = ros::message_traits::datatype<sensor_msgs::Image>();
00174   std::string camera_info_message_type = ros::message_traits::datatype<sensor_msgs::CameraInfo>();
00175 
00176   ros::master::V_TopicInfo topics;
00177   ros::master::getTopics(topics);
00178   ros::master::V_TopicInfo::iterator it;
00179   std::vector<std::string> image_topics;
00180   std::vector<std::string> camera_info_topics;
00181   for (it = topics.begin(); it != topics.end(); ++it)
00182   {
00183     const ros::master::TopicInfo &topic = *it;
00184     if (topic.datatype == image_message_type)
00185     {
00186       image_topics.push_back(topic.name);
00187     }
00188     else if (topic.datatype == camera_info_message_type)
00189     {
00190       camera_info_topics.push_back(topic.name);
00191     }
00192   }
00193 
00194   async_web_server_cpp::HttpReply::builder(async_web_server_cpp::HttpReply::ok).header("Connection", "close").header(
00195       "Server", "web_video_server").header("Cache-Control",
00196                                            "no-cache, no-store, must-revalidate, pre-check=0, post-check=0, max-age=0").header(
00197       "Pragma", "no-cache").header("Content-type", "text/html;").write(connection);
00198 
00199   connection->write("<html>"
00200                     "<head><title>ROS Image Topic List</title></head>"
00201                     "<body><h1>Available ROS Image Topics:</h1>");
00202   connection->write("<ul>");
00203   BOOST_FOREACH(std::string & camera_info_topic, camera_info_topics)
00204   {
00205     if (boost::algorithm::ends_with(camera_info_topic, "/camera_info"))
00206     {
00207       std::string base_topic = camera_info_topic.substr(0, camera_info_topic.size() - strlen("camera_info"));
00208       connection->write("<li>");
00209       connection->write(base_topic);
00210       connection->write("<ul>");
00211       std::vector<std::string>::iterator image_topic_itr = image_topics.begin();
00212       for (; image_topic_itr != image_topics.end();)
00213       {
00214         if (boost::starts_with(*image_topic_itr, base_topic))
00215         {
00216           connection->write("<li><a href=\"/stream_viewer?topic=");
00217           connection->write(*image_topic_itr);
00218           connection->write("\">");
00219           connection->write(image_topic_itr->substr(base_topic.size()));
00220           connection->write("</a> (");
00221           connection->write("<a href=\"/snapshot?topic=");
00222           connection->write(*image_topic_itr);
00223           connection->write("\">Snapshot</a>)");
00224           connection->write("</li>");
00225 
00226           image_topic_itr = image_topics.erase(image_topic_itr);
00227         }
00228         else
00229         {
00230           ++image_topic_itr;
00231         }
00232       }
00233       connection->write("</ul>");
00234     }
00235     connection->write("</li>");
00236   }
00237   connection->write("</ul>");
00238   // Add the rest of the image topics that don't have camera_info.
00239   connection->write("<ul>");
00240   std::vector<std::string>::iterator image_topic_itr = image_topics.begin();
00241   for (; image_topic_itr != image_topics.end();) {
00242     connection->write("<li><a href=\"/stream_viewer?topic=");
00243     connection->write(*image_topic_itr);
00244     connection->write("\">");
00245     connection->write(*image_topic_itr);
00246     connection->write("</a> (");
00247     connection->write("<a href=\"/snapshot?topic=");
00248     connection->write(*image_topic_itr);
00249     connection->write("\">Snapshot</a>)");
00250     connection->write("</li>");
00251 
00252     image_topic_itr = image_topics.erase(image_topic_itr);
00253   }
00254   connection->write("</ul></body></html>");
00255   return true;
00256 }
00257 
00258 }
00259 
00260 int main(int argc, char **argv)
00261 {
00262   ros::init(argc, argv, "web_video_server");
00263 
00264   ros::NodeHandle nh;
00265   ros::NodeHandle private_nh("~");
00266 
00267   web_video_server::WebVideoServer server(nh, private_nh);
00268   server.spin();
00269 
00270   return (0);
00271 }


web_video_server
Author(s): Mitchell Wills
autogenerated on Sun Jan 22 2017 04:06:43