@@ -37,13 +37,10 @@ void MultipartStream::sendPartHeader(const ros::Time &time, const std::string& t
3737 connection_->write (async_web_server_cpp::HttpReply::to_buffers (*headers), headers);
3838}
3939
40- void MultipartStream::sendPartFooter (const ros::Time &time ) {
40+ void MultipartStream::sendPartFooter () {
4141 boost::shared_ptr<std::string> str (new std::string (" \r\n --" +boundry_+" \r\n " ));
42- PendingFooter pf;
43- pf.timestamp = time;
44- pf.contents = str;
4542 connection_->write (boost::asio::buffer (*str), str);
46- if (max_queue_size_ > 0 ) pending_footers_.push (pf );
43+ if (max_queue_size_ > 0 ) pending_footers_.push (str );
4744}
4845
4946void MultipartStream::sendPartAndClear (const ros::Time &time, const std::string& type,
@@ -52,7 +49,7 @@ void MultipartStream::sendPartAndClear(const ros::Time &time, const std::string&
5249 {
5350 sendPartHeader (time, type, data.size ());
5451 connection_->write_and_clear (data);
55- sendPartFooter (time );
52+ sendPartFooter ();
5653 }
5754}
5855
@@ -63,24 +60,14 @@ void MultipartStream::sendPart(const ros::Time &time, const std::string& type,
6360 {
6461 sendPartHeader (time, type, boost::asio::buffer_size (buffer));
6562 connection_->write (buffer, resource);
66- sendPartFooter (time );
63+ sendPartFooter ();
6764 }
6865}
6966
7067bool MultipartStream::isBusy () {
71- ros::Time currentTime = ros::Time::now ();
72- while (!pending_footers_.empty ())
68+ while (!pending_footers_.empty () && pending_footers_.front ().expired ())
7369 {
74- if (pending_footers_.front ().contents .expired ()) {
75- pending_footers_.pop ();
76- } else {
77- ros::Time footerTime = pending_footers_.front ().timestamp ;
78- if ((currentTime - footerTime).toSec () > 0.5 ) {
79- pending_footers_.pop ();
80- } else {
81- break ;
82- }
83- }
70+ pending_footers_.pop ();
8471 }
8572 return !(max_queue_size_ == 0 || pending_footers_.size () < max_queue_size_);
8673}
0 commit comments