Skip to content

Commit d00eedb

Browse files
committed
Use wall clock in places where the connection can leak if the sim time is looping
1 parent 5eab98c commit d00eedb

File tree

4 files changed

+11
-10
lines changed

4 files changed

+11
-10
lines changed

include/web_video_server/image_streamer.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -65,7 +65,7 @@ class ImageTransportImageStreamer : public ImageStreamer
6565
bool invert_;
6666
std::string default_transport_;
6767

68-
ros::Time last_frame;
68+
ros::WallTime last_frame;
6969
cv::Mat output_size_image;
7070
boost::mutex send_mutex_;
7171

include/web_video_server/multipart_stream.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,7 @@ namespace web_video_server
1010
{
1111

1212
struct PendingFooter {
13-
ros::Time timestamp;
13+
ros::WallTime timestamp;
1414
boost::weak_ptr<std::string> contents;
1515
};
1616

src/image_streamer.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -63,7 +63,7 @@ void ImageTransportImageStreamer::restreamFrame(double max_age)
6363
if (inactive_ || !initialized_ )
6464
return;
6565
try {
66-
if ( last_frame + ros::Duration(max_age) < ros::Time::now() ) {
66+
if ( last_frame + ros::WallDuration(max_age) < ros::WallTime::now() ) {
6767
boost::mutex::scoped_lock lock(send_mutex_);
6868
sendImage(output_size_image, ros::Time::now() ); // don't update last_frame, it may remain an old value.
6969
}
@@ -154,7 +154,7 @@ void ImageTransportImageStreamer::imageCallback(const sensor_msgs::ImageConstPtr
154154
initialized_ = true;
155155
}
156156

157-
last_frame = ros::Time::now();
157+
last_frame = ros::WallTime::now();
158158
sendImage(output_size_image, msg->header.stamp);
159159
}
160160
catch (cv_bridge::Exception &e)

src/multipart_stream.cpp

Lines changed: 7 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -15,9 +15,10 @@ void MultipartStream::sendInitialHeader() {
1515
async_web_server_cpp::HttpReply::builder(async_web_server_cpp::HttpReply::ok).header("Connection", "close").header(
1616
"Server", "web_video_server").header("Cache-Control",
1717
"no-cache, no-store, must-revalidate, pre-check=0, post-check=0, max-age=0").header(
18-
"Pragma", "no-cache").header("Content-type", "multipart/x-mixed-replace;boundary="+boundry_).header(
19-
"Access-Control-Allow-Origin", "*").header("Access-Control-Allow-Methods", "GET,POST,PUT,DELETE,HEAD,OPTIONS").header(
20-
"Access-Control-Allow-Headers", "Origin, Authorization, Accept, Content-Type").header("Access-Control-Max-Age", "3600").write(connection_);
18+
"Pragma", "no-cache").header("Content-type", "multipart/x-mixed-replace;boundary="+boundry_)
19+
.header("Access-Control-Allow-Origin", "*").header("Access-Control-Allow-Methods", "GET,POST,PUT,DELETE,HEAD,OPTIONS")
20+
.header("Access-Control-Allow-Headers", "Origin, Authorization, Accept, Content-Type")
21+
.header("Access-Control-Max-Age", "3600").write(connection_);
2122
connection_->write("--"+boundry_+"\r\n");
2223
}
2324

@@ -40,7 +41,7 @@ void MultipartStream::sendPartHeader(const ros::Time &time, const std::string& t
4041
void MultipartStream::sendPartFooter(const ros::Time &time) {
4142
boost::shared_ptr<std::string> str(new std::string("\r\n--"+boundry_+"\r\n"));
4243
PendingFooter pf;
43-
pf.timestamp = time;
44+
pf.timestamp = ros::WallTime::now();
4445
pf.contents = str;
4546
connection_->write(boost::asio::buffer(*str), str);
4647
if (max_queue_size_ > 0) pending_footers_.push(pf);
@@ -68,13 +69,13 @@ void MultipartStream::sendPart(const ros::Time &time, const std::string& type,
6869
}
6970

7071
bool MultipartStream::isBusy() {
71-
ros::Time currentTime = ros::Time::now();
72+
auto currentTime = ros::WallTime::now();
7273
while (!pending_footers_.empty())
7374
{
7475
if (pending_footers_.front().contents.expired()) {
7576
pending_footers_.pop();
7677
} else {
77-
ros::Time footerTime = pending_footers_.front().timestamp;
78+
auto footerTime = pending_footers_.front().timestamp;
7879
if ((currentTime - footerTime).toSec() > 0.5) {
7980
pending_footers_.pop();
8081
} else {

0 commit comments

Comments
 (0)