connection.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2014, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  *
00029  * connection.h
00030  *
00031  *  Created on: Oct 30, 2012
00032  *      Author: jkammerl
00033  *
00034  *  & partly:
00035  *  Copyright (c) 2003-2011 Christopher M. Kohlhoff (chris at kohlhoff dot com)
00036  */
00037 
00038 #ifndef HTTP_CONNECTION_H
00039 #define HTTP_CONNECTION_H
00040 
00041 #include <boost/asio.hpp>
00042 #include <boost/array.hpp>
00043 #include <boost/noncopyable.hpp>
00044 #include <boost/shared_ptr.hpp>
00045 #include <boost/enable_shared_from_this.hpp>
00046 #include "reply.h"
00047 #include "request.h"
00048 #include "request_parser.h"
00049 
00050 #include "ffmpeg_encoder.h"
00051 #include "encoder_manager.h"
00052 
00053 #include "server_configuration.h"
00054 
00055 #define STREAM_PATH "/streams"
00056 #define WEB_PATH "/www"
00057 
00058 //#define HTTP_TRANSFER_ENCODING
00059 
00060 namespace ros_http_video_streamer
00061 {
00062 
00064 class connection
00065   : public boost::enable_shared_from_this<connection>,
00066     private boost::noncopyable
00067 {
00068 public:
00070   explicit connection(boost::asio::io_service& io_service,
00071                       EncoderManager& encoder_manager,
00072                       const ServerConfiguration& default_server_conf);
00073   virtual ~connection();
00074 
00076   boost::asio::ip::tcp::socket& socket();
00077 
00079   void start();
00080 
00081 private:
00082   // Get list of available image topics
00083   void getImageTopics();
00084 
00085   // send http headers for data streaming
00086   void sendHTTPStreamingHeaders();
00087 
00088   // Worker thread for streaming http data to the client
00089   void streamingWorkerThread(const std::string& topic,
00090                              const ServerConfiguration& config);
00091 
00092   // Generate a HTML page showing a list of available image topics
00093   void generateImageTopicHTML();
00094 
00095   // Generate a HTML page that displays a video stream
00096   void generateVideoStreamHTML(const std::string& image_topic,
00097                                const ServerConfiguration& config);
00098 
00099   // Parse streaming parameters from URL
00100   void getStreamingParametersFromURL(const std::string url, ServerConfiguration& config);
00101 
00103   void handleRead(const boost::system::error_code& e,
00104       std::size_t bytes_transferred);
00105 
00107   void handleWrite(const boost::system::error_code& e);
00108 
00111   static bool urlDecode(const std::string& in, std::string& out);
00112 
00113   // find mime extension for file type
00114   std::string mimeExtensionToType(const std::string& extension);
00115 
00116   // Default server configutaion
00117   const ServerConfiguration& server_conf_;
00118 
00119   // Vector of available image topics
00120   std::vector<std::string> image_topics_;
00121 
00123   boost::asio::io_service::strand strand_;
00124 
00126   boost::asio::ip::tcp::socket socket_;
00127 
00129   boost::array<char, 8192> buffer_;
00130 
00132   request request_;
00133 
00135   request_parser request_parser_;
00136 
00138   reply reply_;
00139 
00140   // Encoder manager used to lookup existing encoder instances
00141   EncoderManager& encoder_manager_;
00142 
00143   // streaming thread
00144   boost::shared_ptr<boost::thread> streaming_thread_;
00145 
00146   // streaming control
00147   bool do_streaming_;
00148 
00149 };
00150 
00151 typedef boost::shared_ptr<connection> connection_ptr;
00152 
00153 
00154 } // ros_http_video_streamer
00155 
00156 #endif // HTTP_SERVER3_CONNECTION_HPP


ros_web_video
Author(s): Julius Kammer
autogenerated on Thu Jun 6 2019 21:07:01