Skip to content

Commit a7f45b5

Browse files
committed
Use chrono steady_clock for frame timing
1 parent f3d5f94 commit a7f45b5

14 files changed

+70
-57
lines changed

include/web_video_server/image_streamer.hpp

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -30,6 +30,7 @@
3030

3131
#pragma once
3232

33+
#include <chrono>
3334
#include <memory>
3435
#include <string>
3536

@@ -64,7 +65,7 @@ class ImageStreamer
6465
/**
6566
* Restreams the last received image frame if older than max_age.
6667
*/
67-
virtual void restreamFrame(double max_age) = 0;
68+
virtual void restreamFrame(std::chrono::duration<double> max_age) = 0;
6869

6970
std::string getTopic()
7071
{
@@ -94,8 +95,8 @@ class ImageTransportImageStreamer : public ImageStreamer
9495

9596
protected:
9697
virtual cv::Mat decodeImage(const sensor_msgs::msg::Image::ConstSharedPtr & msg);
97-
virtual void sendImage(const cv::Mat &, const rclcpp::Time & time) = 0;
98-
virtual void restreamFrame(double max_age);
98+
virtual void sendImage(const cv::Mat &, const std::chrono::steady_clock::time_point & time) = 0;
99+
virtual void restreamFrame(std::chrono::duration<double> max_age);
99100
virtual void initialize(const cv::Mat &);
100101

101102
image_transport::Subscriber image_sub_;
@@ -105,7 +106,7 @@ class ImageTransportImageStreamer : public ImageStreamer
105106
std::string default_transport_;
106107
std::string qos_profile_name_;
107108

108-
rclcpp::Time last_frame;
109+
std::chrono::steady_clock::time_point last_frame_;
109110
cv::Mat output_size_image;
110111
std::mutex send_mutex_;
111112

include/web_video_server/jpeg_streamers.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -52,7 +52,7 @@ class MjpegStreamer : public ImageTransportImageStreamer
5252
~MjpegStreamer();
5353

5454
protected:
55-
virtual void sendImage(const cv::Mat &, const rclcpp::Time & time);
55+
virtual void sendImage(const cv::Mat &, const std::chrono::steady_clock::time_point & time);
5656

5757
private:
5858
MultipartStream stream_;
@@ -78,7 +78,7 @@ class JpegSnapshotStreamer : public ImageTransportImageStreamer
7878
~JpegSnapshotStreamer();
7979

8080
protected:
81-
virtual void sendImage(const cv::Mat &, const rclcpp::Time & time);
81+
virtual void sendImage(const cv::Mat &, const std::chrono::steady_clock::time_point & time);
8282

8383
private:
8484
int quality_;

include/web_video_server/libav_streamer.hpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -43,6 +43,7 @@ extern "C"
4343
}
4444

4545
#include <memory>
46+
#include <optional>
4647
#include <string>
4748

4849
#include "image_transport/image_transport.hpp"
@@ -66,7 +67,7 @@ class LibavStreamer : public ImageTransportImageStreamer
6667

6768
protected:
6869
virtual void initializeEncoder();
69-
virtual void sendImage(const cv::Mat &, const rclcpp::Time & time);
70+
virtual void sendImage(const cv::Mat &, const std::chrono::steady_clock::time_point & time);
7071
virtual void initialize(const cv::Mat &);
7172
AVFormatContext * format_context_;
7273
const AVCodec * codec_;
@@ -78,7 +79,7 @@ class LibavStreamer : public ImageTransportImageStreamer
7879
private:
7980
AVFrame * frame_;
8081
struct SwsContext * sws_context_;
81-
rclcpp::Time first_image_timestamp_;
82+
std::optional<std::chrono::steady_clock::time_point> first_image_timestamp_;
8283
std::mutex encode_mutex_;
8384

8485
std::string format_name_;

include/web_video_server/multipart_stream.hpp

Lines changed: 8 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -43,34 +43,35 @@ namespace web_video_server
4343

4444
struct PendingFooter
4545
{
46-
rclcpp::Time timestamp;
46+
std::chrono::steady_clock::time_point timestamp;
4747
std::weak_ptr<std::string> contents;
4848
};
4949

5050
class MultipartStream
5151
{
5252
public:
5353
MultipartStream(
54-
std::function<rclcpp::Time()> get_now,
5554
async_web_server_cpp::HttpConnectionPtr & connection,
5655
const std::string & boundry = "boundarydonotcross",
5756
std::size_t max_queue_size = 1);
5857

5958
void sendInitialHeader();
60-
void sendPartHeader(const rclcpp::Time & time, const std::string & type, size_t payload_size);
61-
void sendPartFooter(const rclcpp::Time & time);
59+
void sendPartHeader(
60+
const std::chrono::steady_clock::time_point & time, const std::string & type,
61+
size_t payload_size);
62+
void sendPartFooter(const std::chrono::steady_clock::time_point & time);
6263
void sendPartAndClear(
63-
const rclcpp::Time & time, const std::string & type,
64+
const std::chrono::steady_clock::time_point & time, const std::string & type,
6465
std::vector<unsigned char> & data);
6566
void sendPart(
66-
const rclcpp::Time & time, const std::string & type, const boost::asio::const_buffer & buffer,
67+
const std::chrono::steady_clock::time_point & time, const std::string & type,
68+
const boost::asio::const_buffer & buffer,
6769
async_web_server_cpp::HttpConnection::ResourcePtr resource);
6870

6971
private:
7072
bool isBusy();
7173

7274
private:
73-
std::function<rclcpp::Time()> get_now_;
7475
const std::size_t max_queue_size_;
7576
async_web_server_cpp::HttpConnectionPtr connection_;
7677
std::string boundry_;

include/web_video_server/png_streamers.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -51,7 +51,7 @@ class PngStreamer : public ImageTransportImageStreamer
5151
~PngStreamer();
5252

5353
protected:
54-
virtual void sendImage(const cv::Mat &, const rclcpp::Time & time);
54+
virtual void sendImage(const cv::Mat &, const std::chrono::steady_clock::time_point & time);
5555
virtual cv::Mat decodeImage(const sensor_msgs::msg::Image::ConstSharedPtr & msg);
5656

5757
private:

include/web_video_server/ros_compressed_streamer.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -51,18 +51,18 @@ class RosCompressedStreamer : public ImageStreamer
5151
rclcpp::Node::SharedPtr node);
5252
~RosCompressedStreamer();
5353
virtual void start();
54-
virtual void restreamFrame(double max_age);
54+
virtual void restreamFrame(std::chrono::duration<double> max_age);
5555

5656
protected:
5757
virtual void sendImage(
5858
const sensor_msgs::msg::CompressedImage::ConstSharedPtr msg,
59-
const rclcpp::Time & time);
59+
const std::chrono::steady_clock::time_point & time);
6060

6161
private:
6262
void imageCallback(const sensor_msgs::msg::CompressedImage::ConstSharedPtr msg);
6363
MultipartStream stream_;
6464
rclcpp::Subscription<sensor_msgs::msg::CompressedImage>::SharedPtr image_sub_;
65-
rclcpp::Time last_frame;
65+
std::chrono::steady_clock::time_point last_frame_;
6666
sensor_msgs::msg::CompressedImage::ConstSharedPtr last_msg;
6767
std::mutex send_mutex_;
6868
std::string qos_profile_name_;

include/web_video_server/web_video_server.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -94,7 +94,7 @@ class WebVideoServer : public rclcpp::Node
9494
const char * begin, const char * end);
9595

9696
private:
97-
void restreamFrames(double max_age);
97+
void restreamFrames(std::chrono::duration<double> max_age);
9898
void cleanup_inactive_streams();
9999

100100
rclcpp::TimerBase::SharedPtr cleanup_timer_;

src/image_streamer.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -110,16 +110,16 @@ void ImageTransportImageStreamer::initialize(const cv::Mat &)
110110
{
111111
}
112112

113-
void ImageTransportImageStreamer::restreamFrame(double max_age)
113+
void ImageTransportImageStreamer::restreamFrame(std::chrono::duration<double> max_age)
114114
{
115115
if (inactive_ || !initialized_) {
116116
return;
117117
}
118118
try {
119-
if (last_frame + rclcpp::Duration::from_seconds(max_age) < node_->now() ) {
119+
if (last_frame_ + max_age < std::chrono::steady_clock::now()) {
120120
std::scoped_lock lock(send_mutex_);
121121
// don't update last_frame, it may remain an old value.
122-
sendImage(output_size_image, node_->now());
122+
sendImage(output_size_image, std::chrono::steady_clock::now());
123123
}
124124
} catch (boost::system::system_error & e) {
125125
// happens when client disconnects
@@ -199,8 +199,8 @@ void ImageTransportImageStreamer::imageCallback(const sensor_msgs::msg::Image::C
199199
initialized_ = true;
200200
}
201201

202-
last_frame = node_->now();
203-
sendImage(output_size_image, msg->header.stamp);
202+
last_frame_ = std::chrono::steady_clock::now();
203+
sendImage(output_size_image, last_frame_);
204204
} catch (cv_bridge::Exception & e) {
205205
auto & clk = *node_->get_clock();
206206
RCLCPP_ERROR_THROTTLE(node_->get_logger(), clk, 40, "cv_bridge exception: %s", e.what());

src/jpeg_streamers.cpp

Lines changed: 9 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,7 @@ MjpegStreamer::MjpegStreamer(
3838
const async_web_server_cpp::HttpRequest & request,
3939
async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr node)
4040
: ImageTransportImageStreamer(request, connection, node),
41-
stream_(std::bind(&rclcpp::Node::now, node), connection)
41+
stream_(connection)
4242
{
4343
quality_ = request.get_query_param_value_or_default<int>("quality", 95);
4444
stream_.sendInitialHeader();
@@ -50,7 +50,9 @@ MjpegStreamer::~MjpegStreamer()
5050
std::scoped_lock lock(send_mutex_); // protects sendImage.
5151
}
5252

53-
void MjpegStreamer::sendImage(const cv::Mat & img, const rclcpp::Time & time)
53+
void MjpegStreamer::sendImage(
54+
const cv::Mat & img,
55+
const std::chrono::steady_clock::time_point & time)
5456
{
5557
std::vector<int> encode_params;
5658
encode_params.push_back(cv::IMWRITE_JPEG_QUALITY);
@@ -94,7 +96,9 @@ JpegSnapshotStreamer::~JpegSnapshotStreamer()
9496
std::scoped_lock lock(send_mutex_); // protects sendImage.
9597
}
9698

97-
void JpegSnapshotStreamer::sendImage(const cv::Mat & img, const rclcpp::Time & time)
99+
void JpegSnapshotStreamer::sendImage(
100+
const cv::Mat & img,
101+
const std::chrono::steady_clock::time_point & time)
98102
{
99103
std::vector<int> encode_params;
100104
encode_params.push_back(cv::IMWRITE_JPEG_QUALITY);
@@ -104,7 +108,8 @@ void JpegSnapshotStreamer::sendImage(const cv::Mat & img, const rclcpp::Time & t
104108
cv::imencode(".jpeg", img, encoded_buffer, encode_params);
105109

106110
char stamp[20];
107-
snprintf(stamp, sizeof(stamp), "%.06lf", time.seconds());
111+
snprintf(stamp, sizeof(stamp), "%.06lf",
112+
std::chrono::duration_cast<std::chrono::duration<double>>(time.time_since_epoch()).count());
108113
async_web_server_cpp::HttpReply::builder(async_web_server_cpp::HttpReply::ok)
109114
.header("Connection", "close")
110115
.header("Server", "web_video_server")

src/libav_streamer.cpp

Lines changed: 9 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -44,9 +44,9 @@ LibavStreamer::LibavStreamer(
4444
const std::string & format_name, const std::string & codec_name,
4545
const std::string & content_type)
4646
: ImageTransportImageStreamer(request, connection, node), format_context_(0), codec_(0),
47-
codec_context_(0), video_stream_(0), frame_(0), sws_context_(0), first_image_timestamp_(0),
48-
format_name_(format_name), codec_name_(codec_name), content_type_(content_type), opt_(0),
49-
io_buffer_(0)
47+
codec_context_(0), video_stream_(0), frame_(0), sws_context_(0),
48+
first_image_timestamp_(std::nullopt), format_name_(format_name), codec_name_(codec_name),
49+
content_type_(content_type), opt_(0), io_buffer_(0)
5050
{
5151
bitrate_ = request.get_query_param_value_or_default<int>("bitrate", 100000);
5252
qmin_ = request.get_query_param_value_or_default<int>("qmin", 10);
@@ -215,10 +215,12 @@ void LibavStreamer::initializeEncoder()
215215
{
216216
}
217217

218-
void LibavStreamer::sendImage(const cv::Mat & img, const rclcpp::Time & time)
218+
void LibavStreamer::sendImage(
219+
const cv::Mat & img,
220+
const std::chrono::steady_clock::time_point & time)
219221
{
220222
std::scoped_lock lock(encode_mutex_);
221-
if (0 == first_image_timestamp_.nanoseconds()) {
223+
if (!first_image_timestamp_.has_value()) {
222224
first_image_timestamp_ = time;
223225
}
224226

@@ -274,7 +276,8 @@ void LibavStreamer::sendImage(const cv::Mat & img, const rclcpp::Time & time)
274276
std::size_t size;
275277
uint8_t * output_buf;
276278

277-
double seconds = (time - first_image_timestamp_).seconds();
279+
double seconds = std::chrono::duration_cast<std::chrono::duration<double>>(time -
280+
first_image_timestamp_.value()).count();
278281
// Encode video at 1/0.95 to minimize delay
279282
pkt->pts = (int64_t)(seconds / av_q2d(video_stream_->time_base) * 0.95);
280283
if (pkt->pts <= 0) {

0 commit comments

Comments
 (0)