@@ -32,10 +32,13 @@ void MultipartStream::sendPartHeader(const ros::Time &time, const std::string& t
32
32
connection_->write (async_web_server_cpp::HttpReply::to_buffers (*headers), headers);
33
33
}
34
34
35
- void MultipartStream::sendPartFooter () {
35
+ void MultipartStream::sendPartFooter (const ros::Time &time ) {
36
36
boost::shared_ptr<std::string> str (new std::string (" \r\n --" +boundry_+" \r\n " ));
37
+ PendingFooter pf;
38
+ pf.timestamp = time;
39
+ pf.contents = str;
37
40
connection_->write (boost::asio::buffer (*str), str);
38
- if (max_queue_size_ > 0 ) pending_footers_.push (str );
41
+ if (max_queue_size_ > 0 ) pending_footers_.push (pf );
39
42
}
40
43
41
44
void MultipartStream::sendPartAndClear (const ros::Time &time, const std::string& type,
@@ -44,7 +47,7 @@ void MultipartStream::sendPartAndClear(const ros::Time &time, const std::string&
44
47
{
45
48
sendPartHeader (time, type, data.size ());
46
49
connection_->write_and_clear (data);
47
- sendPartFooter ();
50
+ sendPartFooter (time );
48
51
}
49
52
}
50
53
@@ -55,14 +58,24 @@ void MultipartStream::sendPart(const ros::Time &time, const std::string& type,
55
58
{
56
59
sendPartHeader (time, type, boost::asio::buffer_size (buffer));
57
60
connection_->write (buffer, resource);
58
- sendPartFooter ();
61
+ sendPartFooter (time );
59
62
}
60
63
}
61
64
62
65
bool MultipartStream::isBusy () {
63
- while (!pending_footers_.empty () && pending_footers_.front ().expired ())
66
+ ros::Time currentTime = ros::Time::now ();
67
+ while (!pending_footers_.empty ())
64
68
{
65
- pending_footers_.pop ();
69
+ if (pending_footers_.front ().contents .expired ()) {
70
+ pending_footers_.pop ();
71
+ } else {
72
+ ros::Time footerTime = pending_footers_.front ().timestamp ;
73
+ if ((currentTime - footerTime).toSec () > 0.5 ) {
74
+ pending_footers_.pop ();
75
+ } else {
76
+ break ;
77
+ }
78
+ }
66
79
}
67
80
return !(max_queue_size_ == 0 || pending_footers_.size () < max_queue_size_);
68
81
}
0 commit comments