@@ -15,9 +15,10 @@ void MultipartStream::sendInitialHeader() {
15
15
async_web_server_cpp::HttpReply::builder (async_web_server_cpp::HttpReply::ok).header (" Connection" , " close" ).header (
16
16
" Server" , " web_video_server" ).header (" Cache-Control" ,
17
17
" no-cache, no-store, must-revalidate, pre-check=0, post-check=0, max-age=0" ).header (
18
- " Pragma" , " no-cache" ).header (" Content-type" , " multipart/x-mixed-replace;boundary=" +boundry_).header (
19
- " Access-Control-Allow-Origin" , " *" ).header (" Access-Control-Allow-Methods" , " GET,POST,PUT,DELETE,HEAD,OPTIONS" ).header (
20
- " Access-Control-Allow-Headers" , " Origin, Authorization, Accept, Content-Type" ).header (" Access-Control-Max-Age" , " 3600" ).write (connection_);
18
+ " Pragma" , " no-cache" ).header (" Content-type" , " multipart/x-mixed-replace;boundary=" +boundry_)
19
+ .header (" Access-Control-Allow-Origin" , " *" ).header (" Access-Control-Allow-Methods" , " GET,POST,PUT,DELETE,HEAD,OPTIONS" )
20
+ .header (" Access-Control-Allow-Headers" , " Origin, Authorization, Accept, Content-Type" )
21
+ .header (" Access-Control-Max-Age" , " 3600" ).write (connection_);
21
22
connection_->write (" --" +boundry_+" \r\n " );
22
23
}
23
24
@@ -40,7 +41,7 @@ void MultipartStream::sendPartHeader(const ros::Time &time, const std::string& t
40
41
void MultipartStream::sendPartFooter (const ros::Time &time) {
41
42
boost::shared_ptr<std::string> str (new std::string (" \r\n --" +boundry_+" \r\n " ));
42
43
PendingFooter pf;
43
- pf.timestamp = time ;
44
+ pf.timestamp = ros::WallTime::now () ;
44
45
pf.contents = str;
45
46
connection_->write (boost::asio::buffer (*str), str);
46
47
if (max_queue_size_ > 0 ) pending_footers_.push (pf);
@@ -68,13 +69,13 @@ void MultipartStream::sendPart(const ros::Time &time, const std::string& type,
68
69
}
69
70
70
71
bool MultipartStream::isBusy () {
71
- ros::Time currentTime = ros::Time ::now ();
72
+ auto currentTime = ros::WallTime ::now ();
72
73
while (!pending_footers_.empty ())
73
74
{
74
75
if (pending_footers_.front ().contents .expired ()) {
75
76
pending_footers_.pop ();
76
77
} else {
77
- ros::Time footerTime = pending_footers_.front ().timestamp ;
78
+ auto footerTime = pending_footers_.front ().timestamp ;
78
79
if ((currentTime - footerTime).toSec () > 0.5 ) {
79
80
pending_footers_.pop ();
80
81
} else {
0 commit comments