Skip to content

Commit 5b7b0a8

Browse files
committed
Revert "Add a workaround for MultipartStream constant busy state (RobotWebTools#83)"
This reverts commit c3d08d4.
1 parent c33cab3 commit 5b7b0a8

File tree

2 files changed

+8
-26
lines changed

2 files changed

+8
-26
lines changed

include/web_video_server/multipart_stream.h

Lines changed: 2 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -9,11 +9,6 @@
99
namespace web_video_server
1010
{
1111

12-
struct PendingFooter {
13-
ros::Time timestamp;
14-
boost::weak_ptr<std::string> contents;
15-
};
16-
1712
class MultipartStream {
1813
public:
1914
MultipartStream(async_web_server_cpp::HttpConnectionPtr& connection,
@@ -22,7 +17,7 @@ class MultipartStream {
2217

2318
void sendInitialHeader();
2419
void sendPartHeader(const ros::Time &time, const std::string& type, size_t payload_size);
25-
void sendPartFooter(const ros::Time &time);
20+
void sendPartFooter();
2621
void sendPartAndClear(const ros::Time &time, const std::string& type, std::vector<unsigned char> &data);
2722
void sendPart(const ros::Time &time, const std::string& type, const boost::asio::const_buffer &buffer,
2823
async_web_server_cpp::HttpConnection::ResourcePtr resource);
@@ -34,7 +29,7 @@ class MultipartStream {
3429
const std::size_t max_queue_size_;
3530
async_web_server_cpp::HttpConnectionPtr connection_;
3631
std::string boundry_;
37-
std::queue<PendingFooter> pending_footers_;
32+
std::queue<boost::weak_ptr<const void> > pending_footers_;
3833
};
3934

4035
}

src/multipart_stream.cpp

Lines changed: 6 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -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

4946
void 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

7067
bool 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

Comments
 (0)