multipart_stream.cpp
Go to the documentation of this file.
00001 #include "web_video_server/multipart_stream.h"
00002 #include "async_web_server_cpp/http_reply.hpp"
00003 
00004 namespace web_video_server
00005 {
00006 
00007 MultipartStream::MultipartStream(
00008     async_web_server_cpp::HttpConnectionPtr& connection,
00009     const std::string& boundry,
00010     std::size_t max_queue_size)
00011   : connection_(connection), boundry_(boundry), max_queue_size_(max_queue_size)
00012 {}
00013 
00014 void MultipartStream::sendInitialHeader() {
00015   async_web_server_cpp::HttpReply::builder(async_web_server_cpp::HttpReply::ok).header("Connection", "close").header(
00016       "Server", "web_video_server").header("Cache-Control",
00017                                            "no-cache, no-store, must-revalidate, pre-check=0, post-check=0, max-age=0").header(
00018       "Pragma", "no-cache").header("Content-type", "multipart/x-mixed-replace;boundary="+boundry_).header(
00019       "Access-Control-Allow-Origin", "*").write(connection_);
00020   connection_->write("--"+boundry_+"\r\n");
00021 }
00022 
00023 void MultipartStream::sendPartHeader(const ros::Time &time, const std::string& type, size_t payload_size) {
00024   char stamp[20];
00025   sprintf(stamp, "%.06lf", time.toSec());
00026   boost::shared_ptr<std::vector<async_web_server_cpp::HttpHeader> > headers(
00027       new std::vector<async_web_server_cpp::HttpHeader>());
00028   headers->push_back(async_web_server_cpp::HttpHeader("Content-type", type));
00029   headers->push_back(async_web_server_cpp::HttpHeader("X-Timestamp", stamp));
00030   headers->push_back(
00031       async_web_server_cpp::HttpHeader("Content-Length", boost::lexical_cast<std::string>(payload_size)));
00032   connection_->write(async_web_server_cpp::HttpReply::to_buffers(*headers), headers);
00033 }
00034 
00035 void MultipartStream::sendPartFooter(const ros::Time &time) {
00036   boost::shared_ptr<std::string> str(new std::string("\r\n--"+boundry_+"\r\n"));
00037   PendingFooter pf;
00038   pf.timestamp = time;
00039   pf.contents = str;
00040   connection_->write(boost::asio::buffer(*str), str);
00041   if (max_queue_size_ > 0) pending_footers_.push(pf);
00042 }
00043 
00044 void MultipartStream::sendPartAndClear(const ros::Time &time, const std::string& type,
00045                                        std::vector<unsigned char> &data) {
00046   if (!isBusy())
00047   {
00048     sendPartHeader(time, type, data.size());
00049     connection_->write_and_clear(data);
00050     sendPartFooter(time);
00051   }
00052 }
00053 
00054 void MultipartStream::sendPart(const ros::Time &time, const std::string& type,
00055                                const boost::asio::const_buffer &buffer,
00056                                async_web_server_cpp::HttpConnection::ResourcePtr resource) {
00057   if (!isBusy())
00058   {
00059     sendPartHeader(time, type, boost::asio::buffer_size(buffer));
00060     connection_->write(buffer, resource);
00061     sendPartFooter(time);
00062   }
00063 }
00064 
00065 bool MultipartStream::isBusy() {
00066   ros::Time currentTime = ros::Time::now();
00067   while (!pending_footers_.empty())
00068   {
00069     if (pending_footers_.front().contents.expired()) {
00070       pending_footers_.pop();
00071     } else {
00072       ros::Time footerTime = pending_footers_.front().timestamp;
00073       if ((currentTime - footerTime).toSec() > 0.5) {
00074         pending_footers_.pop();
00075       } else {
00076         break;
00077       }
00078     }
00079   }
00080   return !(max_queue_size_ == 0 || pending_footers_.size() < max_queue_size_);
00081 }
00082 
00083 }


web_video_server
Author(s): Mitchell Wills
autogenerated on Thu Jun 6 2019 18:02:48