Skip to content

Commit c3d08d4

Browse files
sfalexrogjihoonl
authored andcommitted
Add a workaround for MultipartStream constant busy state (#83)
* Add a workaround for MultipartStream constant busy state * Remove C++11 features
1 parent 243d0fb commit c3d08d4

File tree

2 files changed

+26
-8
lines changed

2 files changed

+26
-8
lines changed

include/web_video_server/multipart_stream.h

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

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

1823
void sendInitialHeader();
1924
void sendPartHeader(const ros::Time &time, const std::string& type, size_t payload_size);
20-
void sendPartFooter();
25+
void sendPartFooter(const ros::Time &time);
2126
void sendPartAndClear(const ros::Time &time, const std::string& type, std::vector<unsigned char> &data);
2227
void sendPart(const ros::Time &time, const std::string& type, const boost::asio::const_buffer &buffer,
2328
async_web_server_cpp::HttpConnection::ResourcePtr resource);
@@ -29,7 +34,7 @@ class MultipartStream {
2934
const std::size_t max_queue_size_;
3035
async_web_server_cpp::HttpConnectionPtr connection_;
3136
std::string boundry_;
32-
std::queue<boost::weak_ptr<const void> > pending_footers_;
37+
std::queue<PendingFooter> pending_footers_;
3338
};
3439

3540
}

src/multipart_stream.cpp

Lines changed: 19 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -32,10 +32,13 @@ void MultipartStream::sendPartHeader(const ros::Time &time, const std::string& t
3232
connection_->write(async_web_server_cpp::HttpReply::to_buffers(*headers), headers);
3333
}
3434

35-
void MultipartStream::sendPartFooter() {
35+
void MultipartStream::sendPartFooter(const ros::Time &time) {
3636
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;
3740
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);
3942
}
4043

4144
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&
4447
{
4548
sendPartHeader(time, type, data.size());
4649
connection_->write_and_clear(data);
47-
sendPartFooter();
50+
sendPartFooter(time);
4851
}
4952
}
5053

@@ -55,14 +58,24 @@ void MultipartStream::sendPart(const ros::Time &time, const std::string& type,
5558
{
5659
sendPartHeader(time, type, boost::asio::buffer_size(buffer));
5760
connection_->write(buffer, resource);
58-
sendPartFooter();
61+
sendPartFooter(time);
5962
}
6063
}
6164

6265
bool MultipartStream::isBusy() {
63-
while (!pending_footers_.empty() && pending_footers_.front().expired())
66+
ros::Time currentTime = ros::Time::now();
67+
while (!pending_footers_.empty())
6468
{
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+
}
6679
}
6780
return !(max_queue_size_ == 0 || pending_footers_.size() < max_queue_size_);
6881
}

0 commit comments

Comments
 (0)