Skip to content

Commit

Permalink
Revert "Add a workaround for MultipartStream constant busy state (Rob…
Browse files Browse the repository at this point in the history
…otWebTools#83)"

This reverts commit c3d08d4.
  • Loading branch information
patrickcjh committed Sep 11, 2024
1 parent c33cab3 commit 5b7b0a8
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 26 deletions.
9 changes: 2 additions & 7 deletions include/web_video_server/multipart_stream.h
Original file line number Diff line number Diff line change
Expand Up @@ -9,11 +9,6 @@
namespace web_video_server
{

struct PendingFooter {
ros::Time timestamp;
boost::weak_ptr<std::string> contents;
};

class MultipartStream {
public:
MultipartStream(async_web_server_cpp::HttpConnectionPtr& connection,
Expand All @@ -22,7 +17,7 @@ class MultipartStream {

void sendInitialHeader();
void sendPartHeader(const ros::Time &time, const std::string& type, size_t payload_size);
void sendPartFooter(const ros::Time &time);
void sendPartFooter();
void sendPartAndClear(const ros::Time &time, const std::string& type, std::vector<unsigned char> &data);
void sendPart(const ros::Time &time, const std::string& type, const boost::asio::const_buffer &buffer,
async_web_server_cpp::HttpConnection::ResourcePtr resource);
Expand All @@ -34,7 +29,7 @@ class MultipartStream {
const std::size_t max_queue_size_;
async_web_server_cpp::HttpConnectionPtr connection_;
std::string boundry_;
std::queue<PendingFooter> pending_footers_;
std::queue<boost::weak_ptr<const void> > pending_footers_;
};

}
Expand Down
25 changes: 6 additions & 19 deletions src/multipart_stream.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,13 +37,10 @@ void MultipartStream::sendPartHeader(const ros::Time &time, const std::string& t
connection_->write(async_web_server_cpp::HttpReply::to_buffers(*headers), headers);
}

void MultipartStream::sendPartFooter(const ros::Time &time) {
void MultipartStream::sendPartFooter() {
boost::shared_ptr<std::string> str(new std::string("\r\n--"+boundry_+"\r\n"));
PendingFooter pf;
pf.timestamp = time;
pf.contents = str;
connection_->write(boost::asio::buffer(*str), str);
if (max_queue_size_ > 0) pending_footers_.push(pf);
if (max_queue_size_ > 0) pending_footers_.push(str);
}

void MultipartStream::sendPartAndClear(const ros::Time &time, const std::string& type,
Expand All @@ -52,7 +49,7 @@ void MultipartStream::sendPartAndClear(const ros::Time &time, const std::string&
{
sendPartHeader(time, type, data.size());
connection_->write_and_clear(data);
sendPartFooter(time);
sendPartFooter();
}
}

Expand All @@ -63,24 +60,14 @@ void MultipartStream::sendPart(const ros::Time &time, const std::string& type,
{
sendPartHeader(time, type, boost::asio::buffer_size(buffer));
connection_->write(buffer, resource);
sendPartFooter(time);
sendPartFooter();
}
}

bool MultipartStream::isBusy() {
ros::Time currentTime = ros::Time::now();
while (!pending_footers_.empty())
while (!pending_footers_.empty() && pending_footers_.front().expired())
{
if (pending_footers_.front().contents.expired()) {
pending_footers_.pop();
} else {
ros::Time footerTime = pending_footers_.front().timestamp;
if ((currentTime - footerTime).toSec() > 0.5) {
pending_footers_.pop();
} else {
break;
}
}
pending_footers_.pop();
}
return !(max_queue_size_ == 0 || pending_footers_.size() < max_queue_size_);
}
Expand Down

0 comments on commit 5b7b0a8

Please sign in to comment.