Skip to content

Commit

Permalink
use ros::Time::now() instead of camera timestamp when publishing
Browse files Browse the repository at this point in the history
  • Loading branch information
QuentinTorg committed Nov 4, 2024
1 parent 3471833 commit 77368b5
Show file tree
Hide file tree
Showing 3 changed files with 6 additions and 5 deletions.
2 changes: 1 addition & 1 deletion include/web_video_server/multipart_stream.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ class MultipartStream {
async_web_server_cpp::HttpConnection::ResourcePtr resource);

private:
bool isBusy(const ros::Time &currentTime);
bool isBusy();

private:
const std::size_t max_queue_size_;
Expand Down
2 changes: 1 addition & 1 deletion src/image_streamer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -149,7 +149,7 @@ void ImageTransportImageStreamer::imageCallback(const sensor_msgs::ImageConstPtr
}

last_frame = ros::Time::now();
sendImage(output_size_image, msg->header.stamp);
sendImage(output_size_image, last_frame);
}
catch (cv_bridge::Exception &e)
{
Expand Down
7 changes: 4 additions & 3 deletions src/multipart_stream.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ void MultipartStream::sendPartFooter(const ros::Time &time) {

void MultipartStream::sendPartAndClear(const ros::Time &time, const std::string& type,
std::vector<unsigned char> &data) {
if (!isBusy(time))
if (!isBusy())
{
sendPartHeader(time, type, data.size());
connection_->write_and_clear(data);
Expand All @@ -59,15 +59,16 @@ void MultipartStream::sendPartAndClear(const ros::Time &time, const std::string&
void MultipartStream::sendPart(const ros::Time &time, const std::string& type,
const boost::asio::const_buffer &buffer,
async_web_server_cpp::HttpConnection::ResourcePtr resource) {
if (!isBusy(time))
if (!isBusy())
{
sendPartHeader(time, type, boost::asio::buffer_size(buffer));
connection_->write(buffer, resource);
sendPartFooter(time);
}
}

bool MultipartStream::isBusy(const ros::Time &currentTime) {
bool MultipartStream::isBusy() {
ros::Time currentTime = ros::Time::now();
while (!pending_footers_.empty())
{
if (pending_footers_.front().contents.expired()) {
Expand Down

0 comments on commit 77368b5

Please sign in to comment.