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   server_.reset(
00065       new async_web_server_cpp::HttpServer(address_, boost::lexical_cast<std::string>(port_),
00066                                            boost::bind(ros_connection_logger, handler_group_, _1, _2, _3, _4),
00067                                            server_threads));
00068 }
00069 
00070 WebVideoServer::~WebVideoServer()
00071 {
00072 }
00073 
00074 void WebVideoServer::spin()
00075 {
00076   server_->run();
00077   ROS_INFO_STREAM("Waiting For connections on " << address_ << ":" << port_);
00078   ros::MultiThreadedSpinner spinner(ros_threads_);
00079   spinner.spin();
00080   server_->stop();
00081 }
00082 
00083 void WebVideoServer::cleanup_inactive_streams()
00084 {
00085   boost::mutex::scoped_lock lock(subscriber_mutex_, boost::try_to_lock);
00086   if (lock)
00087   {
00088     typedef std::vector<boost::shared_ptr<ImageStreamer> >::iterator itr_type;
00089     itr_type new_end = std::remove_if(image_subscribers_.begin(), image_subscribers_.end(),
00090                                       boost::bind(&ImageStreamer::isInactive, _1));
00091     if (__verbose)
00092     {
00093       for (itr_type itr = new_end; itr < image_subscribers_.end(); ++itr)
00094       {
00095         ROS_INFO_STREAM("Removed Stream: " << (*itr)->getTopic());
00096       }
00097     }
00098     image_subscribers_.erase(new_end, image_subscribers_.end());
00099   }
00100 }
00101 
00102 bool WebVideoServer::handle_stream(const async_web_server_cpp::HttpRequest &request,
00103                                    async_web_server_cpp::HttpConnectionPtr connection, const char* begin,
00104                                    const char* end)
00105 {
00106   std::string type = request.get_query_param_value_or_default("type", "mjpeg");
00107   if (stream_types_.find(type) != stream_types_.end())
00108   {
00109     boost::shared_ptr<ImageStreamer> streamer = stream_types_[type]->create_streamer(request, connection, nh_);
00110     streamer->start();
00111     boost::mutex::scoped_lock lock(subscriber_mutex_);
00112     image_subscribers_.push_back(streamer);
00113   }
00114   else
00115   {
00116     async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::not_found)(request, connection, begin,
00117                                                                                              end);
00118   }
00119   return true;
00120 }
00121 
00122 bool WebVideoServer::handle_snapshot(const async_web_server_cpp::HttpRequest &request,
00123                                      async_web_server_cpp::HttpConnectionPtr connection, const char* begin,
00124                                      const char* end)
00125 {
00126   boost::shared_ptr<ImageStreamer> streamer(new JpegSnapshotStreamer(request, connection, nh_));
00127   streamer->start();
00128 
00129   boost::mutex::scoped_lock lock(subscriber_mutex_);
00130   image_subscribers_.push_back(streamer);
00131   return true;
00132 }
00133 
00134 bool WebVideoServer::handle_stream_viewer(const async_web_server_cpp::HttpRequest &request,
00135                                           async_web_server_cpp::HttpConnectionPtr connection, const char* begin,
00136                                           const char* end)
00137 {
00138   std::string type = request.get_query_param_value_or_default("type", "mjpeg");
00139   if (stream_types_.find(type) != stream_types_.end())
00140   {
00141     std::string topic = request.get_query_param_value_or_default("topic", "");
00142 
00143     async_web_server_cpp::HttpReply::builder(async_web_server_cpp::HttpReply::ok).header("Connection", "close").header(
00144         "Server", "web_video_server").header("Content-type", "text/html;").write(connection);
00145 
00146     std::stringstream ss;
00147     ss << "<html><head><title>" << topic << "</title></head><body>";
00148     ss << "<h1>" << topic << "</h1>";
00149     ss << stream_types_[type]->create_viewer(request);
00150     ss << "</body></html>";
00151     connection->write(ss.str());
00152   }
00153   else
00154   {
00155     async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::not_found)(request, connection, begin,
00156                                                                                              end);
00157   }
00158   return true;
00159 }
00160 
00161 bool WebVideoServer::handle_list_streams(const async_web_server_cpp::HttpRequest &request,
00162                                          async_web_server_cpp::HttpConnectionPtr connection, const char* begin,
00163                                          const char* end)
00164 {
00165   std::string image_message_type = ros::message_traits::datatype<sensor_msgs::Image>();
00166   std::string camera_info_message_type = ros::message_traits::datatype<sensor_msgs::CameraInfo>();
00167 
00168   ros::master::V_TopicInfo topics;
00169   ros::master::getTopics(topics);
00170   ros::master::V_TopicInfo::iterator it;
00171   std::vector<std::string> image_topics;
00172   std::vector<std::string> camera_info_topics;
00173   for (it = topics.begin(); it != topics.end(); ++it)
00174   {
00175     const ros::master::TopicInfo &topic = *it;
00176     if (topic.datatype == image_message_type)
00177     {
00178       image_topics.push_back(topic.name);
00179     }
00180     else if (topic.datatype == camera_info_message_type)
00181     {
00182       camera_info_topics.push_back(topic.name);
00183     }
00184   }
00185 
00186   async_web_server_cpp::HttpReply::builder(async_web_server_cpp::HttpReply::ok).header("Connection", "close").header(
00187       "Server", "web_video_server").header("Cache-Control",
00188                                            "no-cache, no-store, must-revalidate, pre-check=0, post-check=0, max-age=0").header(
00189       "Pragma", "no-cache").header("Content-type", "text/html;").write(connection);
00190 
00191   connection->write("<html>"
00192                     "<head><title>ROS Image Topic List</title></head>"
00193                     "<body><h1>Available ROS Image Topics:</h1>");
00194   connection->write("<ul>");
00195   BOOST_FOREACH(std::string & camera_info_topic, camera_info_topics)
00196   {
00197     if (boost::algorithm::ends_with(camera_info_topic, "/camera_info"))
00198     {
00199       std::string base_topic = camera_info_topic.substr(0, camera_info_topic.size() - strlen("camera_info"));
00200       connection->write("<li>");
00201       connection->write(base_topic);
00202       connection->write("<ul>");
00203       std::vector<std::string>::iterator image_topic_itr = image_topics.begin();
00204       for (; image_topic_itr != image_topics.end();)
00205       {
00206         if (boost::starts_with(*image_topic_itr, base_topic))
00207         {
00208           connection->write("<li><a href=\"/stream_viewer?topic=");
00209           connection->write(*image_topic_itr);
00210           connection->write("\">");
00211           connection->write(image_topic_itr->substr(base_topic.size()));
00212           connection->write("</a> (");
00213           connection->write("<a href=\"/snapshot?topic=");
00214           connection->write(*image_topic_itr);
00215           connection->write("\">Snapshot</a>)");
00216           connection->write("</li>");
00217 
00218           image_topic_itr = image_topics.erase(image_topic_itr);
00219         }
00220         else
00221         {
00222           ++image_topic_itr;
00223         }
00224       }
00225       connection->write("</ul>");
00226     }
00227     connection->write("</li>");
00228   }
00229   connection->write("</ul></body></html>");
00230   return true;
00231 }
00232 
00233 }
00234 
00235 int main(int argc, char **argv)
00236 {
00237   ros::init(argc, argv, "web_video_server");
00238 
00239   ros::NodeHandle nh;
00240   ros::NodeHandle private_nh("~");
00241 
00242   web_video_server::WebVideoServer server(nh, private_nh);
00243   server.spin();
00244 
00245   return (0);
00246 }


web_video_server
Author(s): Mitchell Wills
autogenerated on Thu Aug 27 2015 15:42:12