connection.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2014, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  *
00029  * connection.cpp
00030  *
00031  *  Created on: Oct 30, 2012
00032  *      Author: jkammerl
00033  *
00034  *  & partly:
00035  *  Copyright (c) 2003-2011 Christopher M. Kohlhoff (chris at kohlhoff dot com)
00036  */
00037 
00038 #include "connection.h"
00039 
00040 #include <string>
00041 #include <vector>
00042 #include <fstream>
00043 #include <sstream>
00044 
00045 #include <boost/bind.hpp>
00046 #include <boost/foreach.hpp>
00047 #include <boost/lexical_cast.hpp>
00048 #include <boost/asio.hpp>
00049 #include <boost/any.hpp>
00050 #include <boost/algorithm/string.hpp>
00051 #include <boost/date_time/posix_time/posix_time.hpp>
00052 #include <boost/date_time/posix_time/posix_time_io.hpp>
00053 
00054 #include "ros/master.h"
00055 #include <sensor_msgs/image_encodings.h>
00056 #include <image_transport/image_transport.h>
00057 #include <image_transport/subscriber_filter.h>
00058 
00059 namespace ros_http_video_streamer
00060 {
00061 
00062 namespace misc_strings {
00063 
00064 const char name_value_separator[] = { ':', ' ' };
00065 const char crlf[] = { '\r', '\n' };
00066 
00067 #ifdef HTTP_TRANSFER_ENCODING
00068 const std::string ok =
00069   "HTTP/1.1 200 OK\r\n";
00070 
00071 } // namespace misc_strings
00072 #else
00073 const std::string ok =
00074   "HTTP/1.0 200 OK\r\n";
00075 
00076 } // namespace misc_strings
00077 #endif
00078 
00079 struct mime_map
00080 {
00081   const char* extension;
00082   const char* mime_type;
00083 } mime_mapping[] =
00084 {
00085   { "gif", "image/gif" },
00086   { "htm", "text/html" },
00087   { "html", "text/html" },
00088   { "jpg", "image/jpeg" },
00089   { "png", "image/png" },
00090   { "css", "text/css" },
00091   { "js", "text/javascript" },
00092   { 0, 0 } // Marks end of list.
00093 };
00094 
00095 connection::connection(boost::asio::io_service& io_service,
00096                        EncoderManager& encoder_manager,
00097                        const ServerConfiguration& default_server_conf)
00098   : server_conf_(default_server_conf),
00099     image_topics_(),
00100     strand_(io_service),
00101     socket_(io_service),
00102     buffer_(),
00103     request_(),
00104     request_parser_(),
00105     reply_(),
00106     encoder_manager_(encoder_manager),
00107     streaming_thread_(),
00108     do_streaming_(false)
00109 {
00110 }
00111 
00112 connection::~connection()
00113 {
00114   do_streaming_ = false;
00115 
00116   if (streaming_thread_)
00117     streaming_thread_->join();
00118 
00119 }
00120 
00121 // send http headers for data streaming
00122 void connection::sendHTTPStreamingHeaders()
00123 {
00124   std::vector<boost::asio::const_buffer> buffers;
00125 
00126   buffers.push_back(boost::asio::buffer(misc_strings::ok));
00127 
00128 #ifdef HTTP_HEADERS
00129 
00130   buffers.push_back(boost::asio::buffer("Date"));
00131   buffers.push_back(boost::asio::buffer(misc_strings::name_value_separator));
00132 
00133   std::ostringstream datetime_ss;
00134   boost::posix_time::time_facet * p_time_output = new boost::posix_time::time_facet;
00135   std::locale special_locale (std::locale(""), p_time_output);
00136   datetime_ss.imbue (special_locale);
00137   (*p_time_output).format("%a, %d %b %Y %H:%M:%S%F %z"); // date time
00138   datetime_ss << boost::posix_time::second_clock::local_time();
00139 
00140   buffers.push_back(boost::asio::buffer(datetime_ss.str().c_str()));
00141   buffers.push_back(boost::asio::buffer(misc_strings::crlf));
00142 
00143   buffers.push_back(boost::asio::buffer("Content-Type"));
00144   buffers.push_back(boost::asio::buffer(misc_strings::name_value_separator));
00145   buffers.push_back(boost::asio::buffer("video/webm"));
00146   buffers.push_back(boost::asio::buffer(misc_strings::crlf));
00147 
00148 
00149   buffers.push_back(boost::asio::buffer("Cache-Control"));
00150   buffers.push_back(boost::asio::buffer(misc_strings::name_value_separator));
00151   buffers.push_back(boost::asio::buffer("no-cache"));
00152   buffers.push_back(boost::asio::buffer(misc_strings::crlf));
00153 
00154   buffers.push_back(boost::asio::buffer("Connection"));
00155   buffers.push_back(boost::asio::buffer(misc_strings::name_value_separator));
00156   buffers.push_back(boost::asio::buffer("Close"));
00157   buffers.push_back(boost::asio::buffer(misc_strings::crlf));
00158 
00159   buffers.push_back(boost::asio::buffer("Access-Control-Allow-Origin"));
00160   buffers.push_back(boost::asio::buffer(misc_strings::name_value_separator));
00161   buffers.push_back(boost::asio::buffer("*"));
00162   buffers.push_back(boost::asio::buffer(misc_strings::crlf));
00163 
00164   buffers.push_back(boost::asio::buffer("Pragma"));
00165   buffers.push_back(boost::asio::buffer(misc_strings::name_value_separator));
00166   buffers.push_back(boost::asio::buffer("no-cache"));
00167   buffers.push_back(boost::asio::buffer(misc_strings::crlf));
00168 
00169   buffers.push_back(boost::asio::buffer("Expires"));
00170   buffers.push_back(boost::asio::buffer(misc_strings::name_value_separator));
00171   buffers.push_back(boost::asio::buffer("0"));
00172   buffers.push_back(boost::asio::buffer(misc_strings::crlf));
00173 
00174   buffers.push_back(boost::asio::buffer("Max-Age"));
00175   buffers.push_back(boost::asio::buffer(misc_strings::name_value_separator));
00176   buffers.push_back(boost::asio::buffer("0"));
00177   buffers.push_back(boost::asio::buffer(misc_strings::crlf));
00178 
00179   buffers.push_back(boost::asio::buffer("Trailer"));
00180   buffers.push_back(boost::asio::buffer(misc_strings::name_value_separator));
00181   buffers.push_back(boost::asio::buffer("Expires"));
00182   buffers.push_back(boost::asio::buffer(misc_strings::crlf));
00183 
00184 
00185   #ifdef HTTP_TRANSFER_ENCODING
00186     buffers.push_back(boost::asio::buffer("Transfer-Encoding"));
00187     buffers.push_back(boost::asio::buffer(misc_strings::name_value_separator));
00188     buffers.push_back(boost::asio::buffer("chunked"));
00189     buffers.push_back(boost::asio::buffer(misc_strings::crlf));
00190   #endif
00191 
00192 #endif
00193 
00194   buffers.push_back(boost::asio::buffer(misc_strings::crlf));
00195 
00196   boost::asio::write(socket_, buffers);
00197 }
00198 
00199 void connection::streamingWorkerThread( const std::string& topic,
00200                                         const ServerConfiguration& config)
00201 {
00202   FFMPEGEncoder image_encoder("WebEncoder", topic, config);
00203 
00204 #ifdef HTTP_TRANSFER_ENCODING
00205   char hexSize[256];
00206 #endif
00207 
00208    std::vector<uint8_t> header;
00209 
00210   if (image_encoder.initEncoding(header) >= 0)
00211   {
00212 
00213     std::vector<boost::asio::const_buffer> buffers;
00214     sendHTTPStreamingHeaders();
00215 
00216 #ifdef HTTP_TRANSFER_ENCODING
00217     sprintf(hexSize, "%X", (unsigned int)header.size());
00218     buffers.push_back(boost::asio::buffer(hexSize, strlen(hexSize)));
00219     buffers.push_back(boost::asio::buffer(misc_strings::crlf));
00220 #endif
00221 
00222     buffers.push_back(boost::asio::buffer(header));
00223 #ifdef HTTP_TRANSFER_ENCODING
00224     buffers.push_back(boost::asio::buffer(misc_strings::crlf));
00225 #endif
00226 
00227     try
00228     {
00229       boost::asio::write(socket_, buffers);
00230       ROS_DEBUG("Video header sent (%d bytes)", (int) header.size());
00231 
00232       std::vector<uint8_t> packet;
00233 
00234       while (do_streaming_)
00235       {
00236         buffers.clear();
00237         packet.clear();
00238 
00239         image_encoder.getVideoPacket(packet);
00240         ROS_DEBUG("Video packet sent (%d bytes)", (int) packet.size());
00241 
00242 #ifdef HTTP_TRANSFER_ENCODING
00243         sprintf(hexSize, "%X", (unsigned int)packet.size());
00244         buffers.push_back(boost::asio::buffer(hexSize, strlen(hexSize)));
00245         buffers.push_back(boost::asio::buffer(misc_strings::crlf));
00246 #endif
00247 
00248         buffers.push_back(boost::asio::buffer(packet));
00249 #ifdef HTTP_TRANSFER_ENCODING
00250         buffers.push_back(boost::asio::buffer(misc_strings::crlf));
00251 #endif
00252 
00253         boost::asio::write(socket_, buffers);
00254       }
00255     }
00256     catch (const boost::system::system_error& err)
00257     {
00258       do_streaming_ = false;
00259     }
00260 
00261   }
00262 
00263    streaming_thread_.reset();
00264 
00265    ROS_DEBUG("Video encoding thread endded");
00266 }
00267 
00268 void connection::getImageTopics()
00269 {
00270   image_topics_.clear();
00271 
00272   std::string image_message_type = ros::message_traits::datatype<sensor_msgs::Image>();
00273 
00274   ros::master::V_TopicInfo topics;
00275   ros::master::getTopics( topics );
00276 
00277   // Loop through all published topics
00278   ros::master::V_TopicInfo::iterator it;
00279   for( it = topics.begin(); it != topics.end(); ++it )
00280   {
00281     const ros::master::TopicInfo& topic = *it;
00282 
00283     // Only add topics whose type matches.
00284     if ( ( topic.datatype == image_message_type ) &&
00285           (topic.name.find("_raw")==std::string::npos ) )
00286     {
00287       image_topics_.push_back(topic.name);
00288     }
00289   }
00290 }
00291 
00292 
00293 void connection::generateImageTopicHTML()
00294 {
00295   reply_.content =
00296       "<html>"
00297       "<head><title>ROS Image Topic List</title></head>"
00298       "<body><h1>Available ROS Image Topics:</h1>";
00299 
00300   BOOST_FOREACH( const std::string& topic_name, image_topics_ )
00301   {
00302     reply_.content += "<p><a href=";
00303     reply_.content += WEB_PATH;
00304     reply_.content += topic_name+">"+topic_name+"</a></p>";
00305   }
00306   reply_.content +=
00307  //     "<a href=\"/webgl_pointcloud_streaming.html\">WebGL-based pointcloud decoder</a>"
00308       "</body>"
00309       "</html>";
00310 
00311   reply_.status = reply::ok;
00312   reply_.headers.resize(2);
00313   reply_.headers[0].name = "Content-Length";
00314   reply_.headers[0].value = boost::lexical_cast<std::string>(reply_.content.size());
00315   reply_.headers[1].name = "Content-Type";
00316   reply_.headers[1].value = "text/html";
00317 }
00318 
00319 void connection::generateVideoStreamHTML(const std::string& image_topic,
00320                                          const ServerConfiguration& config)
00321 {
00322   reply_.content =
00323 
00324       "<!DOCTYPE html>"
00325       "<html>"
00326       "<head>"
00327           "<meta charset=\"utf-8\">"
00328               "<title>ROS Topic: ";
00329 
00330   reply_.content += image_topic;
00331 
00332   reply_.content +=
00333                "</title>"
00334       "</head>"
00335       "<body>"
00336               "<div id=\"wrapper\">"
00337                               "<h1>Video stream of ROS topic: ";
00338 
00339   reply_.content += image_topic;
00340 
00341   reply_.content +=
00342                                "</h1>"
00343               "<div id=\"content\">"
00344 
00345                   "<div id=\"movie\">"
00346                           "<video src=\"";
00347 
00348   //reply_.content += server_conf_.address_+":"+boost::lexical_cast<std::string>(config.port_);
00349   reply_.content += STREAM_PATH;
00350   reply_.content += image_topic;
00351   reply_.content +=".webm?enc=";
00352   reply_.content +=config.codec_;
00353   reply_.content +="&bitrate=";
00354   reply_.content +=boost::lexical_cast<std::string>( config.bitrate_ );
00355   reply_.content +="&framerate=";
00356   reply_.content +=boost::lexical_cast<std::string>( config.framerate_ );
00357 
00358   reply_.content +=
00359 
00360                                       "\" autoplay=\"true\" preload=\"none\" >  "
00361                           "</video>"
00362                   "</div>"
00363               "</div>"
00364           "</div>"
00365       "</body>"
00366       "</html>";
00367 
00368   reply_.status = reply::ok;
00369   reply_.headers.resize(2);
00370   reply_.headers[0].name = "Content-Length";
00371   reply_.headers[0].value = boost::lexical_cast<std::string>(reply_.content.size());
00372   reply_.headers[1].name = "Content-Type";
00373   reply_.headers[1].value = "text/html";
00374 }
00375 
00376 void connection::getStreamingParametersFromURL(const std::string url, ServerConfiguration& config)
00377 {
00378   std::vector<std::string> parameters;
00379   boost::split(parameters,url,boost::is_any_of("&"));
00380   BOOST_FOREACH( const std::string& p, parameters )
00381   {
00382     std::vector<std::string> setting;
00383     boost::split(setting,p,boost::is_any_of("="));
00384 
00385     if (setting.size()==2)
00386     {
00387       try {
00388         if (!setting[0].compare("bitrate"))
00389         {
00390           config.bitrate_ = boost::lexical_cast<int>( setting[1] );
00391         } else
00392         if (!setting[0].compare("framerate"))
00393         {
00394           config.framerate_ = boost::lexical_cast<int>( setting[1] );
00395         } else
00396         if (!setting[0].compare("enc"))
00397         {
00398           config.codec_ = setting[1] ;
00399         } else
00400         if (!setting[0].compare("profile"))
00401         {
00402           config.profile_ = setting[1] ;
00403         } else
00404         if (!setting[0].compare("width"))
00405         {
00406           config.frame_width_ = boost::lexical_cast<int>( setting[1] );
00407         }
00408         else
00409         if (!setting[0].compare("height"))
00410         {
00411           config.frame_height_ = boost::lexical_cast<int>( setting[1] );
00412         }
00413         else
00414         if (!setting[0].compare("quality"))
00415         {
00416           config.quality_ = boost::lexical_cast<int>( setting[1] );
00417         }
00418         else
00419         if (!setting[0].compare("gop"))
00420         {
00421           config.gop_ = boost::lexical_cast<int>( setting[1] );
00422         } else
00423         {
00424           ROS_WARN_STREAM("Invalid configuration parameter in http request: "<<setting[1]);
00425         }
00426       } catch (boost::bad_lexical_cast& e)  {}
00427     }
00428   }
00429 
00430 }
00431 
00432 
00433 boost::asio::ip::tcp::socket& connection::socket()
00434 {
00435   return socket_;
00436 }
00437 
00438 void connection::start()
00439 {
00440 
00441   socket_.async_read_some(boost::asio::buffer(buffer_),
00442       strand_.wrap(
00443         boost::bind(&connection::handleRead, shared_from_this(),
00444           boost::asio::placeholders::error,
00445           boost::asio::placeholders::bytes_transferred)));
00446 
00447 }
00448 
00449 std::string connection::mimeExtensionToType(const std::string& extension)
00450 {
00451   for (mime_map* m = mime_mapping; m->extension; ++m)
00452   {
00453     if (m->extension == extension)
00454     {
00455       return m->mime_type;
00456     }
00457   }
00458 
00459   return "text/plain";
00460 }
00461 
00462 void connection::handleRead(const boost::system::error_code& e,
00463     std::size_t bytes_transferred)
00464 {
00465 
00466   if (!e)
00467   {
00468     boost::tribool result;
00469     boost::tie(result, boost::tuples::ignore) = request_parser_.parse(
00470         request_, buffer_.data(), buffer_.data() + bytes_transferred);
00471         
00472     const std::string remote_ip = boost::lexical_cast<std::string>(socket_.remote_endpoint());
00473 
00474     if (result)
00475     {
00476       ROS_DEBUG("Http request received from %s: %s", remote_ip.c_str(), request_.uri.c_str());
00477 
00478       std::string request_path;
00479       // update list of available image topics
00480       getImageTopics();
00481 
00482       if (!urlDecode(request_.uri, request_path))
00483       {
00484         reply_ = reply::stock_reply(reply::bad_request);
00485       } else
00486       if (request_path[request_path.size() - 1] == '/')
00487       {
00488         // generate a HTML page showing image topics
00489         generateImageTopicHTML();
00490       }
00491       else if (!request_path.empty() && request_path.find(STREAM_PATH) != std::string::npos)
00492       {
00493         std::string request_topic = request_path.substr(strlen(STREAM_PATH));
00494 
00495         std::string image_topic = request_topic.substr(0, request_topic.find(".webm"));
00496         std::string parameter_req = request_topic.substr(request_topic.find("?")+1);
00497 
00498         // check for requested stream
00499         bool stream_found = false;
00500         BOOST_FOREACH( const std::string& topic_name, image_topics_ )
00501         {
00502           if (!image_topic.compare(topic_name))
00503             stream_found = true;
00504         }
00505 
00506         if (stream_found)
00507         {
00508           ServerConfiguration config = server_conf_;
00509 
00510           // get stream parameters from URL
00511           getStreamingParametersFromURL(parameter_req, config);
00512 
00513           // start streaming thread
00514           do_streaming_ = true;
00515           streaming_thread_ = boost::shared_ptr<boost::thread>(
00516               new boost::thread( boost::bind(&connection::streamingWorkerThread, shared_from_this(), image_topic, config )  ) );
00517 
00518           ROS_INFO("Starting encoder for topic %s (codec: %s, bitrate: %d, framerate: %d)",
00519                    image_topic.c_str(),
00520                    config.codec_.c_str(),
00521                    config.bitrate_,
00522                    config.framerate_);
00523 
00524           return;
00525         }
00526       }
00527       else if (!request_path.empty() && request_path.find(WEB_PATH) != std::string::npos)
00528       {
00529         std::string request_topic = request_path.substr(strlen(WEB_PATH));
00530 
00531         std::string image_topic = request_topic.substr(0, request_topic.find("?"));
00532 
00533         bool stream_found = false;
00534         BOOST_FOREACH( const std::string& topic_name, image_topics_ )
00535         {
00536           if (!image_topic.compare(topic_name))
00537             stream_found = true;
00538         }
00539 
00540         if (stream_found)
00541         {
00542           ROS_INFO("Requesting www for %s", image_topic.c_str());
00543 
00544           // display HTML page that displays a video stream
00545           generateVideoStreamHTML(image_topic, server_conf_);
00546 
00547         } else
00548         {
00549           reply_ = reply::stock_reply(reply::not_found);
00550         }
00551       } else
00552       {
00553 
00554         if (server_conf_.www_file_server_)
00555         {        // Determine the file extension.
00556           std::size_t last_slash_pos = request_path.find_last_of("/");
00557           std::size_t last_dot_pos = request_path.find_last_of(".");
00558           std::string extension;
00559           if (last_dot_pos != std::string::npos && last_dot_pos > last_slash_pos)
00560           {
00561             extension = request_path.substr(last_dot_pos + 1);
00562           }
00563 
00564           // Open the file to send back.
00565           std::string full_path = server_conf_.wwwroot_ + request_path;
00566           std::ifstream is(full_path.c_str(), std::ios::in | std::ios::binary);
00567           if (!is)
00568           {
00569             reply_ = reply::stock_reply(reply::not_found);
00570             ROS_INFO("Http request from client %s: %s - file not found ", remote_ip.c_str(), request_.uri.c_str(), full_path.c_str());
00571             return;
00572           }
00573 
00574           // Fill out the reply to be sent to the client.
00575           reply_.status = reply::ok;
00576           char buf[2048];
00577           while (is.read(buf, sizeof(buf)).gcount() > 0)
00578             reply_.content.append(buf, is.gcount());
00579           reply_.headers.resize(2);
00580           reply_.headers[0].name = "Content-Length";
00581           reply_.headers[0].value = boost::lexical_cast < std::string > (reply_.content.size());
00582           reply_.headers[1].name = "Content-Type";
00583           reply_.headers[1].value = mimeExtensionToType(extension);
00584         } else
00585         {
00586           reply_ = reply::stock_reply(reply::forbidden);
00587           boost::asio::async_write(socket_, reply_.to_buffers(),
00588               strand_.wrap(
00589                 boost::bind(&connection::handleWrite, shared_from_this(),
00590                   boost::asio::placeholders::error)));
00591         }
00592       }
00593 
00594   //    request_handler_.handle_request(request_path, reply_);
00595       boost::asio::async_write(socket_, reply_.to_buffers(),
00596           strand_.wrap(
00597             boost::bind(&connection::handleWrite, shared_from_this(),
00598               boost::asio::placeholders::error)));
00599     }
00600     else if (!result)
00601     {
00602       reply_ = reply::stock_reply(reply::bad_request);
00603       boost::asio::async_write(socket_, reply_.to_buffers(),
00604           strand_.wrap(
00605             boost::bind(&connection::handleWrite, shared_from_this(),
00606               boost::asio::placeholders::error)));
00607     }
00608     else
00609     {
00610       socket_.async_read_some(boost::asio::buffer(buffer_),
00611           strand_.wrap(
00612             boost::bind(&connection::handleRead, shared_from_this(),
00613               boost::asio::placeholders::error,
00614               boost::asio::placeholders::bytes_transferred)));
00615     }
00616   } else
00617   {
00618     ROS_INFO("Http read error: %s", e.message().c_str());
00619   }
00620 
00621   // If an error occurs then no new asynchronous operations are started. This
00622   // means that all shared_ptr references to the connection object will
00623   // disappear and the object will be destroyed automatically after this
00624   // handler returns. The connection class's destructor closes the socket.
00625 }
00626 
00627 
00628 void connection::handleWrite(const boost::system::error_code& e)
00629 {
00630   if (!e)
00631   {
00632     // Initiate graceful connection closure.
00633     boost::system::error_code ignored_ec;
00634     socket_.shutdown(boost::asio::ip::tcp::socket::shutdown_both, ignored_ec);
00635   }
00636 
00637   // No new asynchronous operations are started. This means that all shared_ptr
00638   // references to the connection object will disappear and the object will be
00639   // destroyed automatically after this handler returns. The connection class's
00640   // destructor closes the socket.
00641 }
00642 
00643 bool connection::urlDecode(const std::string& in, std::string& out)
00644 {
00645   out.clear();
00646   out.reserve(in.size());
00647   for (std::size_t i = 0; i < in.size(); ++i)
00648   {
00649     if (in[i] == '%')
00650     {
00651       if (i + 3 <= in.size())
00652       {
00653         int value = 0;
00654         std::istringstream is(in.substr(i + 1, 2));
00655         if (is >> std::hex >> value)
00656         {
00657           out += static_cast<char>(value);
00658           i += 2;
00659         }
00660         else
00661         {
00662           return false;
00663         }
00664       }
00665       else
00666       {
00667         return false;
00668       }
00669     }
00670     else if (in[i] == '+')
00671     {
00672       out += ' ';
00673     }
00674     else
00675     {
00676       out += in[i];
00677     }
00678   }
00679   return true;
00680 }
00681 
00682 } // ros_http_video_streamer


ros_web_video
Author(s): Julius Kammer
autogenerated on Mon Oct 6 2014 06:57:43