├── .gitignore ├── mainpage.dox ├── AUTHORS.md ├── include ├── header.h ├── request.h ├── reply.h ├── server.h ├── request_parser.h ├── server_configuration.h ├── image_subscriber.h ├── ffmpeg_encoder.h ├── ffmpeg_wrapper.h ├── connection.h └── encoder_manager.h ├── README.md ├── .travis.yml ├── package.xml ├── LICENSE ├── src ├── server.cpp ├── image_subscriber.cpp ├── topic_streamer.cpp ├── request_parser.cpp ├── reply.cpp ├── ffmpeg_encoder.cpp ├── ffmpeg_wrapper.cpp └── connection.cpp ├── CMakeLists.txt └── CHANGELOG.rst /.gitignore: -------------------------------------------------------------------------------- 1 | .cproject 2 | .project 3 | FFmpeg 4 | libvpx 5 | -------------------------------------------------------------------------------- /mainpage.dox: -------------------------------------------------------------------------------- 1 | /** 2 | \mainpage 3 | 4 | \b Streaming of ROS Image Topics via HTTP 5 | This package is typically used to stream encoded point cloud messages to a web browser for use in ros3djs. 6 | */ 7 | 8 | -------------------------------------------------------------------------------- /AUTHORS.md: -------------------------------------------------------------------------------- 1 | Original Authors 2 | ---------------- 3 | 4 | * [Julius Kammerl](http://www.kammerl.de) (jkammerl@willowgarage.com) 5 | 6 | Contributors 7 | ------------ 8 | 9 | * [Russell Toris](http://users.wpi.edu/~rctoris/) (rctoris@wpi.edu) 10 | -------------------------------------------------------------------------------- /include/header.h: -------------------------------------------------------------------------------- 1 | // 2 | // header.hpp 3 | // ~~~~~~~~~~ 4 | // 5 | // Copyright (c) 2003-2011 Christopher M. Kohlhoff (chris at kohlhoff dot com) 6 | // 7 | // Distributed under the Boost Software License, Version 1.0. (See accompanying 8 | // file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) 9 | // 10 | 11 | #ifndef HTTP_SERVER3_HEADER_H 12 | #define HTTP_SERVER3_HEADER_H 13 | 14 | #include 15 | 16 | namespace ros_http_video_streamer 17 | { 18 | 19 | struct header 20 | { 21 | std::string name; 22 | std::string value; 23 | }; 24 | 25 | } // ros_http_video_streamer 26 | 27 | #endif // HTTP_SERVER3_HEADER_HPP 28 | -------------------------------------------------------------------------------- /include/request.h: -------------------------------------------------------------------------------- 1 | // 2 | // request.hpp 3 | // ~~~~~~~~~~~ 4 | // 5 | // Copyright (c) 2003-2011 Christopher M. Kohlhoff (chris at kohlhoff dot com) 6 | // 7 | // Distributed under the Boost Software License, Version 1.0. (See accompanying 8 | // file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) 9 | // 10 | 11 | #ifndef HTTP_SERVER3_REQUEST_H 12 | #define HTTP_SERVER3_REQUEST_H 13 | 14 | #include 15 | #include 16 | #include "header.h" 17 | 18 | namespace ros_http_video_streamer 19 | { 20 | 21 | /// A request received from a client. 22 | struct request 23 | { 24 | std::string method; 25 | std::string uri; 26 | int http_version_major; 27 | int http_version_minor; 28 | std::vector
headers; 29 | }; 30 | 31 | } // ros_http_video_streamer 32 | 33 | #endif // HTTP_SERVER3_REQUEST_HPP 34 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | ## DEPRECATION NOTICE 2 | ros_web_video has been replaced by [web_video_server](https://github.com/RobotWebTools/web_video_server). 3 | 4 | ros_web_video [![Build Status](https://api.travis-ci.org/RobotWebTools/ros_web_video.png)](https://travis-ci.org/RobotWebTools/ros_web_video) 5 | ============= 6 | 7 | #### Streaming of ROS Image Topics via HTTP 8 | For full documentation, see [the ROS wiki](http://ros.org/wiki/ros_web_video). 9 | 10 | [Doxygen](http://docs.ros.org/indigo/api/ros_web_video/html/) files can be found on the ROS wiki. 11 | 12 | This project is released as part of the [Robot Web Tools](http://robotwebtools.org/) effort. 13 | 14 | ### License 15 | ros_web_video is released with a BSD license. For full terms and conditions, see the [LICENSE](LICENSE) file. 16 | 17 | ### Authors 18 | See the [AUTHORS](AUTHORS.md) file for a full list of contributors. 19 | -------------------------------------------------------------------------------- /.travis.yml: -------------------------------------------------------------------------------- 1 | language: 2 | - cpp 3 | - python 4 | python: 5 | - "2.7" 6 | compiler: 7 | - gcc 8 | 9 | branches: 10 | only: 11 | - master 12 | - develop 13 | 14 | install: 15 | - sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu precise main" > /etc/apt/sources.list.d/ros-latest.list' 16 | - wget http://packages.ros.org/ros.key -O - | sudo apt-key add - 17 | - sudo apt-get update -qq 18 | - sudo apt-get install python-catkin-pkg python-rosdep ros-groovy-catkin ros-hydro-catkin -qq 19 | - sudo rosdep init 20 | - rosdep update 21 | - mkdir -p /tmp/ws/src 22 | - ln -s `pwd` /tmp/ws/src/package 23 | - cd /tmp/ws 24 | - rosdep install --from-paths src --ignore-src --rosdistro groovy -y 25 | - rosdep install --from-paths src --ignore-src --rosdistro hydro -y 26 | 27 | script: 28 | - source /opt/ros/groovy/setup.bash 29 | - catkin_make 30 | - catkin_make install 31 | - rm -rf build/ install/ devel/ 32 | - source /opt/ros/hydro/setup.bash 33 | - catkin_make 34 | - catkin_make install 35 | -------------------------------------------------------------------------------- /package.xml: -------------------------------------------------------------------------------- 1 | 2 | ros_web_video 3 | 0.1.14 4 | Streaming of ROS Image Topics via HTTP 5 | 6 | Russell Toris 7 | Julius Kammer 8 | 9 | BSD 10 | 11 | http://wiki.ros.org/ros_web_video 12 | https://github.com/RobotWebTools/ros_web_video/issues 13 | https://github.com/RobotWebTools/ros_web_video 14 | 15 | catkin 16 | 17 | bzip2 18 | image_transport 19 | mk 20 | roscpp 21 | rostime 22 | sensor_msgs 23 | yasm 24 | zlib 25 | git 26 | 27 | bzip2 28 | image_transport 29 | mk 30 | roscpp 31 | rostime 32 | sensor_msgs 33 | zlib 34 | 35 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | Software License Agreement (BSD License) 2 | 3 | Copyright (c) 2014, Willow Garage Inc., Worcester Polytechnic Institute 4 | All rights reserved. 5 | 6 | Redistribution and use in source and binary forms, with or without 7 | modification, are permitted provided that the following conditions 8 | are met: 9 | 10 | * Redistributions of source code must retain the above copyright 11 | notice, this list of conditions and the following disclaimer. 12 | * Redistributions in binary form must reproduce the above 13 | copyright notice, this list of conditions and the following 14 | disclaimer in the documentation and/or other materials provided 15 | with the distribution. 16 | * Neither the name of Willow Garage Inc., Worcester Polytechnic 17 | Institute, nor the names of its contributors may be used to 18 | endorse or promote products derived from this software without 19 | specific prior written permission. 20 | 21 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 22 | "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 23 | LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 24 | FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 25 | COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 26 | INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 27 | BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 28 | LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 29 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 30 | LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 31 | ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 32 | POSSIBILITY OF SUCH DAMAGE. 33 | -------------------------------------------------------------------------------- /include/reply.h: -------------------------------------------------------------------------------- 1 | // 2 | // reply.hpp 3 | // ~~~~~~~~~ 4 | // 5 | // Copyright (c) 2003-2011 Christopher M. Kohlhoff (chris at kohlhoff dot com) 6 | // 7 | // Distributed under the Boost Software License, Version 1.0. (See accompanying 8 | // file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) 9 | // 10 | 11 | #ifndef HTTP_SERVER3_REPLY_H 12 | #define HTTP_SERVER3_REPLY_H 13 | 14 | #include 15 | #include 16 | #include 17 | #include "header.h" 18 | 19 | namespace ros_http_video_streamer 20 | { 21 | 22 | /// A reply to be sent to a client. 23 | struct reply 24 | { 25 | /// The status of the reply. 26 | enum status_type 27 | { 28 | ok = 200, 29 | created = 201, 30 | accepted = 202, 31 | no_content = 204, 32 | multiple_choices = 300, 33 | moved_permanently = 301, 34 | moved_temporarily = 302, 35 | not_modified = 304, 36 | bad_request = 400, 37 | unauthorized = 401, 38 | forbidden = 403, 39 | not_found = 404, 40 | internal_server_error = 500, 41 | not_implemented = 501, 42 | bad_gateway = 502, 43 | service_unavailable = 503 44 | } status; 45 | 46 | /// The headers to be included in the reply. 47 | std::vector
headers; 48 | 49 | /// The content to be sent in the reply. 50 | std::string content; 51 | 52 | /// Convert the reply into a vector of buffers. The buffers do not own the 53 | /// underlying memory blocks, therefore the reply object must remain valid and 54 | /// not be changed until the write operation has completed. 55 | std::vector to_buffers(); 56 | 57 | /// Get a stock reply. 58 | static reply stock_reply(status_type status); 59 | }; 60 | 61 | } // ros_http_video_streamer 62 | 63 | #endif // HTTP_SERVER3_REPLY_HPP 64 | -------------------------------------------------------------------------------- /include/server.h: -------------------------------------------------------------------------------- 1 | // 2 | // server.hpp 3 | // ~~~~~~~~~~ 4 | // 5 | // Copyright (c) 2003-2011 Christopher M. Kohlhoff (chris at kohlhoff dot com) 6 | // 7 | // Distributed under the Boost Software License, Version 1.0. (See accompanying 8 | // file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) 9 | // 10 | 11 | #ifndef HTTP_SERVER3_SERVER_H 12 | #define HTTP_SERVER3_SERVER_H 13 | 14 | #include 15 | #include 16 | #include 17 | #include 18 | #include 19 | #include "connection.h" 20 | 21 | #include "encoder_manager.h" 22 | 23 | #include "server_configuration.h" 24 | 25 | namespace ros_http_video_streamer 26 | { 27 | 28 | /// The top-level class of the HTTP server. 29 | class server 30 | : private boost::noncopyable 31 | { 32 | public: 33 | /// Construct the server to listen on the specified TCP address and port, and 34 | /// serve up files from the given directory. 35 | explicit server(const ServerConfiguration& server_conf, std::size_t thread_pool_size); 36 | 37 | /// Run the server's io_service loop. 38 | void run(); 39 | 40 | /// Stop the server. 41 | void stop(); 42 | 43 | private: 44 | /// Handle completion of an asynchronous accept operation. 45 | void handle_accept(const boost::system::error_code& e); 46 | 47 | const ServerConfiguration& server_conf_; 48 | 49 | /// The number of threads that will call io_service::run(). 50 | std::size_t thread_pool_size_; 51 | 52 | /// The io_service used to perform asynchronous operations. 53 | boost::asio::io_service io_service_; 54 | 55 | /// Acceptor used to listen for incoming connections. 56 | boost::asio::ip::tcp::acceptor acceptor_; 57 | 58 | // Encoder manager to handle encoding instances 59 | EncoderManager encoder_manager_; 60 | 61 | /// The next connection to be accepted. 62 | connection_ptr new_connection_; 63 | 64 | 65 | //std::vector > connection_threads_; 66 | }; 67 | 68 | } // ros_http_video_streamer 69 | 70 | #endif // HTTP_SERVER3_SERVER_HPP 71 | -------------------------------------------------------------------------------- /include/request_parser.h: -------------------------------------------------------------------------------- 1 | // 2 | // request_parser.hpp 3 | // ~~~~~~~~~~~~~~~~~~ 4 | // 5 | // Copyright (c) 2003-2011 Christopher M. Kohlhoff (chris at kohlhoff dot com) 6 | // 7 | // Distributed under the Boost Software License, Version 1.0. (See accompanying 8 | // file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) 9 | // 10 | 11 | #ifndef HTTP_SERVER3_REQUEST_PARSER_H 12 | #define HTTP_SERVER3_REQUEST_PARSER_H 13 | 14 | #include 15 | #include 16 | 17 | namespace ros_http_video_streamer 18 | { 19 | 20 | struct request; 21 | 22 | /// Parser for incoming requests. 23 | class request_parser 24 | { 25 | public: 26 | /// Construct ready to parse the request method. 27 | request_parser(); 28 | 29 | /// Reset to initial parser state. 30 | void reset(); 31 | 32 | /// Parse some data. The tribool return value is true when a complete request 33 | /// has been parsed, false if the data is invalid, indeterminate when more 34 | /// data is required. The InputIterator return value indicates how much of the 35 | /// input has been consumed. 36 | template 37 | boost::tuple parse(request& req, 38 | InputIterator begin, InputIterator end) 39 | { 40 | while (begin != end) 41 | { 42 | boost::tribool result = consume(req, *begin++); 43 | if (result || !result) 44 | return boost::make_tuple(result, begin); 45 | } 46 | boost::tribool result = boost::indeterminate; 47 | return boost::make_tuple(result, begin); 48 | } 49 | 50 | private: 51 | /// Handle the next character of input. 52 | boost::tribool consume(request& req, char input); 53 | 54 | /// Check if a byte is an HTTP character. 55 | static bool is_char(int c); 56 | 57 | /// Check if a byte is an HTTP control character. 58 | static bool is_ctl(int c); 59 | 60 | /// Check if a byte is defined as an HTTP tspecial character. 61 | static bool is_tspecial(int c); 62 | 63 | /// Check if a byte is a digit. 64 | static bool is_digit(int c); 65 | 66 | /// The current state of the parser. 67 | enum state 68 | { 69 | method_start, 70 | method, 71 | uri_start, 72 | uri, 73 | http_version_h, 74 | http_version_t_1, 75 | http_version_t_2, 76 | http_version_p, 77 | http_version_slash, 78 | http_version_major_start, 79 | http_version_major, 80 | http_version_minor_start, 81 | http_version_minor, 82 | expecting_newline_1, 83 | header_line_start, 84 | header_lws, 85 | header_name, 86 | space_before_header_value, 87 | header_value, 88 | expecting_newline_2, 89 | expecting_newline_3 90 | } state_; 91 | }; 92 | 93 | } // ros_http_video_streamer 94 | 95 | #endif // HTTP_SERVER3_REQUEST_PARSER_HPP 96 | -------------------------------------------------------------------------------- /src/server.cpp: -------------------------------------------------------------------------------- 1 | // 2 | // server.cpp 3 | // ~~~~~~~~~~ 4 | // 5 | // Copyright (c) 2003-2011 Christopher M. Kohlhoff (chris at kohlhoff dot com) 6 | // 7 | // Distributed under the Boost Software License, Version 1.0. (See accompanying 8 | // file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) 9 | // 10 | 11 | #include "server.h" 12 | 13 | #include 14 | #include 15 | #include 16 | #include 17 | 18 | #include 19 | 20 | namespace ros_http_video_streamer 21 | { 22 | 23 | server::server(const ServerConfiguration& server_conf, std::size_t thread_pool_size) 24 | : server_conf_(server_conf), 25 | thread_pool_size_(thread_pool_size), 26 | acceptor_(io_service_), 27 | encoder_manager_(), 28 | new_connection_(new connection(io_service_, encoder_manager_, server_conf)) 29 | { 30 | // Open the acceptor with the option to reuse the address (i.e. SO_REUSEADDR). 31 | boost::asio::ip::tcp::resolver resolver(io_service_); 32 | boost::asio::ip::tcp::resolver::query query("0.0.0.0", 33 | boost::lexical_cast(server_conf.port_)); 34 | boost::asio::ip::tcp::endpoint endpoint = *resolver.resolve(query); 35 | acceptor_.open(endpoint.protocol()); 36 | acceptor_.set_option(boost::asio::ip::tcp::acceptor::reuse_address(true)); 37 | acceptor_.bind(endpoint); 38 | acceptor_.listen(); 39 | acceptor_.async_accept(new_connection_->socket(), 40 | boost::bind(&server::handle_accept, this, 41 | boost::asio::placeholders::error)); 42 | } 43 | 44 | void server::run() 45 | { 46 | // Create a pool of threads to run all of the io_services. 47 | std::vector > threads; 48 | for (std::size_t i = 0; i < thread_pool_size_; ++i) 49 | { 50 | boost::shared_ptr thread(new boost::thread( 51 | boost::bind(&boost::asio::io_service::run, &io_service_))); 52 | threads.push_back(thread); 53 | } 54 | 55 | // Wait for all threads in the pool to exit. 56 | for (std::size_t i = 0; i < threads.size(); ++i) 57 | threads[i]->join(); 58 | } 59 | 60 | void server::stop() 61 | { 62 | io_service_.stop(); 63 | } 64 | 65 | void server::handle_accept(const boost::system::error_code& e) 66 | { 67 | if (!e) 68 | { 69 | 70 | // connection_threads_.push_back( boost::shared_ptr( new boost::thread( boost::bind(&connection::start, new_connection_ ) ) ) ); 71 | 72 | new_connection_->start(); 73 | new_connection_.reset(new connection(io_service_, encoder_manager_, server_conf_)); 74 | acceptor_.async_accept(new_connection_->socket(), 75 | boost::bind(&server::handle_accept, this, 76 | boost::asio::placeholders::error)); 77 | } 78 | } 79 | 80 | } // ros_http_video_streamer 81 | 82 | -------------------------------------------------------------------------------- /include/server_configuration.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (c) 2014, Willow Garage, Inc. 3 | * All rights reserved. 4 | * 5 | * Redistribution and use in source and binary forms, with or without 6 | * modification, are permitted provided that the following conditions are met: 7 | * 8 | * * Redistributions of source code must retain the above copyright 9 | * notice, this list of conditions and the following disclaimer. 10 | * * Redistributions in binary form must reproduce the above copyright 11 | * notice, this list of conditions and the following disclaimer in the 12 | * documentation and/or other materials provided with the distribution. 13 | * * Neither the name of the Willow Garage, Inc. nor the names of its 14 | * contributors may be used to endorse or promote products derived from 15 | * this software without specific prior written permission. 16 | * 17 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 18 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 19 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 20 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 21 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 22 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 23 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 24 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 25 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 26 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 27 | * POSSIBILITY OF SUCH DAMAGE. 28 | * 29 | * server_configuration.h 30 | * 31 | * Created on: Nov 1, 2012 32 | * Author: jkammerl 33 | */ 34 | 35 | #ifndef SERVER_CONFIGURATION_H_ 36 | #define SERVER_CONFIGURATION_H_ 37 | 38 | #include 39 | 40 | namespace ros_http_video_streamer 41 | { 42 | 43 | struct ServerConfiguration 44 | { 45 | ServerConfiguration() : 46 | // DEFAULT CONFIGURATION 47 | port_(8888), 48 | codec_("webm"), 49 | bitrate_(100000), 50 | framerate_(31), 51 | quality_(-1), 52 | gop_(60), 53 | frame_width_(-1), 54 | frame_height_(-1), 55 | profile_("realtime"), 56 | wwwroot_("./www"), 57 | ros_transport_("raw"), 58 | www_file_server_(false) 59 | { 60 | } 61 | 62 | //////////////////////////// 63 | // Server configuration 64 | //////////////////////////// 65 | 66 | // network port 67 | int port_; 68 | 69 | //////////////////////////// 70 | // Codec configuration 71 | //////////////////////////// 72 | 73 | // codec name 74 | std::string codec_; 75 | // maximum bit rate 76 | int bitrate_; 77 | // maximum frame rate 78 | int framerate_; 79 | // quality // quantization 80 | int quality_; 81 | // group of pictures -> I-frame rate 82 | int gop_; 83 | // width of frame 84 | int frame_width_; 85 | // height of frame 86 | int frame_height_; 87 | // codec profile 88 | std::string profile_; 89 | // codec profile 90 | std::string wwwroot_; 91 | // ros transport 92 | std::string ros_transport_; 93 | // enable www file server 94 | bool www_file_server_; 95 | }; 96 | 97 | } // ros_http_video_streamer 98 | 99 | #endif /* SERVER_CONFIGURATION_H_ */ 100 | -------------------------------------------------------------------------------- /include/image_subscriber.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (c) 2014, Willow Garage, Inc. 3 | * All rights reserved. 4 | * 5 | * Redistribution and use in source and binary forms, with or without 6 | * modification, are permitted provided that the following conditions are met: 7 | * 8 | * * Redistributions of source code must retain the above copyright 9 | * notice, this list of conditions and the following disclaimer. 10 | * * Redistributions in binary form must reproduce the above copyright 11 | * notice, this list of conditions and the following disclaimer in the 12 | * documentation and/or other materials provided with the distribution. 13 | * * Neither the name of the Willow Garage, Inc. nor the names of its 14 | * contributors may be used to endorse or promote products derived from 15 | * this software without specific prior written permission. 16 | * 17 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 18 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 19 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 20 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 21 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 22 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 23 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 24 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 25 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 26 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 27 | * POSSIBILITY OF SUCH DAMAGE. 28 | * 29 | * image_subscriber.h 30 | * 31 | * Created on: Oct 30, 2012 32 | * Author: jkammerl 33 | */ 34 | 35 | #ifndef ROS_IMAGE_SUBSCRIBE_H_ 36 | #define ROS_IMAGE_SUBSCRIBE_H_ 37 | 38 | #include 39 | #include 40 | 41 | #include 42 | #include 43 | #include 44 | #include 45 | 46 | 47 | #include "ros/ros.h" 48 | 49 | #include 50 | #include 51 | 52 | 53 | namespace ros_http_video_streamer 54 | { 55 | 56 | ////////////////////////////////////////////////////////// 57 | // This class subscribes to a ROS image publisher 58 | // and manages a queue of received images 59 | ////////////////////////////////////////////////////////// 60 | class ImageSubscriber 61 | { 62 | public: 63 | 64 | typedef boost::shared_ptr ptr; 65 | 66 | // Specify ROS topic in constructor 67 | ImageSubscriber(const std::string& topic, const std::string& transport); 68 | virtual ~ImageSubscriber(); 69 | 70 | // get image from receiver queue 71 | void getImageFromQueue( sensor_msgs::ImageConstPtr& frame); 72 | 73 | // empty queue 74 | void emptyQueue( ); 75 | 76 | private: 77 | // ROS subscriber callback 78 | void image_cb(const sensor_msgs::ImageConstPtr& msg); 79 | // reset connection 80 | void reset(); 81 | // subscribe 82 | void subscribe(); 83 | 84 | // ROS topic 85 | const std::string topic_; 86 | // ROS transport scheme 87 | const std::string transport_; 88 | 89 | // ROS node handle 90 | ros::NodeHandle nh; 91 | // ROS image transport & subscriber 92 | image_transport::ImageTransport it; 93 | boost::shared_ptr sub; 94 | 95 | // mutex to protect image queue 96 | boost::mutex frame_mutex_; 97 | // image queue 98 | std::deque frame_queue_; 99 | 100 | }; 101 | 102 | } // ros_http_video_streamer 103 | 104 | #endif /* ROS_IMAGE_SUBSCRIBE_H_ */ 105 | -------------------------------------------------------------------------------- /src/image_subscriber.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (c) 2014, Willow Garage, Inc. 3 | * All rights reserved. 4 | * 5 | * Redistribution and use in source and binary forms, with or without 6 | * modification, are permitted provided that the following conditions are met: 7 | * 8 | * * Redistributions of source code must retain the above copyright 9 | * notice, this list of conditions and the following disclaimer. 10 | * * Redistributions in binary form must reproduce the above copyright 11 | * notice, this list of conditions and the following disclaimer in the 12 | * documentation and/or other materials provided with the distribution. 13 | * * Neither the name of the Willow Garage, Inc. nor the names of its 14 | * contributors may be used to endorse or promote products derived from 15 | * this software without specific prior written permission. 16 | * 17 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 18 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 19 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 20 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 21 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 22 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 23 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 24 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 25 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 26 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 27 | * POSSIBILITY OF SUCH DAMAGE. 28 | * 29 | * image_subscriber.cpp 30 | * 31 | * Created on: Oct 30, 2012 32 | * Author: jkammerl 33 | */ 34 | 35 | #include "image_subscriber.h" 36 | 37 | // Size of image queue - 38 | // a large queue might increase the latency on the video stream 39 | #define IMAGE_BUFFER_SIZE 1 40 | 41 | namespace ros_http_video_streamer 42 | { 43 | 44 | ImageSubscriber::ImageSubscriber(const std::string& topic, const std::string& transport) : 45 | topic_(topic), 46 | transport_(transport), 47 | nh(""), 48 | it(nh), 49 | sub(), 50 | frame_mutex_(), 51 | frame_queue_() 52 | { 53 | if (!topic.empty()) 54 | { 55 | subscribe(); 56 | } 57 | } 58 | 59 | ImageSubscriber::~ImageSubscriber() 60 | { 61 | // boost::mutex::scoped_lock lock(frame_mutex_); 62 | sub.reset(); 63 | } 64 | 65 | void ImageSubscriber::subscribe() 66 | { 67 | boost::mutex::scoped_lock lock(frame_mutex_); 68 | 69 | sub.reset(new image_transport::SubscriberFilter()); 70 | sub->subscribe(it, topic_, 1, image_transport::TransportHints(transport_)); 71 | sub->registerCallback(boost::bind(&ImageSubscriber::image_cb, this, _1)); 72 | 73 | emptyQueue(); 74 | } 75 | 76 | void ImageSubscriber::emptyQueue() 77 | { 78 | frame_queue_.clear(); 79 | } 80 | 81 | void ImageSubscriber::image_cb(const sensor_msgs::ImageConstPtr& msg) 82 | { 83 | boost::mutex::scoped_lock lock(frame_mutex_); 84 | 85 | sensor_msgs::ImageConstPtr new_msg = sensor_msgs::ImageConstPtr(new const sensor_msgs::Image(*msg)); 86 | 87 | frame_queue_.push_front(new_msg); 88 | 89 | while (frame_queue_.size() > IMAGE_BUFFER_SIZE) 90 | frame_queue_.pop_back(); 91 | } 92 | 93 | void ImageSubscriber::getImageFromQueue(sensor_msgs::ImageConstPtr& frame) 94 | { 95 | frame.reset(); 96 | { 97 | boost::mutex::scoped_lock lock(frame_mutex_); 98 | 99 | // if queue not empty.. 100 | if (frame_queue_.size()) 101 | { 102 | // pop frame from back of queue 103 | frame = frame_queue_.back(); 104 | frame_queue_.pop_back(); 105 | } 106 | } 107 | } 108 | 109 | } // ros_http_video_streamer 110 | -------------------------------------------------------------------------------- /include/ffmpeg_encoder.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (c) 2014, Willow Garage, Inc. 3 | * All rights reserved. 4 | * 5 | * Redistribution and use in source and binary forms, with or without 6 | * modification, are permitted provided that the following conditions are met: 7 | * 8 | * * Redistributions of source code must retain the above copyright 9 | * notice, this list of conditions and the following disclaimer. 10 | * * Redistributions in binary form must reproduce the above copyright 11 | * notice, this list of conditions and the following disclaimer in the 12 | * documentation and/or other materials provided with the distribution. 13 | * * Neither the name of the Willow Garage, Inc. nor the names of its 14 | * contributors may be used to endorse or promote products derived from 15 | * this software without specific prior written permission. 16 | * 17 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 18 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 19 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 20 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 21 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 22 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 23 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 24 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 25 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 26 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 27 | * POSSIBILITY OF SUCH DAMAGE. 28 | * 29 | * 30 | * ffmpeg_encoder.h 31 | * 32 | * Created on: Oct 30, 2012 33 | * Author: jkammerl 34 | */ 35 | 36 | #ifndef FFMPEG_ENCODER_H_ 37 | #define FFMPEG_ENCODER_H_ 38 | 39 | #define DEPTH_TO_RGB_AVERAGE 40 | 41 | #include 42 | #include 43 | #include 44 | 45 | #include 46 | 47 | #include 48 | 49 | #include "ffmpeg_wrapper.h" 50 | #include "image_subscriber.h" 51 | #include "server_configuration.h" 52 | 53 | namespace ros_http_video_streamer 54 | { 55 | 56 | class FFMPEGEncoder 57 | { 58 | public: 59 | 60 | typedef boost::shared_ptr ptr; 61 | 62 | FFMPEGEncoder(const std::string& refID, 63 | const std::string& topic, 64 | const ServerConfiguration& config); 65 | 66 | virtual ~FFMPEGEncoder(); 67 | 68 | // receive header data 69 | // this method blocks until the header data is availble from the codec 70 | int initEncoding(std::vector& buf); 71 | 72 | // retrieve reverence string 73 | const std::string& getRefID(); 74 | 75 | // stop encoding 76 | void start(); 77 | 78 | // stop encoding 79 | void stop(); 80 | 81 | // encode frame 82 | void getVideoPacket(std::vector& buf); 83 | 84 | private: 85 | 86 | // method to convert floating point image to 8-bit monochrome image 87 | void convertFloatingPointImageToMono8(float* input, 88 | const std::size_t width, 89 | const std::size_t height, 90 | std::vector& output); 91 | 92 | // encoding thread running? 93 | bool doEncoding_; 94 | 95 | // reference ID used for registration 96 | const std::string refID_; 97 | 98 | // ROS topic 99 | const std::string topic_; 100 | 101 | // server&encoder configuration 102 | const ServerConfiguration& config_; 103 | 104 | // ROS image subscriber class 105 | ImageSubscriber subscriber_; 106 | 107 | // current frame ID 108 | unsigned frameID_; 109 | // init flag 110 | bool init_; 111 | 112 | boost::posix_time::ptime last_tick; 113 | 114 | // ffmpeg wrapper instance 115 | FFMPEG_Wrapper* ffmpeg_; 116 | 117 | }; 118 | 119 | } // ros_http_video_streamer 120 | 121 | #endif /* FFMPEG_ENCODER_H_ */ 122 | -------------------------------------------------------------------------------- /include/ffmpeg_wrapper.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (c) 2014, Willow Garage, Inc. 3 | * All rights reserved. 4 | * 5 | * Redistribution and use in source and binary forms, with or without 6 | * modification, are permitted provided that the following conditions are met: 7 | * 8 | * * Redistributions of source code must retain the above copyright 9 | * notice, this list of conditions and the following disclaimer. 10 | * * Redistributions in binary form must reproduce the above copyright 11 | * notice, this list of conditions and the following disclaimer in the 12 | * documentation and/or other materials provided with the distribution. 13 | * * Neither the name of the Willow Garage, Inc. nor the names of its 14 | * contributors may be used to endorse or promote products derived from 15 | * this software without specific prior written permission. 16 | * 17 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 18 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 19 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 20 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 21 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 22 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 23 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 24 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 25 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 26 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 27 | * POSSIBILITY OF SUCH DAMAGE. 28 | * 29 | * 30 | * ffmpeg_wrapper.h 31 | * 32 | * Created on: Oct 30, 2012 33 | * Author: jkammerl 34 | */ 35 | 36 | #include 37 | #include 38 | #include 39 | #include 40 | 41 | #include 42 | #include 43 | #include 44 | #include 45 | 46 | #include "server_configuration.h" 47 | 48 | #ifndef FFMPEG_WRAPPER_HEADER_INCLUDED 49 | #define FFMPEG_WRAPPER_HEADER_INCLUDED 50 | 51 | #ifdef HAVE_AV_CONFIG_H 52 | #undef HAVE_AV_CONFIG_H 53 | #endif 54 | 55 | #define CODER_BUF_SIZE 50000 56 | 57 | 58 | namespace ros_http_video_streamer 59 | { 60 | 61 | // ffmpeg forward declarations 62 | class AVCodec; 63 | class AVOutputFormat; 64 | class AVCodecContext; 65 | class AVFormatContext; 66 | class AVPicture; 67 | class AVStream; 68 | class AVFrame; 69 | 70 | 71 | class FFMPEG_Wrapper 72 | { 73 | 74 | public: 75 | 76 | FFMPEG_Wrapper(); 77 | ~FFMPEG_Wrapper(); 78 | 79 | // initialize ffmpeg coding 80 | int init(int input_width, 81 | int input_height, 82 | const ServerConfiguration& config); 83 | 84 | // shutdown ffmpeg coding 85 | void shutdown(); 86 | 87 | // encode bgr8 encoded frame 88 | void encode_bgr_frame(uint8_t *bgr_data, std::vector& encoded_frame); 89 | // encode rgb8 encoded frame 90 | void encode_rgb_frame(uint8_t *rgb_data, std::vector& encoded_frame); 91 | 92 | // encode bgr8 encoded frame 93 | void encode_mono8_frame(uint8_t *gray8_data, std::vector& encoded_frame); 94 | // encode bgr16 encoded frame 95 | void encode_mono16_frame(uint8_t *gray16_data, std::vector& encoded_frame); 96 | 97 | // retrieve header 98 | void get_header(std::vector& header); 99 | // retrieve trailer 100 | void get_trailer(std::vector& trailer); 101 | 102 | private: 103 | // templated encoding method 104 | template 105 | void encode_frame(uint8_t *image_data, std::vector& encoded_frame); 106 | 107 | //int ff_lockmgr(void **mutex, enum AVLockOp op); 108 | 109 | // mutex to protect encoding queue 110 | boost::mutex frame_mutex_; 111 | boost::mutex codec_mutex_; 112 | 113 | // ffmpeg contexts 114 | AVCodec *ffmpeg_codec_; 115 | AVOutputFormat *ffmpeg_output_format_; 116 | AVCodecContext *ffmpeg_codec_context_; 117 | AVFormatContext *ffmpeg_format_context_; 118 | AVPicture* ffmpeg_src_picture_; 119 | AVPicture* ffmpeg_dst_picture_; 120 | AVStream *ffmpeg_video_st_; 121 | AVFrame *ffmpeg_frame_; 122 | double ffmpeg_video_pts_; 123 | struct SwsContext *ffmpeg_sws_ctx_; 124 | 125 | // Server and codec configuration 126 | ServerConfiguration config_; 127 | 128 | // image dimensions 129 | int input_width_; 130 | int input_height_; 131 | int output_width_; 132 | int output_height_; 133 | 134 | boost::posix_time::ptime time_started_; 135 | 136 | bool init_; 137 | 138 | }; 139 | 140 | } // ros_http_video_streamer 141 | 142 | #endif 143 | 144 | -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(ros_web_video) 3 | 4 | ## Find catkin macros and libraries 5 | ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) 6 | ## is used, also find other catkin packages 7 | find_package(catkin REQUIRED roscpp rostime sensor_msgs image_transport mk) 8 | find_package(Boost COMPONENTS system filesystem thread REQUIRED) 9 | find_package(BZip2 REQUIRED) 10 | find_package(ZLIB REQUIRED) 11 | 12 | ################################################### 13 | ## Declare things to be passed to other projects ## 14 | ################################################### 15 | 16 | ## LIBRARIES: libraries you create in this project that dependent projects also need 17 | ## CATKIN_DEPENDS: catkin_packages dependent projects also need 18 | ## DEPENDS: system dependencies of this project that dependent projects also need 19 | catkin_package( 20 | INCLUDE_DIRS include 21 | LIBRARIES ${PROJECT_NAME} 22 | CATKIN_DEPENDS sensor_msgs image_transport roscpp rostime mk 23 | ) 24 | 25 | ########### 26 | ## Build ## 27 | ########### 28 | 29 | ## Specify additional locations of header files 30 | include_directories(include 31 | ${PROJECT_SOURCE_DIR}/FFmpeg/ 32 | ${catkin_INCLUDE_DIRS} 33 | ${Boost_INCLUDE_DIRS} 34 | ${ZLIB_INCLUDE_DIRS} 35 | ${BZIP2_INCLUDE_DIR} 36 | ) 37 | 38 | link_directories( 39 | ${catkin_LIBRARY_DIRS} 40 | ${Boost_LIBRARY_DIRS} 41 | ${ZLIB_LIBRARY_DIRS} 42 | ${BZIP2_LIBRARY_DIR} 43 | ) 44 | 45 | add_definitions( 46 | ${ZLIB_CFLAGS_OTHER} 47 | ${BZIP2_CFLAGS_OTHER} 48 | ) 49 | 50 | ## Grab external libraries 51 | execute_process( 52 | COMMAND git config --global http.sslVerify false 53 | WORKING_DIRECTORY ${PROJECT_SOURCE_DIR}/ 54 | ) 55 | execute_process( 56 | COMMAND git clone https://chromium.googlesource.com/webm/libvpx 57 | WORKING_DIRECTORY ${PROJECT_SOURCE_DIR}/ 58 | ) 59 | execute_process( 60 | COMMAND git checkout v1.2.0 61 | WORKING_DIRECTORY ${PROJECT_SOURCE_DIR}/libvpx 62 | ) 63 | execute_process( 64 | COMMAND git clone https://github.com/FFmpeg/FFmpeg.git 65 | WORKING_DIRECTORY ${PROJECT_SOURCE_DIR}/ 66 | ) 67 | execute_process( 68 | COMMAND git checkout n1.1 69 | WORKING_DIRECTORY ${PROJECT_SOURCE_DIR}/FFmpeg 70 | ) 71 | execute_process( 72 | COMMAND git config --global http.sslVerify true 73 | WORKING_DIRECTORY ${PROJECT_SOURCE_DIR}/ 74 | ) 75 | 76 | ## Setup libvpx 77 | execute_process( 78 | COMMAND ./configure --enable-vp8 79 | WORKING_DIRECTORY ${PROJECT_SOURCE_DIR}/libvpx/ 80 | ) 81 | execute_process( 82 | COMMAND make 83 | WORKING_DIRECTORY ${PROJECT_SOURCE_DIR}/libvpx/ 84 | ) 85 | 86 | ## Setup FFmpeg 87 | execute_process( 88 | COMMAND ./configure --enable-libvpx --extra-cflags="-I../libvpx" --extra-ldflags="-L../libvpx" --enable-gpl 89 | WORKING_DIRECTORY ${PROJECT_SOURCE_DIR}/FFmpeg/ 90 | ) 91 | execute_process( 92 | COMMAND make WORKING_DIRECTORY 93 | ${PROJECT_SOURCE_DIR}/FFmpeg/ 94 | ) 95 | 96 | ## Declare a cpp executables and libraries 97 | add_executable(${PROJECT_NAME} 98 | src/ffmpeg_wrapper.cpp 99 | src/server.cpp 100 | src/connection.cpp 101 | src/topic_streamer.cpp 102 | src/reply.cpp 103 | src/request_parser.cpp 104 | src/image_subscriber.cpp 105 | src/ffmpeg_encoder.cpp 106 | ) 107 | 108 | add_library(avcodec STATIC IMPORTED) 109 | set_property(TARGET avcodec 110 | PROPERTY IMPORTED_LOCATION ${PROJECT_SOURCE_DIR}/FFmpeg/libavcodec/libavcodec.a 111 | ) 112 | 113 | add_library(avformat STATIC IMPORTED) 114 | set_property(TARGET avformat PROPERTY 115 | IMPORTED_LOCATION ${PROJECT_SOURCE_DIR}/FFmpeg/libavformat/libavformat.a 116 | ) 117 | 118 | add_library(avutil STATIC IMPORTED) 119 | set_property(TARGET avutil PROPERTY 120 | IMPORTED_LOCATION ${PROJECT_SOURCE_DIR}/FFmpeg/libavutil/libavutil.a 121 | ) 122 | 123 | add_library(avfilter STATIC IMPORTED) 124 | set_property(TARGET avfilter PROPERTY 125 | IMPORTED_LOCATION ${PROJECT_SOURCE_DIR}/FFmpeg/libavfilter/libavfilter.a 126 | ) 127 | 128 | add_library(swscale STATIC IMPORTED) 129 | set_property(TARGET swscale PROPERTY 130 | IMPORTED_LOCATION ${PROJECT_SOURCE_DIR}/FFmpeg/libswscale/libswscale.a 131 | ) 132 | 133 | add_library(vpx STATIC IMPORTED) 134 | set_property(TARGET vpx PROPERTY 135 | IMPORTED_LOCATION ${PROJECT_SOURCE_DIR}/libvpx/libvpx.a 136 | ) 137 | 138 | target_link_libraries(${PROJECT_NAME} 139 | ${catkin_LIBRARIES} 140 | ${Boost_LIBRARIES} 141 | avcodec 142 | avformat 143 | avutil 144 | avfilter 145 | swscale 146 | vpx 147 | ${BZIP2_LIBRARIES} 148 | ${ZLIB_LIBRARIES} 149 | ) 150 | 151 | ############# 152 | ## Install ## 153 | ############# 154 | 155 | ## Mark executables and/or libraries for installation 156 | install(TARGETS ${PROJECT_NAME} 157 | RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} 158 | ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 159 | LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 160 | ) 161 | 162 | install(DIRECTORY include/ 163 | DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} 164 | FILES_MATCHING PATTERN "*.h" PATTERN "*.hpp" 165 | ) 166 | -------------------------------------------------------------------------------- /src/topic_streamer.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (c) 2014, Willow Garage, Inc. 3 | * All rights reserved. 4 | * 5 | * Redistribution and use in source and binary forms, with or without 6 | * modification, are permitted provided that the following conditions are met: 7 | * 8 | * * Redistributions of source code must retain the above copyright 9 | * notice, this list of conditions and the following disclaimer. 10 | * * Redistributions in binary form must reproduce the above copyright 11 | * notice, this list of conditions and the following disclaimer in the 12 | * documentation and/or other materials provided with the distribution. 13 | * * Neither the name of the Willow Garage, Inc. nor the names of its 14 | * contributors may be used to endorse or promote products derived from 15 | * this software without specific prior written permission. 16 | * 17 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 18 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 19 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 20 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 21 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 22 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 23 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 24 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 25 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 26 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 27 | * POSSIBILITY OF SUCH DAMAGE. 28 | * 29 | * main.cpp 30 | * 31 | * Created on: Nov 1, 2012 32 | * Author: jkammerl 33 | */ 34 | 35 | #include 36 | #include 37 | #include 38 | #include 39 | #include "server.h" 40 | 41 | #include "ros/ros.h" 42 | 43 | #include "server_configuration.h" 44 | 45 | void showConfig(const ros_http_video_streamer::ServerConfiguration& config) 46 | { 47 | std::cout << "ROS Http Video Streamer" << std::endl << std::endl; 48 | std::cout << "Settings:" << std::endl; 49 | std::cout << " Port: " << config.port_ << std::endl; 50 | std::cout << " Codec: " << config.codec_ << std::endl; 51 | std::cout << " Bitrate: " << config.bitrate_ << std::endl; 52 | std::cout << " Framerate: " << config.framerate_ << std::endl; 53 | std::cout << " Codec profile: " << config.profile_ << std::endl; 54 | std::cout << " Fileserver enabled: " << config.www_file_server_ << std::endl; 55 | std::cout << " Fileserver Root: " << config.wwwroot_ << std::endl; 56 | } 57 | 58 | int main(int argc, char* argv[]) 59 | { 60 | ros::init(argc, argv, "ROS_Http_Video_Streamer"); 61 | 62 | ROS_WARN("WARNING -- ros_web_video IS NOW DEPRECATED."); 63 | ROS_WARN("PLEASE SEE https://github.com/RobotWebTools/web_video_server."); 64 | 65 | // Default server configuration 66 | ros_http_video_streamer::ServerConfiguration server_conf; 67 | 68 | // ROS parameters 69 | ros::NodeHandle priv_nh_("~"); 70 | 71 | // read network port from param server 72 | priv_nh_.param("port", server_conf.port_, server_conf.port_); 73 | 74 | // read default codec from param server 75 | priv_nh_.param("codec", server_conf.codec_, server_conf.codec_); 76 | 77 | // read default bitrate from param server 78 | priv_nh_.param("bitrate", server_conf.bitrate_, server_conf.bitrate_); 79 | 80 | // read default frame rate from param server 81 | priv_nh_.param("framerate", server_conf.framerate_, server_conf.framerate_); 82 | 83 | // read quality parameter from param server 84 | priv_nh_.param("quality", server_conf.quality_, server_conf.quality_); 85 | 86 | // read group of pictures from param server 87 | priv_nh_.param("gop", server_conf.gop_, server_conf.gop_); 88 | 89 | // read default encoding profile from param server 90 | priv_nh_.param("profile", server_conf.profile_, server_conf.profile_); 91 | 92 | // read default encoding profile from param server 93 | priv_nh_.param("wwwroot", server_conf.wwwroot_, server_conf.wwwroot_); 94 | 95 | // read default ROS transport scheme 96 | priv_nh_.param("transport", server_conf.ros_transport_, server_conf.ros_transport_); 97 | 98 | // read default encoding profile from param server 99 | priv_nh_.param("www_file_server", server_conf.www_file_server_, server_conf.www_file_server_); 100 | 101 | showConfig(server_conf); 102 | 103 | try 104 | { 105 | 106 | // Run server in background thread. 107 | ros_http_video_streamer::server s(server_conf, 10); 108 | boost::thread t(boost::bind(&ros_http_video_streamer::server::run, &s)); 109 | 110 | ros::spin(); 111 | 112 | // Stop the server. 113 | s.stop(); 114 | t.join(); 115 | 116 | } 117 | catch (std::exception& e) 118 | { 119 | std::cerr << "exception: " << e.what() << "\n"; 120 | } 121 | 122 | return 0; 123 | } 124 | 125 | -------------------------------------------------------------------------------- /include/connection.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (c) 2014, Willow Garage, Inc. 3 | * All rights reserved. 4 | * 5 | * Redistribution and use in source and binary forms, with or without 6 | * modification, are permitted provided that the following conditions are met: 7 | * 8 | * * Redistributions of source code must retain the above copyright 9 | * notice, this list of conditions and the following disclaimer. 10 | * * Redistributions in binary form must reproduce the above copyright 11 | * notice, this list of conditions and the following disclaimer in the 12 | * documentation and/or other materials provided with the distribution. 13 | * * Neither the name of the Willow Garage, Inc. nor the names of its 14 | * contributors may be used to endorse or promote products derived from 15 | * this software without specific prior written permission. 16 | * 17 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 18 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 19 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 20 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 21 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 22 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 23 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 24 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 25 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 26 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 27 | * POSSIBILITY OF SUCH DAMAGE. 28 | * 29 | * connection.h 30 | * 31 | * Created on: Oct 30, 2012 32 | * Author: jkammerl 33 | * 34 | * & partly: 35 | * Copyright (c) 2003-2011 Christopher M. Kohlhoff (chris at kohlhoff dot com) 36 | */ 37 | 38 | #ifndef HTTP_CONNECTION_H 39 | #define HTTP_CONNECTION_H 40 | 41 | #include 42 | #include 43 | #include 44 | #include 45 | #include 46 | #include "reply.h" 47 | #include "request.h" 48 | #include "request_parser.h" 49 | 50 | #include "ffmpeg_encoder.h" 51 | #include "encoder_manager.h" 52 | 53 | #include "server_configuration.h" 54 | 55 | #define STREAM_PATH "/streams" 56 | #define WEB_PATH "/www" 57 | 58 | //#define HTTP_TRANSFER_ENCODING 59 | 60 | namespace ros_http_video_streamer 61 | { 62 | 63 | /// Represents a single connection from a client. 64 | class connection 65 | : public boost::enable_shared_from_this, 66 | private boost::noncopyable 67 | { 68 | public: 69 | /// Construct a connection with the given io_service. 70 | explicit connection(boost::asio::io_service& io_service, 71 | EncoderManager& encoder_manager, 72 | const ServerConfiguration& default_server_conf); 73 | virtual ~connection(); 74 | 75 | /// Get the socket associated with the connection. 76 | boost::asio::ip::tcp::socket& socket(); 77 | 78 | /// Start the first asynchronous operation for the connection. 79 | void start(); 80 | 81 | private: 82 | // Get list of available image topics 83 | void getImageTopics(); 84 | 85 | // send http headers for data streaming 86 | void sendHTTPStreamingHeaders(); 87 | 88 | // Worker thread for streaming http data to the client 89 | void streamingWorkerThread(const std::string& topic, 90 | const ServerConfiguration& config); 91 | 92 | // Generate a HTML page showing a list of available image topics 93 | void generateImageTopicHTML(); 94 | 95 | // Generate a HTML page that displays a video stream 96 | void generateVideoStreamHTML(const std::string& image_topic, 97 | const ServerConfiguration& config); 98 | 99 | // Parse streaming parameters from URL 100 | void getStreamingParametersFromURL(const std::string url, ServerConfiguration& config); 101 | 102 | /// Handle completion of a read operation. 103 | void handleRead(const boost::system::error_code& e, 104 | std::size_t bytes_transferred); 105 | 106 | /// Handle completion of a write operation. 107 | void handleWrite(const boost::system::error_code& e); 108 | 109 | /// Perform URL-decoding on a string. Returns false if the encoding was 110 | /// invalid. 111 | static bool urlDecode(const std::string& in, std::string& out); 112 | 113 | // find mime extension for file type 114 | std::string mimeExtensionToType(const std::string& extension); 115 | 116 | // Default server configutaion 117 | const ServerConfiguration& server_conf_; 118 | 119 | // Vector of available image topics 120 | std::vector image_topics_; 121 | 122 | /// Strand to ensure the connection's handlers are not called concurrently. 123 | boost::asio::io_service::strand strand_; 124 | 125 | /// Socket for the connection. 126 | boost::asio::ip::tcp::socket socket_; 127 | 128 | /// Buffer for incoming data. 129 | boost::array buffer_; 130 | 131 | /// The incoming request. 132 | request request_; 133 | 134 | /// The parser for the incoming request. 135 | request_parser request_parser_; 136 | 137 | /// The reply to be sent back to the client. 138 | reply reply_; 139 | 140 | // Encoder manager used to lookup existing encoder instances 141 | EncoderManager& encoder_manager_; 142 | 143 | // streaming thread 144 | boost::shared_ptr streaming_thread_; 145 | 146 | // streaming control 147 | bool do_streaming_; 148 | 149 | }; 150 | 151 | typedef boost::shared_ptr connection_ptr; 152 | 153 | 154 | } // ros_http_video_streamer 155 | 156 | #endif // HTTP_SERVER3_CONNECTION_HPP 157 | -------------------------------------------------------------------------------- /include/encoder_manager.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (c) 2014, Willow Garage, Inc. 3 | * All rights reserved. 4 | * 5 | * Redistribution and use in source and binary forms, with or without 6 | * modification, are permitted provided that the following conditions are met: 7 | * 8 | * * Redistributions of source code must retain the above copyright 9 | * notice, this list of conditions and the following disclaimer. 10 | * * Redistributions in binary form must reproduce the above copyright 11 | * notice, this list of conditions and the following disclaimer in the 12 | * documentation and/or other materials provided with the distribution. 13 | * * Neither the name of the Willow Garage, Inc. nor the names of its 14 | * contributors may be used to endorse or promote products derived from 15 | * this software without specific prior written permission. 16 | * 17 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 18 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 19 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 20 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 21 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 22 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 23 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 24 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 25 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 26 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 27 | * POSSIBILITY OF SUCH DAMAGE. 28 | * 29 | * 30 | * encoder_manager.h 31 | * 32 | * Created on: Oct 30, 2012 33 | * Author: jkammerl 34 | */ 35 | 36 | 37 | #ifndef ENCODING_MANAGER_H_ 38 | #define ENCODING_MANAGER_H_ 39 | 40 | #include "ffmpeg_encoder.h" 41 | 42 | #include "server_configuration.h" 43 | 44 | #include 45 | #include 46 | 47 | //#define SHARED_ENCODERS 48 | 49 | namespace ros_http_video_streamer 50 | { 51 | 52 | class EncoderManager 53 | { 54 | public: 55 | EncoderManager() : 56 | mutex_(), 57 | image_encoder_map_(), 58 | request_counter_(0) 59 | { 60 | } 61 | 62 | virtual ~EncoderManager() 63 | { 64 | } 65 | 66 | // 67 | FFMPEGEncoder::ptr subscribe(const std::string& topic, 68 | const ServerConfiguration& config) 69 | { 70 | boost::mutex::scoped_lock lock(mutex_); 71 | 72 | ++request_counter_; 73 | 74 | std::string refID = topic + ":" + 75 | config.codec_ + ":" + 76 | "BR:"+boost::lexical_cast(config.bitrate_) + 77 | "FR:"+boost::lexical_cast(config.framerate_) + 78 | "FW:"+boost::lexical_cast(config.frame_width_) + 79 | "FH:"+boost::lexical_cast(config.frame_height_) + 80 | "Q:"+boost::lexical_cast(config.quality_) + 81 | "GOP:"+boost::lexical_cast(config.gop_); 82 | 83 | FFMPEGEncoder::ptr image_encoder; 84 | 85 | #ifdef SHARED_ENCODERS 86 | // search for encoder instance in image_encoder_map_ 87 | std::map::iterator it; 88 | it = image_encoder_map_.find(refID); 89 | 90 | if (it!=image_encoder_map_.end()) 91 | { 92 | image_encoder = (it->second).enc_; 93 | (it->second).listener_count_++; 94 | } 95 | else 96 | { 97 | // if not found, create new instance of encoder 98 | image_encoder = FFMPEGEncoder::ptr(new FFMPEGEncoder(refID, topic, config)); 99 | 100 | EncoderInfo encInfo; 101 | encInfo.enc_ = image_encoder; 102 | encInfo.listener_count_ = 1; 103 | 104 | // add it to the image_encoder_map_ 105 | image_encoder_map_[refID] = encInfo; 106 | } 107 | #else 108 | // make request ID unique 109 | refID += "ReqID:" + boost::lexical_cast(request_counter_); 110 | image_encoder = FFMPEGEncoder::ptr(new FFMPEGEncoder(refID, topic, config)); 111 | 112 | EncoderInfo encInfo; 113 | encInfo.enc_ = image_encoder; 114 | encInfo.listener_count_ = 1; 115 | 116 | image_encoder_map_[refID] = encInfo; 117 | #endif 118 | 119 | return image_encoder; 120 | } 121 | 122 | void unsubscribe(const std::string& refID) 123 | { 124 | boost::mutex::scoped_lock lock(mutex_); 125 | 126 | // search for encoder instance 127 | std::map::iterator it; 128 | it = image_encoder_map_.find(refID); 129 | 130 | if (it != image_encoder_map_.end()) 131 | { 132 | EncoderInfo& encInfo = it->second; 133 | encInfo.listener_count_--; 134 | 135 | if (!encInfo.listener_count_) 136 | image_encoder_map_.erase(refID); 137 | 138 | ROS_INFO("Deleting encoder: %s", refID.c_str()); 139 | } 140 | } 141 | 142 | private: 143 | 144 | // struct that contains a shared pointer to an encoder instance and 145 | // manages the listener count 146 | struct EncoderInfo 147 | { 148 | EncoderInfo() : 149 | listener_count_(0) 150 | { 151 | } 152 | 153 | // shared pointer to encoder 154 | FFMPEGEncoder::ptr enc_; 155 | // amount of subscribed http listeners 156 | std::size_t listener_count_; 157 | }; 158 | 159 | // mutex to protect the image_encoder_map 160 | boost::mutex mutex_; 161 | // hash map that maps reference strings to image encoder instances 162 | std::map image_encoder_map_; 163 | 164 | // total amounts of encoder requests to manager class (used to construct unique reference IDs) 165 | unsigned int request_counter_; 166 | 167 | }; 168 | 169 | } // ros_http_video_streamer 170 | 171 | 172 | #endif /* ENCODING_MANAGER_H_ */ 173 | -------------------------------------------------------------------------------- /CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package ros_web_video 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.1.14 (2014-10-30) 6 | ------------------- 7 | * DEPRECATION NOTICE 8 | * Contributors: Russell Toris 9 | 10 | 0.1.13 (2014-10-08) 11 | ------------------- 12 | * Merge pull request #6 from mitchellwills/develop 13 | Fix ros_web_video HTTP header generation 14 | * Fixed ROS_INFO argument mismatch 15 | * Fixed HTTP Header generation 16 | * Contributors: Mitchell Wills, Russell Toris 17 | 18 | 0.1.12 (2014-04-21) 19 | ------------------- 20 | * travis speed fix 21 | * resets SSL flag in cmake 22 | * travis updated to remove external gits 23 | * Contributors: Russell Toris 24 | 25 | 0.1.11 (2014-04-18) 26 | ------------------- 27 | * CA-cert fix 28 | * Contributors: Russell Toris 29 | 30 | 0.1.10 (2014-04-17) 31 | ------------------- 32 | * ignores downloads 33 | * Remove submodule entry 34 | * modules removed 35 | * submodules being weird 36 | * Contributors: Russell Toris 37 | 38 | 0.1.9 (2014-04-17) 39 | ------------------ 40 | * build now downloads deps 41 | * Contributors: Russell Toris 42 | 43 | 0.1.8 (2014-04-17) 44 | ------------------ 45 | * submodule now in correct directory 46 | * travis now runs hydro and groovy and submodules now initilized in build 47 | * Contributors: Russell Toris 48 | 49 | 0.1.7 (2014-04-16) 50 | ------------------ 51 | * submodule moved to HTTPS 52 | * git submodules now used instead of willow servers for ffmpeg 53 | * v1.2.0 libvpx 54 | * libvpx added 55 | * moved to submodule 56 | * cmake cleanup 57 | * basic cleanup 58 | * adding travis.yml 59 | * adding travis.yml 60 | * Contributors: Julius Kammerl, Russell Toris 61 | 62 | 0.1.6 (2013-05-16) 63 | ------------------ 64 | * 0.1.5 -> 0.1.6 65 | * adding switch to disable file serving 66 | * adding file_server ros parameter 67 | * package.xml 68 | * renaming project to ros_web_video 69 | * Contributors: Julius Kammerl 70 | 71 | 0.1.5 (2013-04-22) 72 | ------------------ 73 | * 0.1.4 -> 0.1.5 74 | * patching "codec not found" crash 75 | * Contributors: Julius Kammerl 76 | 77 | 0.1.4 (2013-04-17) 78 | ------------------ 79 | * 0.1.3 -> 0.1.4 80 | * patching ffmpeg bug 81 | * Contributors: Julius Kammerl 82 | 83 | 0.1.3 (2013-02-15) 84 | ------------------ 85 | * 0.1.2 -> 0.1.3 86 | * adding download_checkmd5.py to 3rdparty 87 | * Contributors: Julius Kammerl 88 | 89 | 0.1.2 (2013-02-14 16:23) 90 | ------------------------ 91 | * 0.1.1 -> 0.1.2 92 | * adding mk package dependency 93 | * Contributors: Julius Kammerl 94 | 95 | 0.1.1 (2013-02-14 14:21) 96 | ------------------------ 97 | * version 0.1.1 98 | * integrating download_unpack_build.mk 99 | * Contributors: Julius Kammerl 100 | 101 | 0.1.0 (2013-02-13) 102 | ------------------ 103 | * version 0.1.0 104 | * adding download script to 3rdparty dir 105 | * Removed the '?' prefix requirement for URLs 106 | * making http headers optional 107 | * removing depthcloud proof-of-concept code 108 | * removed bad bzip2 dependecy 109 | * adding missing bzip2 dependency 110 | * more catkinization 111 | * adding zlib dependency to CMakeLists.txt and package.xml 112 | * Merge branch 'groovy-devel' of github.com:RobotWebTools/ros_http_video_streamer into groovy-devel 113 | * adding zlib to package.xml 114 | * minor.. added comments 115 | * adding MIME types for css and javascript files 116 | * fixing wwwroot bug 117 | * adding debug output to web file server 118 | * renaming webGL_pointcloud_image_encoder in CMakeList 119 | * renaming web_gl pointlcoud converter node 120 | * switching to local rosparam nodehandle + additional debug output 121 | * Merge pull request `#2 `_ from jon-weisz/cmake_fixcmake-fix-for-3rdparty 122 | fixed 3rdparty library build problem in ros_http_video_streamer by expli... 123 | * fixed 3rdparty library build problem in ros_http_video_streamer by explicitly executing the make command in CMakeLists.txt 124 | * more ffmpeg tuning 125 | * adding rosparam parameter in order to define the ROS image transport 126 | * adding filter in order to remove raw image topics from topic list 127 | * fixed encoding <-> data transmission synchronization 128 | * adding additional parameters to server configuration 129 | * adding roscpp and rostime deps 130 | * catkinizing image streamer 131 | * Adding 3rdparty checkout&compilation to CMake 132 | * Merge pull request `#1 `_ from KaijenHsiao/master 133 | added rosdep for yasm 134 | * added rosdep for yasm 135 | * adding mutex lock manager 136 | * adding additional mutext to protect av_open/av_close 137 | * explicit ffmpeg_wrapper shutdown 138 | * adding ROS makefile 139 | * cleanup 140 | * restructured javascript code 141 | * ffmepg initialization startup protection 142 | * transfercoding header fix 143 | * minor 144 | * shared pointers seem to be reused in openni_launch 145 | * more thread security 146 | * more mleak fixing 147 | * fixing memory leak 148 | * switching back to image transport 149 | * moving OrbitControls.js to js folder 150 | * Adding orbit control to webgl pointcloud viewer 151 | * unsubscribe from image topics in deconstructor 152 | * Merge branch 'master' of github.com:ros-interactive-manipulation/ros_http_video_streamer 153 | * major commit: improved pointcloud rendering, fixed image subscription bug 154 | * major commit: improved pointcloud rendering, fixed image subscription bug 155 | * fixing http headers 156 | * Merge branch 'master' of github.com:ros-interactive-manipulation/ros_http_video_streamer 157 | * adding .webm to URLs to make Firefox happy 158 | * fixing multithreading 159 | * Merge branch 'master' of github.com:ros-interactive-manipulation/ros_http_video_streamer 160 | * fixing race condition 161 | * missing include 162 | * improved depth encoding for webgl-pointcloud streamer 163 | * Adding ROS makefile 164 | * minor 165 | * removed depth encoding functionality from streaming server 166 | * adding webgl-based pointcloud streaming html page 167 | * adding file server functionality to streamer 168 | * adding webGL-based http frontend for pointcloud streaming + first working version of depth_to_webGL streamer 169 | * Merge branch 'master' of github.com:jkammerl/ros_http_video_streamer 170 | * more on depth_to_webGL_pointclouds.. 171 | * ffmpeg tuning 172 | * minor 173 | * adding additional parameters to the streaming URL request 174 | * added depth_to_webGL_pointclouds.cpp tool 175 | * adding global encoding configuration 176 | * more depth coding 177 | * Merge branch 'master' of github.com:jkammerl/ros_http_video_streamer 178 | * extended depthmap encoding 179 | * revisions, added image rescaling 180 | * improved parameter handling, added experimental depth_to_rgb encoding tests 181 | * adding webgl_pointcloud_streaming file 182 | * minor 183 | * adding ros_http_video_streamer namespace 184 | * initial commit 185 | * Contributors: Interactive Manipulation, Julius Kammerl, Kaijen Hsiao, jon-weisz 186 | -------------------------------------------------------------------------------- /src/request_parser.cpp: -------------------------------------------------------------------------------- 1 | // 2 | // request_parser.cpp 3 | // ~~~~~~~~~~~~~~~~~~ 4 | // 5 | // Copyright (c) 2003-2011 Christopher M. Kohlhoff (chris at kohlhoff dot com) 6 | // 7 | // Distributed under the Boost Software License, Version 1.0. (See accompanying 8 | // file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) 9 | // 10 | 11 | #include "request_parser.h" 12 | #include "request.h" 13 | 14 | namespace ros_http_video_streamer 15 | { 16 | 17 | request_parser::request_parser() 18 | : state_(method_start) 19 | { 20 | } 21 | 22 | void request_parser::reset() 23 | { 24 | state_ = method_start; 25 | } 26 | 27 | boost::tribool request_parser::consume(request& req, char input) 28 | { 29 | switch (state_) 30 | { 31 | case method_start: 32 | if (!is_char(input) || is_ctl(input) || is_tspecial(input)) 33 | { 34 | return false; 35 | } 36 | else 37 | { 38 | state_ = method; 39 | req.method.push_back(input); 40 | return boost::indeterminate; 41 | } 42 | case method: 43 | if (input == ' ') 44 | { 45 | state_ = uri; 46 | return boost::indeterminate; 47 | } 48 | else if (!is_char(input) || is_ctl(input) || is_tspecial(input)) 49 | { 50 | return false; 51 | } 52 | else 53 | { 54 | req.method.push_back(input); 55 | return boost::indeterminate; 56 | } 57 | case uri_start: 58 | if (is_ctl(input)) 59 | { 60 | return false; 61 | } 62 | else 63 | { 64 | state_ = uri; 65 | req.uri.push_back(input); 66 | return boost::indeterminate; 67 | } 68 | case uri: 69 | if (input == ' ') 70 | { 71 | state_ = http_version_h; 72 | return boost::indeterminate; 73 | } 74 | else if (is_ctl(input)) 75 | { 76 | return false; 77 | } 78 | else 79 | { 80 | req.uri.push_back(input); 81 | return boost::indeterminate; 82 | } 83 | case http_version_h: 84 | if (input == 'H') 85 | { 86 | state_ = http_version_t_1; 87 | return boost::indeterminate; 88 | } 89 | else 90 | { 91 | return false; 92 | } 93 | case http_version_t_1: 94 | if (input == 'T') 95 | { 96 | state_ = http_version_t_2; 97 | return boost::indeterminate; 98 | } 99 | else 100 | { 101 | return false; 102 | } 103 | case http_version_t_2: 104 | if (input == 'T') 105 | { 106 | state_ = http_version_p; 107 | return boost::indeterminate; 108 | } 109 | else 110 | { 111 | return false; 112 | } 113 | case http_version_p: 114 | if (input == 'P') 115 | { 116 | state_ = http_version_slash; 117 | return boost::indeterminate; 118 | } 119 | else 120 | { 121 | return false; 122 | } 123 | case http_version_slash: 124 | if (input == '/') 125 | { 126 | req.http_version_major = 0; 127 | req.http_version_minor = 0; 128 | state_ = http_version_major_start; 129 | return boost::indeterminate; 130 | } 131 | else 132 | { 133 | return false; 134 | } 135 | case http_version_major_start: 136 | if (is_digit(input)) 137 | { 138 | req.http_version_major = req.http_version_major * 10 + input - '0'; 139 | state_ = http_version_major; 140 | return boost::indeterminate; 141 | } 142 | else 143 | { 144 | return false; 145 | } 146 | case http_version_major: 147 | if (input == '.') 148 | { 149 | state_ = http_version_minor_start; 150 | return boost::indeterminate; 151 | } 152 | else if (is_digit(input)) 153 | { 154 | req.http_version_major = req.http_version_major * 10 + input - '0'; 155 | return boost::indeterminate; 156 | } 157 | else 158 | { 159 | return false; 160 | } 161 | case http_version_minor_start: 162 | if (is_digit(input)) 163 | { 164 | req.http_version_minor = req.http_version_minor * 10 + input - '0'; 165 | state_ = http_version_minor; 166 | return boost::indeterminate; 167 | } 168 | else 169 | { 170 | return false; 171 | } 172 | case http_version_minor: 173 | if (input == '\r') 174 | { 175 | state_ = expecting_newline_1; 176 | return boost::indeterminate; 177 | } 178 | else if (is_digit(input)) 179 | { 180 | req.http_version_minor = req.http_version_minor * 10 + input - '0'; 181 | return boost::indeterminate; 182 | } 183 | else 184 | { 185 | return false; 186 | } 187 | case expecting_newline_1: 188 | if (input == '\n') 189 | { 190 | state_ = header_line_start; 191 | return boost::indeterminate; 192 | } 193 | else 194 | { 195 | return false; 196 | } 197 | case header_line_start: 198 | if (input == '\r') 199 | { 200 | state_ = expecting_newline_3; 201 | return boost::indeterminate; 202 | } 203 | else if (!req.headers.empty() && (input == ' ' || input == '\t')) 204 | { 205 | state_ = header_lws; 206 | return boost::indeterminate; 207 | } 208 | else if (!is_char(input) || is_ctl(input) || is_tspecial(input)) 209 | { 210 | return false; 211 | } 212 | else 213 | { 214 | req.headers.push_back(header()); 215 | req.headers.back().name.push_back(input); 216 | state_ = header_name; 217 | return boost::indeterminate; 218 | } 219 | case header_lws: 220 | if (input == '\r') 221 | { 222 | state_ = expecting_newline_2; 223 | return boost::indeterminate; 224 | } 225 | else if (input == ' ' || input == '\t') 226 | { 227 | return boost::indeterminate; 228 | } 229 | else if (is_ctl(input)) 230 | { 231 | return false; 232 | } 233 | else 234 | { 235 | state_ = header_value; 236 | req.headers.back().value.push_back(input); 237 | return boost::indeterminate; 238 | } 239 | case header_name: 240 | if (input == ':') 241 | { 242 | state_ = space_before_header_value; 243 | return boost::indeterminate; 244 | } 245 | else if (!is_char(input) || is_ctl(input) || is_tspecial(input)) 246 | { 247 | return false; 248 | } 249 | else 250 | { 251 | req.headers.back().name.push_back(input); 252 | return boost::indeterminate; 253 | } 254 | case space_before_header_value: 255 | if (input == ' ') 256 | { 257 | state_ = header_value; 258 | return boost::indeterminate; 259 | } 260 | else 261 | { 262 | return false; 263 | } 264 | case header_value: 265 | if (input == '\r') 266 | { 267 | state_ = expecting_newline_2; 268 | return boost::indeterminate; 269 | } 270 | else if (is_ctl(input)) 271 | { 272 | return false; 273 | } 274 | else 275 | { 276 | req.headers.back().value.push_back(input); 277 | return boost::indeterminate; 278 | } 279 | case expecting_newline_2: 280 | if (input == '\n') 281 | { 282 | state_ = header_line_start; 283 | return boost::indeterminate; 284 | } 285 | else 286 | { 287 | return false; 288 | } 289 | case expecting_newline_3: 290 | return (input == '\n'); 291 | default: 292 | return false; 293 | } 294 | } 295 | 296 | bool request_parser::is_char(int c) 297 | { 298 | return c >= 0 && c <= 127; 299 | } 300 | 301 | bool request_parser::is_ctl(int c) 302 | { 303 | return (c >= 0 && c <= 31) || (c == 127); 304 | } 305 | 306 | bool request_parser::is_tspecial(int c) 307 | { 308 | switch (c) 309 | { 310 | case '(': case ')': case '<': case '>': case '@': 311 | case ',': case ';': case ':': case '\\': case '"': 312 | case '/': case '[': case ']': case '?': case '=': 313 | case '{': case '}': case ' ': case '\t': 314 | return true; 315 | default: 316 | return false; 317 | } 318 | } 319 | 320 | bool request_parser::is_digit(int c) 321 | { 322 | return c >= '0' && c <= '9'; 323 | } 324 | 325 | } // ros_http_video_streamer 326 | -------------------------------------------------------------------------------- /src/reply.cpp: -------------------------------------------------------------------------------- 1 | // 2 | // reply.cpp 3 | // ~~~~~~~~~ 4 | // 5 | // Copyright (c) 2003-2011 Christopher M. Kohlhoff (chris at kohlhoff dot com) 6 | // 7 | // Distributed under the Boost Software License, Version 1.0. (See accompanying 8 | // file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) 9 | // 10 | 11 | #include "reply.h" 12 | #include 13 | #include 14 | 15 | namespace ros_http_video_streamer 16 | { 17 | 18 | namespace status_strings { 19 | 20 | const std::string ok = 21 | "HTTP/1.0 200 OK\r\n"; 22 | const std::string created = 23 | "HTTP/1.0 201 Created\r\n"; 24 | const std::string accepted = 25 | "HTTP/1.0 202 Accepted\r\n"; 26 | const std::string no_content = 27 | "HTTP/1.0 204 No Content\r\n"; 28 | const std::string multiple_choices = 29 | "HTTP/1.0 300 Multiple Choices\r\n"; 30 | const std::string moved_permanently = 31 | "HTTP/1.0 301 Moved Permanently\r\n"; 32 | const std::string moved_temporarily = 33 | "HTTP/1.0 302 Moved Temporarily\r\n"; 34 | const std::string not_modified = 35 | "HTTP/1.0 304 Not Modified\r\n"; 36 | const std::string bad_request = 37 | "HTTP/1.0 400 Bad Request\r\n"; 38 | const std::string unauthorized = 39 | "HTTP/1.0 401 Unauthorized\r\n"; 40 | const std::string forbidden = 41 | "HTTP/1.0 403 Forbidden\r\n"; 42 | const std::string not_found = 43 | "HTTP/1.0 404 Not Found\r\n"; 44 | const std::string internal_server_error = 45 | "HTTP/1.0 500 Internal Server Error\r\n"; 46 | const std::string not_implemented = 47 | "HTTP/1.0 501 Not Implemented\r\n"; 48 | const std::string bad_gateway = 49 | "HTTP/1.0 502 Bad Gateway\r\n"; 50 | const std::string service_unavailable = 51 | "HTTP/1.0 503 Service Unavailable\r\n"; 52 | 53 | boost::asio::const_buffer to_buffer(reply::status_type status) 54 | { 55 | switch (status) 56 | { 57 | case reply::ok: 58 | return boost::asio::buffer(ok); 59 | case reply::created: 60 | return boost::asio::buffer(created); 61 | case reply::accepted: 62 | return boost::asio::buffer(accepted); 63 | case reply::no_content: 64 | return boost::asio::buffer(no_content); 65 | case reply::multiple_choices: 66 | return boost::asio::buffer(multiple_choices); 67 | case reply::moved_permanently: 68 | return boost::asio::buffer(moved_permanently); 69 | case reply::moved_temporarily: 70 | return boost::asio::buffer(moved_temporarily); 71 | case reply::not_modified: 72 | return boost::asio::buffer(not_modified); 73 | case reply::bad_request: 74 | return boost::asio::buffer(bad_request); 75 | case reply::unauthorized: 76 | return boost::asio::buffer(unauthorized); 77 | case reply::forbidden: 78 | return boost::asio::buffer(forbidden); 79 | case reply::not_found: 80 | return boost::asio::buffer(not_found); 81 | case reply::internal_server_error: 82 | return boost::asio::buffer(internal_server_error); 83 | case reply::not_implemented: 84 | return boost::asio::buffer(not_implemented); 85 | case reply::bad_gateway: 86 | return boost::asio::buffer(bad_gateway); 87 | case reply::service_unavailable: 88 | return boost::asio::buffer(service_unavailable); 89 | default: 90 | return boost::asio::buffer(internal_server_error); 91 | } 92 | } 93 | 94 | } // namespace status_strings 95 | 96 | namespace misc_strings { 97 | 98 | const char name_value_separator[] = { ':', ' ' }; 99 | const char crlf[] = { '\r', '\n' }; 100 | 101 | } // namespace misc_strings 102 | 103 | std::vector reply::to_buffers() 104 | { 105 | std::vector buffers; 106 | buffers.push_back(status_strings::to_buffer(status)); 107 | for (std::size_t i = 0; i < headers.size(); ++i) 108 | { 109 | header& h = headers[i]; 110 | buffers.push_back(boost::asio::buffer(h.name)); 111 | buffers.push_back(boost::asio::buffer(misc_strings::name_value_separator)); 112 | buffers.push_back(boost::asio::buffer(h.value)); 113 | buffers.push_back(boost::asio::buffer(misc_strings::crlf)); 114 | } 115 | buffers.push_back(boost::asio::buffer(misc_strings::crlf)); 116 | buffers.push_back(boost::asio::buffer(content)); 117 | return buffers; 118 | } 119 | 120 | namespace stock_replies { 121 | 122 | const char ok[] = ""; 123 | const char created[] = 124 | "" 125 | "Created" 126 | "

201 Created

" 127 | ""; 128 | const char accepted[] = 129 | "" 130 | "Accepted" 131 | "

202 Accepted

" 132 | ""; 133 | const char no_content[] = 134 | "" 135 | "No Content" 136 | "

204 Content

" 137 | ""; 138 | const char multiple_choices[] = 139 | "" 140 | "Multiple Choices" 141 | "

300 Multiple Choices

" 142 | ""; 143 | const char moved_permanently[] = 144 | "" 145 | "Moved Permanently" 146 | "

301 Moved Permanently

" 147 | ""; 148 | const char moved_temporarily[] = 149 | "" 150 | "Moved Temporarily" 151 | "

302 Moved Temporarily

" 152 | ""; 153 | const char not_modified[] = 154 | "" 155 | "Not Modified" 156 | "

304 Not Modified

" 157 | ""; 158 | const char bad_request[] = 159 | "" 160 | "Bad Request" 161 | "

400 Bad Request

" 162 | ""; 163 | const char unauthorized[] = 164 | "" 165 | "Unauthorized" 166 | "

401 Unauthorized

" 167 | ""; 168 | const char forbidden[] = 169 | "" 170 | "Forbidden" 171 | "

403 Forbidden

" 172 | ""; 173 | const char not_found[] = 174 | "" 175 | "Not Found" 176 | "

404 Not Found

" 177 | ""; 178 | const char internal_server_error[] = 179 | "" 180 | "Internal Server Error" 181 | "

500 Internal Server Error

" 182 | ""; 183 | const char not_implemented[] = 184 | "" 185 | "Not Implemented" 186 | "

501 Not Implemented

" 187 | ""; 188 | const char bad_gateway[] = 189 | "" 190 | "Bad Gateway" 191 | "

502 Bad Gateway

" 192 | ""; 193 | const char service_unavailable[] = 194 | "" 195 | "Service Unavailable" 196 | "

503 Service Unavailable

" 197 | ""; 198 | 199 | std::string to_string(reply::status_type status) 200 | { 201 | switch (status) 202 | { 203 | case reply::ok: 204 | return ok; 205 | case reply::created: 206 | return created; 207 | case reply::accepted: 208 | return accepted; 209 | case reply::no_content: 210 | return no_content; 211 | case reply::multiple_choices: 212 | return multiple_choices; 213 | case reply::moved_permanently: 214 | return moved_permanently; 215 | case reply::moved_temporarily: 216 | return moved_temporarily; 217 | case reply::not_modified: 218 | return not_modified; 219 | case reply::bad_request: 220 | return bad_request; 221 | case reply::unauthorized: 222 | return unauthorized; 223 | case reply::forbidden: 224 | return forbidden; 225 | case reply::not_found: 226 | return not_found; 227 | case reply::internal_server_error: 228 | return internal_server_error; 229 | case reply::not_implemented: 230 | return not_implemented; 231 | case reply::bad_gateway: 232 | return bad_gateway; 233 | case reply::service_unavailable: 234 | return service_unavailable; 235 | default: 236 | return internal_server_error; 237 | } 238 | } 239 | 240 | } // namespace stock_replies 241 | 242 | reply reply::stock_reply(reply::status_type status) 243 | { 244 | reply rep; 245 | rep.status = status; 246 | rep.content = stock_replies::to_string(status); 247 | rep.headers.resize(2); 248 | rep.headers[0].name = "Content-Length"; 249 | rep.headers[0].value = boost::lexical_cast(rep.content.size()); 250 | rep.headers[1].name = "Content-Type"; 251 | rep.headers[1].value = "text/html"; 252 | return rep; 253 | } 254 | 255 | } // ros_http_video_streamer 256 | -------------------------------------------------------------------------------- /src/ffmpeg_encoder.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (c) 2014, Willow Garage, Inc. 3 | * All rights reserved. 4 | * 5 | * Redistribution and use in source and binary forms, with or without 6 | * modification, are permitted provided that the following conditions are met: 7 | * 8 | * * Redistributions of source code must retain the above copyright 9 | * notice, this list of conditions and the following disclaimer. 10 | * * Redistributions in binary form must reproduce the above copyright 11 | * notice, this list of conditions and the following disclaimer in the 12 | * documentation and/or other materials provided with the distribution. 13 | * * Neither the name of the Willow Garage, Inc. nor the names of its 14 | * contributors may be used to endorse or promote products derived from 15 | * this software without specific prior written permission. 16 | * 17 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 18 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 19 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 20 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 21 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 22 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 23 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 24 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 25 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 26 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 27 | * POSSIBILITY OF SUCH DAMAGE. 28 | * 29 | * 30 | * ffmpeg_encoder.cpp 31 | * 32 | * Created on: Oct 30, 2012 33 | * Author: jkammerl 34 | */ 35 | 36 | #include "boost/date_time/posix_time/posix_time.hpp" 37 | 38 | #include 39 | 40 | #include "ffmpeg_encoder.h" 41 | #include "image_subscriber.h" 42 | 43 | #include "boost/date_time/posix_time/posix_time.hpp" //include all types plus i/o 44 | 45 | #define MAX_DEPTH 4.0 46 | #define RAW_DEPTH_IMAGE_RESOLUTION 512 47 | 48 | namespace enc = sensor_msgs::image_encodings; 49 | 50 | namespace ros_http_video_streamer 51 | { 52 | 53 | FFMPEGEncoder::FFMPEGEncoder(const std::string& refID, const std::string& topic, const ServerConfiguration& config) : 54 | doEncoding_(true), 55 | refID_(refID), 56 | topic_(topic), 57 | config_(config), 58 | subscriber_(topic, config.ros_transport_), 59 | frameID_(0), 60 | init_(false), 61 | ffmpeg_(0) 62 | { 63 | start(); 64 | } 65 | 66 | FFMPEGEncoder::~FFMPEGEncoder() 67 | { 68 | stop(); 69 | } 70 | 71 | void FFMPEGEncoder::start() 72 | { 73 | } 74 | 75 | void FFMPEGEncoder::stop() 76 | { 77 | 78 | if (doEncoding_) 79 | { 80 | doEncoding_ = false; 81 | 82 | if (ffmpeg_) 83 | { 84 | ffmpeg_->shutdown(); 85 | delete (ffmpeg_); 86 | ffmpeg_ = 0; 87 | } 88 | } 89 | 90 | } 91 | 92 | const std::string& FFMPEGEncoder::getRefID() 93 | { 94 | return refID_; 95 | } 96 | 97 | void FFMPEGEncoder::convertFloatingPointImageToMono8(float* input, const std::size_t width, const std::size_t height, 98 | std::vector& output) 99 | { 100 | std::size_t image_size, i; 101 | float* input_ptr; 102 | uint8_t* output_ptr; 103 | 104 | // prepare output vector 105 | image_size = width * height; 106 | output.resize(image_size); 107 | 108 | // Find min. and max. pixel value 109 | float minValue = std::numeric_limits::max(); 110 | float maxValue = std::numeric_limits::min(); 111 | input_ptr = input; 112 | output_ptr = &output[0]; 113 | bool valid_image = false; 114 | for (i = 0; i < image_size; ++i) 115 | { 116 | if (*input_ptr == *input_ptr) // check for NaN 117 | { 118 | minValue = std::min(minValue, *input_ptr); 119 | maxValue = std::max(maxValue, *input_ptr); 120 | valid_image = true; 121 | } 122 | input_ptr++; 123 | } 124 | 125 | // reset data pointer 126 | input_ptr = input; 127 | output_ptr = &output[0]; 128 | 129 | // Rescale floating point image and convert it to 8-bit 130 | float dynamic_range = maxValue - minValue; 131 | if (valid_image && (dynamic_range > 0.0f)) 132 | { 133 | // Rescale and quantize 134 | for (i = 0; i < image_size; ++i, ++input_ptr, ++output_ptr) 135 | { 136 | if (*input_ptr == *input_ptr) // check for NaN 137 | { 138 | *output_ptr = ((*input_ptr - minValue) / dynamic_range) * 255u; 139 | } 140 | else 141 | { 142 | *output_ptr = 0u; 143 | } 144 | } 145 | 146 | } 147 | else 148 | { 149 | // clear output buffer 150 | memset(output_ptr, 0, image_size * sizeof(uint8_t)); 151 | } 152 | } 153 | 154 | int FFMPEGEncoder::initEncoding(std::vector& header) 155 | { 156 | sensor_msgs::ImageConstPtr frame; 157 | 158 | boost::posix_time::ptime start = boost::posix_time::microsec_clock::local_time();; 159 | 160 | while (!init_ && (boost::posix_time::time_duration(boost::posix_time::microsec_clock::local_time()-start).total_seconds()<5.0)) 161 | { 162 | // get frame from ROS iamge subscriber 163 | subscriber_.getImageFromQueue(frame); 164 | 165 | if ((frame) && (!ffmpeg_)) 166 | { 167 | // ffmpeg wrapper has not been initialized yet 168 | ffmpeg_ = new FFMPEG_Wrapper(); 169 | 170 | // first input frame defines resolution 171 | if (ffmpeg_ && ffmpeg_->init(frame->width, frame->height, config_)>=0 ) 172 | { 173 | 174 | // retrieve header data from ffmpeg wrapper 175 | ffmpeg_->get_header(header); 176 | 177 | ROS_DEBUG("Codec header received: %d bytes", (int)header.size()); 178 | 179 | subscriber_.emptyQueue(); 180 | 181 | // FFMPEG initialized 182 | init_ = true; 183 | } 184 | 185 | } 186 | else 187 | { 188 | boost::this_thread::sleep(boost::posix_time::milliseconds(100)); 189 | } 190 | } 191 | 192 | return init_?0:-1; 193 | } 194 | 195 | void FFMPEGEncoder::getVideoPacket(std::vector& buf) 196 | { 197 | buf.clear(); 198 | 199 | if (!init_) 200 | { 201 | ROS_ERROR("Video encoding not initialized."); 202 | return; 203 | } 204 | 205 | while (buf.size() == 0) 206 | { 207 | // time stamps used to control the encoder rate 208 | unsigned int milisec_used; 209 | const unsigned int milisec_per_frame = 1000 / config_.framerate_; 210 | 211 | sensor_msgs::ImageConstPtr frame; 212 | 213 | // get frame from ROS iamge subscriber 214 | subscriber_.getImageFromQueue(frame); 215 | 216 | ROS_DEBUG("Encoding triggered.."); 217 | 218 | if (frame) 219 | { 220 | 221 | std::vector frame_buf_temp; 222 | 223 | bool valid_format = true; 224 | 225 | // Bit depth of image frame 226 | unsigned int num_channels = enc::numChannels(frame->encoding); 227 | switch (num_channels) 228 | { 229 | case 1: 230 | // monochrome 8-bit encoded frame 231 | if ((!frame->encoding.compare("mono8")) || (!frame->encoding.compare("8UC1"))) 232 | { 233 | ffmpeg_->encode_mono8_frame((uint8_t*)&frame->data[0], buf); 234 | } 235 | else if ((!frame->encoding.compare("mono16")) || (!frame->encoding.compare("16UC1"))) 236 | { 237 | // monochrome 16-bit encoded frame 238 | 239 | ffmpeg_->encode_mono16_frame((uint8_t*)&frame->data[0], buf); 240 | 241 | } 242 | else if (!frame->encoding.compare("32FC1")) 243 | { 244 | // floating-point encoded frame 245 | 246 | std::vector normalized_image; 247 | 248 | convertFloatingPointImageToMono8((float*)&frame->data[0], frame->width, frame->height, normalized_image); 249 | 250 | ffmpeg_->encode_mono8_frame(&normalized_image[0], buf); 251 | 252 | } 253 | else 254 | { 255 | valid_format = false; 256 | } 257 | break; 258 | case 3: 259 | if (frame->encoding.find("rgb") != std::string::npos) 260 | { 261 | // rgb encoded frame 262 | 263 | ffmpeg_->encode_rgb_frame((uint8_t*)&frame->data[0], buf); 264 | } 265 | else if (frame->encoding.find("bgr") != std::string::npos) 266 | { 267 | // bgr encoded frame 268 | 269 | ffmpeg_->encode_bgr_frame((uint8_t*)&frame->data[0], buf); 270 | } 271 | else 272 | { 273 | valid_format = false; 274 | } 275 | break; 276 | default: 277 | valid_format = false; 278 | break; 279 | } 280 | 281 | if (!valid_format) 282 | { 283 | ROS_ERROR("Invalid image format"); 284 | } 285 | 286 | } 287 | 288 | // calculate encoding time 289 | boost::posix_time::ptime now = boost::posix_time::microsec_clock::local_time(); 290 | boost::posix_time::time_duration diff = now - last_tick; 291 | last_tick = now; 292 | milisec_used = diff.total_milliseconds(); 293 | 294 | if (milisec_used < milisec_per_frame) 295 | { 296 | // if encoder worked faster than the desired frame rate -> go sleeping 297 | boost::this_thread::sleep(boost::posix_time::milliseconds(milisec_per_frame - milisec_used)); 298 | } 299 | } 300 | 301 | ROS_DEBUG("Frame received: %d bytes", (int)buf.size()); 302 | 303 | } 304 | 305 | } // ros_http_video_streamer 306 | -------------------------------------------------------------------------------- /src/ffmpeg_wrapper.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (c) 2014, Willow Garage, Inc. 3 | * All rights reserved. 4 | * 5 | * Redistribution and use in source and binary forms, with or without 6 | * modification, are permitted provided that the following conditions are met: 7 | * 8 | * * Redistributions of source code must retain the above copyright 9 | * notice, this list of conditions and the following disclaimer. 10 | * * Redistributions in binary form must reproduce the above copyright 11 | * notice, this list of conditions and the following disclaimer in the 12 | * documentation and/or other materials provided with the distribution. 13 | * * Neither the name of the Willow Garage, Inc. nor the names of its 14 | * contributors may be used to endorse or promote products derived from 15 | * this software without specific prior written permission. 16 | * 17 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 18 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 19 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 20 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 21 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 22 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 23 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 24 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 25 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 26 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 27 | * POSSIBILITY OF SUCH DAMAGE. 28 | * 29 | * 30 | * ffmpeg_wrapper.cpp 31 | * 32 | * Created on: Oct 30, 2012 33 | * Author: jkammerl 34 | */ 35 | 36 | #include 37 | #include 38 | #include 39 | 40 | #include 41 | 42 | #include "ffmpeg_wrapper.h" 43 | #include 44 | 45 | #ifdef HAVE_AV_CONFIG_H 46 | #undef HAVE_AV_CONFIG_H 47 | #endif 48 | 49 | #ifdef __cplusplus 50 | #define __STDC_CONSTANT_MACROS 51 | #ifdef _STDINT_H 52 | #undef _STDINT_H 53 | #endif 54 | # include 55 | #endif 56 | 57 | #define MILLISEC_FOR_FFMPEG_INIT (5*1000) 58 | 59 | // include ffmpeg C headers 60 | 61 | namespace ros_http_video_streamer 62 | { 63 | 64 | extern "C" 65 | { 66 | #include 67 | #include 68 | #include "libavutil/intreadwrite.h" 69 | #include "libavformat/avio.h" 70 | #include 71 | #include "libavutil/opt.h" 72 | } 73 | 74 | 75 | FFMPEG_Wrapper::FFMPEG_Wrapper() : 76 | ffmpeg_codec_(0), 77 | ffmpeg_output_format_(0), 78 | ffmpeg_codec_context_(0), 79 | ffmpeg_format_context_(0), 80 | ffmpeg_src_picture_(new AVPicture), 81 | ffmpeg_dst_picture_(new AVPicture), 82 | ffmpeg_video_st_(0), 83 | ffmpeg_frame_(0), 84 | ffmpeg_video_pts_(0.0), 85 | ffmpeg_sws_ctx_(0), 86 | config_(), 87 | input_width_(-1), 88 | input_height_(-1), 89 | output_width_(-1), 90 | output_height_(-1), 91 | init_(false) 92 | { 93 | } 94 | 95 | FFMPEG_Wrapper::~FFMPEG_Wrapper() 96 | { 97 | shutdown(); 98 | } 99 | 100 | static int ff_lockmgr(void **mutex, enum AVLockOp op) 101 | { 102 | if (NULL == mutex) 103 | return -1; 104 | 105 | switch (op) 106 | { 107 | case AV_LOCK_CREATE: 108 | { 109 | *mutex = NULL; 110 | boost::mutex * m = new boost::mutex(); 111 | *mutex = static_cast(m); 112 | break; 113 | } 114 | case AV_LOCK_OBTAIN: 115 | { 116 | boost::mutex * m = static_cast(*mutex); 117 | m->lock(); 118 | break; 119 | } 120 | case AV_LOCK_RELEASE: 121 | { 122 | boost::mutex * m = static_cast(*mutex); 123 | m->unlock(); 124 | break; 125 | } 126 | case AV_LOCK_DESTROY: 127 | { 128 | boost::mutex * m = static_cast(*mutex); 129 | m->lock(); 130 | m->unlock(); 131 | delete m; 132 | break; 133 | } 134 | default: 135 | break; 136 | } 137 | return 0; 138 | } 139 | 140 | 141 | 142 | int FFMPEG_Wrapper::init(int input_width, 143 | int input_height, 144 | const ServerConfiguration& config) 145 | { 146 | boost::mutex::scoped_lock lock(frame_mutex_); 147 | 148 | time_started_ = boost::posix_time::microsec_clock::local_time(); 149 | 150 | config_ = config; 151 | 152 | input_width_ = input_width; 153 | input_height_ = input_height; 154 | 155 | output_width_ = config.frame_width_; 156 | output_height_ = config.frame_height_; 157 | 158 | if (output_width_<0) 159 | output_width_ = input_width_; 160 | 161 | if (output_height_<0) 162 | output_height_ = input_height_; 163 | 164 | av_lockmgr_register(&ff_lockmgr); 165 | 166 | /* register all the codecs */ 167 | avcodec_register_all(); 168 | av_register_all(); 169 | 170 | // lookup webm codec 171 | avformat_alloc_output_context2(&ffmpeg_format_context_, NULL, config_.codec_.c_str(), NULL); 172 | if (!ffmpeg_format_context_) { 173 | return -1; 174 | } 175 | 176 | ffmpeg_output_format_ = ffmpeg_format_context_->oformat; 177 | 178 | /* Add the audio and video streams using the default format codecs 179 | * and initialize the codecs. */ 180 | ffmpeg_video_st_ = NULL; 181 | if (ffmpeg_output_format_->video_codec != AV_CODEC_ID_NONE) 182 | { 183 | 184 | /* find the video encoder */ 185 | ffmpeg_codec_ = avcodec_find_encoder(ffmpeg_output_format_->video_codec); 186 | if (!(ffmpeg_codec_)) 187 | { 188 | fprintf(stderr, "Codec not found (%s)\n",config_.codec_.c_str()); 189 | return -1; 190 | } 191 | 192 | ffmpeg_video_st_ = avformat_new_stream(ffmpeg_format_context_, ffmpeg_codec_); 193 | if (!ffmpeg_video_st_) 194 | { 195 | fprintf(stderr, "Could not alloc stream\n"); 196 | return -1; 197 | } 198 | 199 | ffmpeg_codec_context_ = ffmpeg_video_st_->codec; 200 | 201 | 202 | 203 | avcodec_get_context_defaults3(ffmpeg_codec_context_, ffmpeg_codec_); 204 | 205 | ////////////////////////////////////////////// 206 | // ffmpeg codec configuration 207 | ////////////////////////////////////////////// 208 | 209 | ffmpeg_codec_context_->codec_id = ffmpeg_output_format_->video_codec; 210 | ffmpeg_codec_context_->bit_rate = config_.bitrate_; 211 | 212 | ffmpeg_codec_context_->width = output_width_; 213 | ffmpeg_codec_context_->height = output_height_; 214 | ffmpeg_codec_context_->delay = 0; 215 | 216 | ffmpeg_codec_context_->time_base.den = config_.framerate_+3; //increased framerate to compensate playback delay 217 | ffmpeg_codec_context_->time_base.num = 1; 218 | ffmpeg_codec_context_->gop_size = config_.gop_; /* emit one intra ffmpeg_frame_ every twelve frames at most */ 219 | ffmpeg_codec_context_->pix_fmt = PIX_FMT_YUV420P; 220 | ffmpeg_codec_context_->max_b_frames = 0; 221 | 222 | av_opt_set(ffmpeg_codec_context_->priv_data, "quality", config_.profile_.c_str(), 0); 223 | 224 | av_opt_set(ffmpeg_codec_context_->priv_data, "deadline", "1", 0); 225 | av_opt_set(ffmpeg_codec_context_->priv_data, "auto-alt-ref", "0", 0); 226 | 227 | // lag in frames 228 | av_opt_set(ffmpeg_codec_context_->priv_data, "lag-in-frames", "1", 0); 229 | av_opt_set(ffmpeg_codec_context_->priv_data, "rc_lookahead", "1", 0); 230 | 231 | av_opt_set(ffmpeg_codec_context_->priv_data, "drop_frame", "1", 0); 232 | 233 | // enable error-resilient coding 234 | av_opt_set(ffmpeg_codec_context_->priv_data, "error-resilient", "1", 0); 235 | 236 | // buffer size of rate controller (length: rc_buffer_size/bitrate * 1000) ms 237 | int bufsize = 10;//ffmpeg_codec_context_->bit_rate/10; 238 | ffmpeg_codec_context_->rc_buffer_size = bufsize; 239 | // prebuffering at decoder 240 | ffmpeg_codec_context_->rc_initial_buffer_occupancy = bufsize ;//bitrate/3; 241 | 242 | av_opt_set_int(ffmpeg_codec_context_->priv_data, "bufsize", bufsize, 0); 243 | av_opt_set_int(ffmpeg_codec_context_->priv_data, "buf-initial", bufsize, 0); 244 | av_opt_set_int(ffmpeg_codec_context_->priv_data, "buf-optimal", bufsize, 0); 245 | 246 | // buffer agressivity 247 | ffmpeg_codec_context_->rc_buffer_aggressivity = 0.5; 248 | 249 | // Quality settings 250 | //ffmpeg_codec_context_->qmin = 50; 251 | //ffmpeg_codec_context_->qmax = 62; 252 | if (config_.quality_>0) 253 | ffmpeg_codec_context_->qmin = config_.quality_; 254 | 255 | //ffmpeg_codec_context_->frame_skip_threshold = 100; 256 | 257 | /* Some formats want stream headers to be separate. */ 258 | if (ffmpeg_format_context_->oformat->flags & AVFMT_GLOBALHEADER) 259 | ffmpeg_codec_context_->flags |= CODEC_FLAG_GLOBAL_HEADER; 260 | } 261 | 262 | if (ffmpeg_video_st_) 263 | { 264 | int ret; 265 | 266 | /* open the codec */ 267 | { 268 | boost::mutex::scoped_lock lock(codec_mutex_); 269 | if (avcodec_open2(ffmpeg_codec_context_, ffmpeg_codec_, NULL) < 0) { 270 | fprintf(stderr, "Could not open video codec\n"); 271 | return -1; 272 | } 273 | } 274 | 275 | /* allocate and init a re-usable ffmpeg_frame_ */ 276 | ffmpeg_frame_ = avcodec_alloc_frame(); 277 | if (!ffmpeg_frame_) { 278 | fprintf(stderr, "Could not allocate video ffmpeg_frame_\n"); 279 | return -1; 280 | } 281 | 282 | /* Allocate the encoded raw picture. */ 283 | ret = avpicture_alloc(ffmpeg_dst_picture_, ffmpeg_codec_context_->pix_fmt, output_width_, output_height_); 284 | if (ret < 0) { 285 | fprintf(stderr, "Could not allocate picture\n"); 286 | return -1; 287 | } 288 | 289 | /* If the output format is not YUV420P, then a temporary YUV420P 290 | * picture is needed too. It is then converted to the required 291 | * output format. */ 292 | ret = avpicture_alloc(ffmpeg_src_picture_, AV_PIX_FMT_RGB24, input_width_, input_height_); 293 | if (ret < 0) { 294 | fprintf(stderr, "Could not allocate temporary picture\n"); 295 | return -1; 296 | } 297 | 298 | /* copy data and linesize picture pointers to ffmpeg_frame_ */ 299 | *((AVPicture *)ffmpeg_frame_) = *ffmpeg_dst_picture_; 300 | 301 | av_dump_format(ffmpeg_format_context_, 0, "", 1); 302 | 303 | ffmpeg_output_format_->flags |= AVFMT_NOFILE; 304 | 305 | if (ffmpeg_frame_) 306 | ffmpeg_frame_->pts = 0; 307 | } 308 | 309 | init_ = true; 310 | 311 | return 0; 312 | } 313 | 314 | 315 | void FFMPEG_Wrapper::shutdown() 316 | { 317 | boost::mutex::scoped_lock lock(frame_mutex_); 318 | 319 | if (init_) 320 | { 321 | 322 | // give ffmpeg enough time to initialize before shutdown 323 | boost::posix_time::ptime now = boost::posix_time::microsec_clock::local_time(); 324 | boost::posix_time::time_duration diff = now - time_started_; 325 | unsigned int milisec_used = std::max(100u,(unsigned int)diff.total_milliseconds()); 326 | 327 | if (milisec_used < MILLISEC_FOR_FFMPEG_INIT) 328 | { 329 | // if encoder worked faster than the desired frame rate -> go sleeping 330 | boost::this_thread::sleep(boost::posix_time::milliseconds(MILLISEC_FOR_FFMPEG_INIT - milisec_used)); 331 | } 332 | 333 | 334 | // Close the codec 335 | if (ffmpeg_codec_context_) 336 | { 337 | boost::mutex::scoped_lock lock(codec_mutex_); 338 | avcodec_close(ffmpeg_codec_context_); 339 | } 340 | 341 | 342 | if (ffmpeg_frame_) 343 | avcodec_free_frame(&ffmpeg_frame_); 344 | 345 | if (ffmpeg_format_context_) 346 | { 347 | /* Free the streams. */ 348 | /* for (i = 0; i < ffmpeg_format_context_->nb_streams; i++) 349 | { 350 | avcodec_close(ffmpeg_format_context_->streams[i]->codec); 351 | av_freep(&ffmpeg_format_context_->streams[i]->metadata); 352 | av_freep(&ffmpeg_format_context_->streams[i]->codec->extradata); 353 | av_freep(&ffmpeg_format_context_->streams[i]->codec); 354 | av_freep(&ffmpeg_format_context_->streams[i]); 355 | 356 | }*/ 357 | 358 | avformat_free_context(ffmpeg_format_context_); 359 | } 360 | 361 | // av_free(ffmpeg_src_picture_->data[0]); 362 | if (ffmpeg_src_picture_) 363 | av_free(ffmpeg_src_picture_); 364 | // av_free(ffmpeg_dst_picture_->data[0]); 365 | if (ffmpeg_dst_picture_) 366 | av_free(ffmpeg_dst_picture_); 367 | 368 | if (ffmpeg_sws_ctx_) 369 | sws_freeContext(ffmpeg_sws_ctx_); 370 | 371 | init_ = false; 372 | 373 | } 374 | } 375 | 376 | void FFMPEG_Wrapper::encode_bgr_frame(uint8_t *bgr_data, std::vector& encoded_frame) 377 | { 378 | encode_frame(bgr_data, encoded_frame); 379 | } 380 | 381 | void FFMPEG_Wrapper::encode_rgb_frame(uint8_t *rgb_data, std::vector& encoded_frame) 382 | { 383 | encode_frame(rgb_data, encoded_frame); 384 | } 385 | 386 | void FFMPEG_Wrapper::encode_mono8_frame(uint8_t *gray8_data, std::vector& encoded_frame) 387 | { 388 | encode_frame(gray8_data, encoded_frame); 389 | } 390 | 391 | void FFMPEG_Wrapper::encode_mono16_frame(uint8_t *gray16_data, std::vector& encoded_frame) 392 | { 393 | encode_frame(gray16_data, encoded_frame); 394 | } 395 | 396 | template 397 | void FFMPEG_Wrapper::encode_frame(uint8_t *image_data, std::vector& encoded_frame) 398 | { 399 | 400 | boost::mutex::scoped_lock lock(frame_mutex_); 401 | 402 | avpicture_fill(ffmpeg_src_picture_, image_data, (AVPixelFormat)CODING_FORMAT, input_width_, input_height_); 403 | 404 | // get format conversion 405 | if (!ffmpeg_sws_ctx_) { 406 | static int sws_flags = SWS_BICUBIC; 407 | ffmpeg_sws_ctx_ = sws_getContext(input_width_, input_height_, (AVPixelFormat)CODING_FORMAT, 408 | output_width_, output_height_, ffmpeg_codec_context_->pix_fmt, 409 | sws_flags, NULL, NULL, NULL); 410 | if (!ffmpeg_sws_ctx_) { 411 | fprintf(stderr, 412 | "Could not initialize the conversion context\n"); 413 | return; 414 | } 415 | } 416 | 417 | sws_scale(ffmpeg_sws_ctx_, 418 | (const uint8_t * const *)ffmpeg_src_picture_->data, 419 | ffmpeg_src_picture_->linesize, 0, input_height_, ffmpeg_dst_picture_->data, ffmpeg_dst_picture_->linesize); 420 | 421 | /* encode the image */ 422 | AVPacket pkt; 423 | int got_output; 424 | 425 | av_init_packet(&pkt); 426 | pkt.data = NULL; // packet data will be allocated by the encoder 427 | pkt.size = 0; 428 | 429 | if (avcodec_encode_video2(ffmpeg_codec_context_, &pkt, ffmpeg_frame_, &got_output) < 0) 430 | { 431 | fprintf(stderr, "Error encoding video ffmpeg_frame_\n"); 432 | return; 433 | } 434 | 435 | /* If size is zero, it means the image was buffered. */ 436 | if (got_output) 437 | { 438 | std::size_t size; 439 | uint8_t* output_buf; 440 | 441 | if (ffmpeg_codec_context_->coded_frame->pts != AV_NOPTS_VALUE) 442 | pkt.pts = av_rescale_q(ffmpeg_codec_context_->coded_frame->pts, ffmpeg_codec_context_->time_base, ffmpeg_video_st_->time_base); 443 | 444 | pkt.pts= ffmpeg_codec_context_->coded_frame->pts; 445 | 446 | if (ffmpeg_codec_context_->coded_frame->key_frame) 447 | pkt.flags |= AV_PKT_FLAG_KEY; 448 | 449 | pkt.stream_index = ffmpeg_video_st_->index; 450 | 451 | if (avio_open_dyn_buf(&ffmpeg_format_context_->pb) >= 0) 452 | { 453 | ffmpeg_format_context_->pb->seekable = 0; 454 | 455 | if (av_write_frame(ffmpeg_format_context_, &pkt)) //av_write_frame 456 | { 457 | fprintf(stderr, "Error occurred when opening output file\n"); 458 | return; 459 | } 460 | 461 | size = avio_close_dyn_buf(ffmpeg_format_context_->pb, &output_buf); 462 | 463 | encoded_frame.resize(size); 464 | memcpy(&encoded_frame[0], output_buf, size); 465 | 466 | av_free(output_buf); 467 | } 468 | } 469 | else 470 | { 471 | encoded_frame.clear(); 472 | } 473 | 474 | av_free_packet(&pkt); 475 | 476 | AVRational timebase = ffmpeg_codec_context_->time_base; 477 | 478 | timebase.den += 2; //increased framerate to compensate playback delay 479 | 480 | //ffmpeg_frame_->pts++; 481 | ffmpeg_frame_->pts += av_rescale_q(1, timebase, ffmpeg_video_st_->time_base); 482 | } 483 | 484 | void FFMPEG_Wrapper::get_header(std::vector& header) 485 | { 486 | boost::mutex::scoped_lock lock(frame_mutex_); 487 | 488 | std::size_t size; 489 | uint8_t* output_buf; 490 | 491 | // define meta data 492 | av_dict_set(&ffmpeg_format_context_->metadata, "author" , "ROS topic http streamer" , 0); 493 | av_dict_set(&ffmpeg_format_context_->metadata, "comment" , "this is awesome" , 0); 494 | av_dict_set(&ffmpeg_format_context_->metadata, "copyright", "BSD", 0); 495 | av_dict_set(&ffmpeg_format_context_->metadata, "title" , "ROS Topic Stream" , 0); 496 | 497 | if (avio_open_dyn_buf(&ffmpeg_format_context_->pb) >= 0) 498 | { 499 | ffmpeg_format_context_->pb->seekable = 0; 500 | 501 | if (avformat_write_header(ffmpeg_format_context_, NULL) < 0) 502 | { 503 | fprintf(stderr, "Error occurred when opening output file\n"); 504 | return; 505 | } 506 | 507 | //av_dict_free(&ffmpeg_format_context_->metadata); 508 | 509 | size = avio_close_dyn_buf(ffmpeg_format_context_->pb, &output_buf); 510 | 511 | // copy header buffer to vector 512 | header.resize(size); 513 | memcpy(&header[0], output_buf, size); 514 | 515 | av_free(output_buf); 516 | } 517 | } 518 | 519 | void FFMPEG_Wrapper::get_trailer(std::vector& trailer) 520 | { 521 | std::size_t size; 522 | uint8_t* output_buf; 523 | 524 | boost::mutex::scoped_lock lock(frame_mutex_); 525 | 526 | if (avio_open_dyn_buf(&ffmpeg_format_context_->pb) >= 0) 527 | { 528 | ffmpeg_format_context_->pb->seekable = 0; 529 | 530 | if (av_write_trailer(ffmpeg_format_context_) < 0) 531 | { 532 | fprintf(stderr, "Error occurred when opening output file\n"); 533 | return; 534 | } 535 | 536 | size = avio_close_dyn_buf(ffmpeg_format_context_->pb, &output_buf); 537 | 538 | // copy header buffer to vector 539 | trailer.resize(size); 540 | memcpy(&trailer[0], output_buf, size); 541 | 542 | av_free(output_buf); 543 | } 544 | } 545 | 546 | } // ros_http_video_streamer 547 | -------------------------------------------------------------------------------- /src/connection.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (c) 2014, Willow Garage, Inc. 3 | * All rights reserved. 4 | * 5 | * Redistribution and use in source and binary forms, with or without 6 | * modification, are permitted provided that the following conditions are met: 7 | * 8 | * * Redistributions of source code must retain the above copyright 9 | * notice, this list of conditions and the following disclaimer. 10 | * * Redistributions in binary form must reproduce the above copyright 11 | * notice, this list of conditions and the following disclaimer in the 12 | * documentation and/or other materials provided with the distribution. 13 | * * Neither the name of the Willow Garage, Inc. nor the names of its 14 | * contributors may be used to endorse or promote products derived from 15 | * this software without specific prior written permission. 16 | * 17 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 18 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 19 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 20 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 21 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 22 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 23 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 24 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 25 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 26 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 27 | * POSSIBILITY OF SUCH DAMAGE. 28 | * 29 | * connection.cpp 30 | * 31 | * Created on: Oct 30, 2012 32 | * Author: jkammerl 33 | * 34 | * & partly: 35 | * Copyright (c) 2003-2011 Christopher M. Kohlhoff (chris at kohlhoff dot com) 36 | */ 37 | 38 | #include "connection.h" 39 | 40 | #include 41 | #include 42 | #include 43 | #include 44 | 45 | #include 46 | #include 47 | #include 48 | #include 49 | #include 50 | #include 51 | #include 52 | #include 53 | 54 | #include "ros/master.h" 55 | #include 56 | #include 57 | #include 58 | 59 | #define HTTP_TRANSFER_ENCODING 60 | 61 | namespace ros_http_video_streamer 62 | { 63 | 64 | namespace misc_strings { 65 | 66 | const char name_value_separator[] = { ':', ' ' }; 67 | const char crlf[] = { '\r', '\n' }; 68 | 69 | #ifdef HTTP_TRANSFER_ENCODING 70 | const std::string ok = 71 | "HTTP/1.1 200 OK\r\n"; 72 | 73 | } // namespace misc_strings 74 | #else 75 | const std::string ok = 76 | "HTTP/1.0 200 OK\r\n"; 77 | 78 | } // namespace misc_strings 79 | #endif 80 | 81 | struct mime_map 82 | { 83 | const char* extension; 84 | const char* mime_type; 85 | } mime_mapping[] = 86 | { 87 | { "gif", "image/gif" }, 88 | { "htm", "text/html" }, 89 | { "html", "text/html" }, 90 | { "jpg", "image/jpeg" }, 91 | { "png", "image/png" }, 92 | { "css", "text/css" }, 93 | { "js", "text/javascript" }, 94 | { 0, 0 } // Marks end of list. 95 | }; 96 | 97 | connection::connection(boost::asio::io_service& io_service, 98 | EncoderManager& encoder_manager, 99 | const ServerConfiguration& default_server_conf) 100 | : server_conf_(default_server_conf), 101 | image_topics_(), 102 | strand_(io_service), 103 | socket_(io_service), 104 | buffer_(), 105 | request_(), 106 | request_parser_(), 107 | reply_(), 108 | encoder_manager_(encoder_manager), 109 | streaming_thread_(), 110 | do_streaming_(false) 111 | { 112 | } 113 | 114 | connection::~connection() 115 | { 116 | do_streaming_ = false; 117 | 118 | if (streaming_thread_) 119 | streaming_thread_->join(); 120 | 121 | } 122 | 123 | // Create an asio buffer containing the contents of a c string 124 | // This method stores all type bytes of the string excluding the null terminator 125 | // Passing a c string to the buffer function creates a buffer that includs the null terminator 126 | static boost::asio::const_buffer create_cstr_asio_buffer(const char* c_str) 127 | { 128 | return boost::asio::buffer(c_str, strlen(c_str)); 129 | } 130 | 131 | // send http headers for data streaming 132 | void connection::sendHTTPStreamingHeaders() 133 | { 134 | std::vector buffers; 135 | 136 | buffers.push_back(boost::asio::buffer(misc_strings::ok)); 137 | 138 | buffers.push_back(boost::asio::buffer("Date")); 139 | buffers.push_back(boost::asio::buffer(misc_strings::name_value_separator)); 140 | 141 | std::ostringstream datetime_ss; 142 | boost::posix_time::time_facet * p_time_output = new boost::posix_time::time_facet; 143 | std::locale special_locale (std::locale(""), p_time_output); 144 | datetime_ss.imbue (special_locale); 145 | (*p_time_output).format("%a, %d %b %Y %H:%M:%S%F %z"); // date time 146 | datetime_ss << boost::posix_time::second_clock::local_time(); 147 | 148 | buffers.push_back(boost::asio::buffer(datetime_ss.str())); 149 | buffers.push_back(boost::asio::buffer(misc_strings::crlf)); 150 | 151 | buffers.push_back(create_cstr_asio_buffer("Content-Type")); 152 | buffers.push_back(boost::asio::buffer(misc_strings::name_value_separator)); 153 | buffers.push_back(create_cstr_asio_buffer("video/webm")); 154 | buffers.push_back(boost::asio::buffer(misc_strings::crlf)); 155 | 156 | 157 | buffers.push_back(create_cstr_asio_buffer("Cache-Control")); 158 | buffers.push_back(boost::asio::buffer(misc_strings::name_value_separator)); 159 | buffers.push_back(create_cstr_asio_buffer("no-cache")); 160 | buffers.push_back(boost::asio::buffer(misc_strings::crlf)); 161 | 162 | buffers.push_back(create_cstr_asio_buffer("Connection")); 163 | buffers.push_back(boost::asio::buffer(misc_strings::name_value_separator)); 164 | buffers.push_back(create_cstr_asio_buffer("Close")); 165 | buffers.push_back(boost::asio::buffer(misc_strings::crlf)); 166 | 167 | buffers.push_back(create_cstr_asio_buffer("Access-Control-Allow-Origin")); 168 | buffers.push_back(boost::asio::buffer(misc_strings::name_value_separator)); 169 | buffers.push_back(create_cstr_asio_buffer("*")); 170 | buffers.push_back(boost::asio::buffer(misc_strings::crlf)); 171 | 172 | buffers.push_back(create_cstr_asio_buffer("Pragma")); 173 | buffers.push_back(boost::asio::buffer(misc_strings::name_value_separator)); 174 | buffers.push_back(create_cstr_asio_buffer("no-cache")); 175 | buffers.push_back(boost::asio::buffer(misc_strings::crlf)); 176 | 177 | buffers.push_back(create_cstr_asio_buffer("Expires")); 178 | buffers.push_back(boost::asio::buffer(misc_strings::name_value_separator)); 179 | buffers.push_back(create_cstr_asio_buffer("0")); 180 | buffers.push_back(boost::asio::buffer(misc_strings::crlf)); 181 | 182 | buffers.push_back(create_cstr_asio_buffer("Max-Age")); 183 | buffers.push_back(boost::asio::buffer(misc_strings::name_value_separator)); 184 | buffers.push_back(create_cstr_asio_buffer("0")); 185 | buffers.push_back(boost::asio::buffer(misc_strings::crlf)); 186 | 187 | buffers.push_back(create_cstr_asio_buffer("Trailer")); 188 | buffers.push_back(boost::asio::buffer(misc_strings::name_value_separator)); 189 | buffers.push_back(create_cstr_asio_buffer("Expires")); 190 | buffers.push_back(boost::asio::buffer(misc_strings::crlf)); 191 | 192 | 193 | #ifdef HTTP_TRANSFER_ENCODING 194 | buffers.push_back(create_cstr_asio_buffer("Transfer-Encoding")); 195 | buffers.push_back(boost::asio::buffer(misc_strings::name_value_separator)); 196 | buffers.push_back(create_cstr_asio_buffer("chunked")); 197 | buffers.push_back(boost::asio::buffer(misc_strings::crlf)); 198 | #endif 199 | 200 | buffers.push_back(boost::asio::buffer(misc_strings::crlf)); 201 | 202 | boost::asio::write(socket_, buffers); 203 | } 204 | 205 | void connection::streamingWorkerThread( const std::string& topic, 206 | const ServerConfiguration& config) 207 | { 208 | FFMPEGEncoder image_encoder("WebEncoder", topic, config); 209 | 210 | #ifdef HTTP_TRANSFER_ENCODING 211 | char hexSize[256]; 212 | #endif 213 | 214 | std::vector header; 215 | 216 | if (image_encoder.initEncoding(header) >= 0) 217 | { 218 | 219 | std::vector buffers; 220 | sendHTTPStreamingHeaders(); 221 | 222 | #ifdef HTTP_TRANSFER_ENCODING 223 | sprintf(hexSize, "%X", (unsigned int)header.size()); 224 | buffers.push_back(create_cstr_asio_buffer(hexSize)); 225 | buffers.push_back(boost::asio::buffer(misc_strings::crlf)); 226 | #endif 227 | 228 | buffers.push_back(boost::asio::buffer(header)); 229 | #ifdef HTTP_TRANSFER_ENCODING 230 | buffers.push_back(boost::asio::buffer(misc_strings::crlf)); 231 | #endif 232 | 233 | try 234 | { 235 | boost::asio::write(socket_, buffers); 236 | ROS_DEBUG("Video header sent (%d bytes)", (int) header.size()); 237 | 238 | std::vector packet; 239 | 240 | while (do_streaming_) 241 | { 242 | buffers.clear(); 243 | packet.clear(); 244 | 245 | image_encoder.getVideoPacket(packet); 246 | ROS_DEBUG("Video packet sent (%d bytes)", (int) packet.size()); 247 | 248 | #ifdef HTTP_TRANSFER_ENCODING 249 | sprintf(hexSize, "%X", (unsigned int)packet.size()); 250 | buffers.push_back(create_cstr_asio_buffer(hexSize)); 251 | buffers.push_back(boost::asio::buffer(misc_strings::crlf)); 252 | #endif 253 | 254 | buffers.push_back(boost::asio::buffer(packet)); 255 | #ifdef HTTP_TRANSFER_ENCODING 256 | buffers.push_back(boost::asio::buffer(misc_strings::crlf)); 257 | #endif 258 | 259 | boost::asio::write(socket_, buffers); 260 | } 261 | } 262 | catch (const boost::system::system_error& err) 263 | { 264 | do_streaming_ = false; 265 | } 266 | 267 | } 268 | 269 | streaming_thread_.reset(); 270 | 271 | ROS_DEBUG("Video encoding thread endded"); 272 | } 273 | 274 | void connection::getImageTopics() 275 | { 276 | image_topics_.clear(); 277 | 278 | std::string image_message_type = ros::message_traits::datatype(); 279 | 280 | ros::master::V_TopicInfo topics; 281 | ros::master::getTopics( topics ); 282 | 283 | // Loop through all published topics 284 | ros::master::V_TopicInfo::iterator it; 285 | for( it = topics.begin(); it != topics.end(); ++it ) 286 | { 287 | const ros::master::TopicInfo& topic = *it; 288 | 289 | // Only add topics whose type matches. 290 | if ( ( topic.datatype == image_message_type ) && 291 | (topic.name.find("_raw")==std::string::npos ) ) 292 | { 293 | image_topics_.push_back(topic.name); 294 | } 295 | } 296 | } 297 | 298 | 299 | void connection::generateImageTopicHTML() 300 | { 301 | reply_.content = 302 | "" 303 | "ROS Image Topic List" 304 | "

Available ROS Image Topics:

"; 305 | 306 | BOOST_FOREACH( const std::string& topic_name, image_topics_ ) 307 | { 308 | reply_.content += "

"+topic_name+"

"; 311 | } 312 | reply_.content += 313 | // "WebGL-based pointcloud decoder" 314 | "" 315 | ""; 316 | 317 | reply_.status = reply::ok; 318 | reply_.headers.resize(2); 319 | reply_.headers[0].name = "Content-Length"; 320 | reply_.headers[0].value = boost::lexical_cast(reply_.content.size()); 321 | reply_.headers[1].name = "Content-Type"; 322 | reply_.headers[1].value = "text/html"; 323 | } 324 | 325 | void connection::generateVideoStreamHTML(const std::string& image_topic, 326 | const ServerConfiguration& config) 327 | { 328 | reply_.content = 329 | 330 | "" 331 | "" 332 | "" 333 | "" 334 | "ROS Topic: "; 335 | 336 | reply_.content += image_topic; 337 | 338 | reply_.content += 339 | "" 340 | "" 341 | "" 342 | "
" 343 | "

Video stream of ROS topic: "; 344 | 345 | reply_.content += image_topic; 346 | 347 | reply_.content += 348 | "

" 349 | "
" 350 | 351 | "
" 352 | "" 368 | "
" 369 | "
" 370 | "
" 371 | "" 372 | ""; 373 | 374 | reply_.status = reply::ok; 375 | reply_.headers.resize(2); 376 | reply_.headers[0].name = "Content-Length"; 377 | reply_.headers[0].value = boost::lexical_cast(reply_.content.size()); 378 | reply_.headers[1].name = "Content-Type"; 379 | reply_.headers[1].value = "text/html"; 380 | } 381 | 382 | void connection::getStreamingParametersFromURL(const std::string url, ServerConfiguration& config) 383 | { 384 | std::vector parameters; 385 | boost::split(parameters,url,boost::is_any_of("&")); 386 | BOOST_FOREACH( const std::string& p, parameters ) 387 | { 388 | std::vector setting; 389 | boost::split(setting,p,boost::is_any_of("=")); 390 | 391 | if (setting.size()==2) 392 | { 393 | try { 394 | if (!setting[0].compare("bitrate")) 395 | { 396 | config.bitrate_ = boost::lexical_cast( setting[1] ); 397 | } else 398 | if (!setting[0].compare("framerate")) 399 | { 400 | config.framerate_ = boost::lexical_cast( setting[1] ); 401 | } else 402 | if (!setting[0].compare("enc")) 403 | { 404 | config.codec_ = setting[1] ; 405 | } else 406 | if (!setting[0].compare("profile")) 407 | { 408 | config.profile_ = setting[1] ; 409 | } else 410 | if (!setting[0].compare("width")) 411 | { 412 | config.frame_width_ = boost::lexical_cast( setting[1] ); 413 | } 414 | else 415 | if (!setting[0].compare("height")) 416 | { 417 | config.frame_height_ = boost::lexical_cast( setting[1] ); 418 | } 419 | else 420 | if (!setting[0].compare("quality")) 421 | { 422 | config.quality_ = boost::lexical_cast( setting[1] ); 423 | } 424 | else 425 | if (!setting[0].compare("gop")) 426 | { 427 | config.gop_ = boost::lexical_cast( setting[1] ); 428 | } else 429 | { 430 | ROS_WARN_STREAM("Invalid configuration parameter in http request: "<extension; ++m) 458 | { 459 | if (m->extension == extension) 460 | { 461 | return m->mime_type; 462 | } 463 | } 464 | 465 | return "text/plain"; 466 | } 467 | 468 | void connection::handleRead(const boost::system::error_code& e, 469 | std::size_t bytes_transferred) 470 | { 471 | 472 | if (!e) 473 | { 474 | boost::tribool result; 475 | boost::tie(result, boost::tuples::ignore) = request_parser_.parse( 476 | request_, buffer_.data(), buffer_.data() + bytes_transferred); 477 | 478 | const std::string remote_ip = boost::lexical_cast(socket_.remote_endpoint()); 479 | 480 | if (result) 481 | { 482 | ROS_DEBUG("Http request received from %s: %s", remote_ip.c_str(), request_.uri.c_str()); 483 | 484 | std::string request_path; 485 | // update list of available image topics 486 | getImageTopics(); 487 | 488 | if (!urlDecode(request_.uri, request_path)) 489 | { 490 | reply_ = reply::stock_reply(reply::bad_request); 491 | } else 492 | if (request_path[request_path.size() - 1] == '/') 493 | { 494 | // generate a HTML page showing image topics 495 | generateImageTopicHTML(); 496 | } 497 | else if (!request_path.empty() && request_path.find(STREAM_PATH) != std::string::npos) 498 | { 499 | std::string request_topic = request_path.substr(strlen(STREAM_PATH)); 500 | 501 | std::string image_topic = request_topic.substr(0, request_topic.find(".webm")); 502 | std::string parameter_req = request_topic.substr(request_topic.find("?")+1); 503 | 504 | // check for requested stream 505 | bool stream_found = false; 506 | BOOST_FOREACH( const std::string& topic_name, image_topics_ ) 507 | { 508 | if (!image_topic.compare(topic_name)) 509 | stream_found = true; 510 | } 511 | 512 | if (stream_found) 513 | { 514 | ServerConfiguration config = server_conf_; 515 | 516 | // get stream parameters from URL 517 | getStreamingParametersFromURL(parameter_req, config); 518 | 519 | // start streaming thread 520 | do_streaming_ = true; 521 | streaming_thread_ = boost::shared_ptr( 522 | new boost::thread( boost::bind(&connection::streamingWorkerThread, shared_from_this(), image_topic, config ) ) ); 523 | 524 | ROS_INFO("Starting encoder for topic %s (codec: %s, bitrate: %d, framerate: %d)", 525 | image_topic.c_str(), 526 | config.codec_.c_str(), 527 | config.bitrate_, 528 | config.framerate_); 529 | 530 | return; 531 | } 532 | } 533 | else if (!request_path.empty() && request_path.find(WEB_PATH) != std::string::npos) 534 | { 535 | std::string request_topic = request_path.substr(strlen(WEB_PATH)); 536 | 537 | std::string image_topic = request_topic.substr(0, request_topic.find("?")); 538 | 539 | bool stream_found = false; 540 | BOOST_FOREACH( const std::string& topic_name, image_topics_ ) 541 | { 542 | if (!image_topic.compare(topic_name)) 543 | stream_found = true; 544 | } 545 | 546 | if (stream_found) 547 | { 548 | ROS_INFO("Requesting www for %s", image_topic.c_str()); 549 | 550 | // display HTML page that displays a video stream 551 | generateVideoStreamHTML(image_topic, server_conf_); 552 | 553 | } else 554 | { 555 | reply_ = reply::stock_reply(reply::not_found); 556 | } 557 | } else 558 | { 559 | 560 | if (server_conf_.www_file_server_) 561 | { // Determine the file extension. 562 | std::size_t last_slash_pos = request_path.find_last_of("/"); 563 | std::size_t last_dot_pos = request_path.find_last_of("."); 564 | std::string extension; 565 | if (last_dot_pos != std::string::npos && last_dot_pos > last_slash_pos) 566 | { 567 | extension = request_path.substr(last_dot_pos + 1); 568 | } 569 | 570 | // Open the file to send back. 571 | std::string full_path = server_conf_.wwwroot_ + request_path; 572 | std::ifstream is(full_path.c_str(), std::ios::in | std::ios::binary); 573 | if (!is) 574 | { 575 | reply_ = reply::stock_reply(reply::not_found); 576 | ROS_INFO("Http request from client %s: %s - file not found", remote_ip.c_str(), full_path.c_str()); 577 | return; 578 | } 579 | 580 | // Fill out the reply to be sent to the client. 581 | reply_.status = reply::ok; 582 | char buf[2048]; 583 | while (is.read(buf, sizeof(buf)).gcount() > 0) 584 | reply_.content.append(buf, is.gcount()); 585 | reply_.headers.resize(2); 586 | reply_.headers[0].name = "Content-Length"; 587 | reply_.headers[0].value = boost::lexical_cast < std::string > (reply_.content.size()); 588 | reply_.headers[1].name = "Content-Type"; 589 | reply_.headers[1].value = mimeExtensionToType(extension); 590 | } else 591 | { 592 | reply_ = reply::stock_reply(reply::forbidden); 593 | boost::asio::async_write(socket_, reply_.to_buffers(), 594 | strand_.wrap( 595 | boost::bind(&connection::handleWrite, shared_from_this(), 596 | boost::asio::placeholders::error))); 597 | } 598 | } 599 | 600 | // request_handler_.handle_request(request_path, reply_); 601 | boost::asio::async_write(socket_, reply_.to_buffers(), 602 | strand_.wrap( 603 | boost::bind(&connection::handleWrite, shared_from_this(), 604 | boost::asio::placeholders::error))); 605 | } 606 | else if (!result) 607 | { 608 | reply_ = reply::stock_reply(reply::bad_request); 609 | boost::asio::async_write(socket_, reply_.to_buffers(), 610 | strand_.wrap( 611 | boost::bind(&connection::handleWrite, shared_from_this(), 612 | boost::asio::placeholders::error))); 613 | } 614 | else 615 | { 616 | socket_.async_read_some(boost::asio::buffer(buffer_), 617 | strand_.wrap( 618 | boost::bind(&connection::handleRead, shared_from_this(), 619 | boost::asio::placeholders::error, 620 | boost::asio::placeholders::bytes_transferred))); 621 | } 622 | } else 623 | { 624 | ROS_INFO("Http read error: %s", e.message().c_str()); 625 | } 626 | 627 | // If an error occurs then no new asynchronous operations are started. This 628 | // means that all shared_ptr references to the connection object will 629 | // disappear and the object will be destroyed automatically after this 630 | // handler returns. The connection class's destructor closes the socket. 631 | } 632 | 633 | 634 | void connection::handleWrite(const boost::system::error_code& e) 635 | { 636 | if (!e) 637 | { 638 | // Initiate graceful connection closure. 639 | boost::system::error_code ignored_ec; 640 | socket_.shutdown(boost::asio::ip::tcp::socket::shutdown_both, ignored_ec); 641 | } 642 | 643 | // No new asynchronous operations are started. This means that all shared_ptr 644 | // references to the connection object will disappear and the object will be 645 | // destroyed automatically after this handler returns. The connection class's 646 | // destructor closes the socket. 647 | } 648 | 649 | bool connection::urlDecode(const std::string& in, std::string& out) 650 | { 651 | out.clear(); 652 | out.reserve(in.size()); 653 | for (std::size_t i = 0; i < in.size(); ++i) 654 | { 655 | if (in[i] == '%') 656 | { 657 | if (i + 3 <= in.size()) 658 | { 659 | int value = 0; 660 | std::istringstream is(in.substr(i + 1, 2)); 661 | if (is >> std::hex >> value) 662 | { 663 | out += static_cast(value); 664 | i += 2; 665 | } 666 | else 667 | { 668 | return false; 669 | } 670 | } 671 | else 672 | { 673 | return false; 674 | } 675 | } 676 | else if (in[i] == '+') 677 | { 678 | out += ' '; 679 | } 680 | else 681 | { 682 | out += in[i]; 683 | } 684 | } 685 | return true; 686 | } 687 | 688 | } // ros_http_video_streamer 689 | --------------------------------------------------------------------------------