@@ -35,11 +35,10 @@ namespace web_video_server
35
35
{
36
36
37
37
MultipartStream::MultipartStream (
38
- std::function<rclcpp::Time()> get_now,
39
38
async_web_server_cpp::HttpConnectionPtr & connection,
40
39
const std::string & boundry,
41
40
std::size_t max_queue_size)
42
- : get_now_(get_now), connection_(connection), boundry_(boundry), max_queue_size_(max_queue_size)
41
+ : connection_(connection), boundry_(boundry), max_queue_size_(max_queue_size)
43
42
{}
44
43
45
44
void MultipartStream::sendInitialHeader ()
@@ -58,11 +57,12 @@ void MultipartStream::sendInitialHeader()
58
57
}
59
58
60
59
void MultipartStream::sendPartHeader (
61
- const rclcpp::Time & time, const std::string & type,
60
+ const std::chrono::steady_clock::time_point & time, const std::string & type,
62
61
size_t payload_size)
63
62
{
64
63
char stamp[20 ];
65
- snprintf (stamp, sizeof (stamp), " %.06lf" , time .seconds ());
64
+ snprintf (stamp, sizeof (stamp), " %.06lf" ,
65
+ std::chrono::duration_cast<std::chrono::duration<double >>(time .time_since_epoch ()).count ());
66
66
std::shared_ptr<std::vector<async_web_server_cpp::HttpHeader>> headers (
67
67
new std::vector<async_web_server_cpp::HttpHeader>());
68
68
headers->push_back (async_web_server_cpp::HttpHeader (" Content-type" , type));
@@ -73,7 +73,7 @@ void MultipartStream::sendPartHeader(
73
73
connection_->write (async_web_server_cpp::HttpReply::to_buffers (*headers), headers);
74
74
}
75
75
76
- void MultipartStream::sendPartFooter (const rclcpp::Time & time)
76
+ void MultipartStream::sendPartFooter (const std::chrono::steady_clock::time_point & time)
77
77
{
78
78
std::shared_ptr<std::string> str (new std::string (" \r\n --" + boundry_ + " \r\n " ));
79
79
PendingFooter pf;
@@ -84,7 +84,7 @@ void MultipartStream::sendPartFooter(const rclcpp::Time & time)
84
84
}
85
85
86
86
void MultipartStream::sendPartAndClear (
87
- const rclcpp::Time & time, const std::string & type,
87
+ const std::chrono::steady_clock::time_point & time, const std::string & type,
88
88
std::vector<unsigned char > & data)
89
89
{
90
90
if (!isBusy ()) {
@@ -95,7 +95,7 @@ void MultipartStream::sendPartAndClear(
95
95
}
96
96
97
97
void MultipartStream::sendPart (
98
- const rclcpp::Time & time, const std::string & type,
98
+ const std::chrono::steady_clock::time_point & time, const std::string & type,
99
99
const boost::asio::const_buffer & buffer,
100
100
async_web_server_cpp::HttpConnection::ResourcePtr resource)
101
101
{
@@ -108,13 +108,15 @@ void MultipartStream::sendPart(
108
108
109
109
bool MultipartStream::isBusy ()
110
110
{
111
- rclcpp::Time currentTime = get_now_ ();
111
+ auto current_time = std::chrono::steady_clock::now ();
112
112
while (!pending_footers_.empty ()) {
113
113
if (pending_footers_.front ().contents .expired ()) {
114
114
pending_footers_.pop ();
115
115
} else {
116
- rclcpp::Time footerTime = pending_footers_.front ().timestamp ;
117
- if ((currentTime - footerTime).seconds () > 0.5 ) {
116
+ auto footer_time = pending_footers_.front ().timestamp ;
117
+ if (std::chrono::duration_cast<std::chrono::duration<double >>((current_time -
118
+ footer_time)).count () > 0.5 )
119
+ {
118
120
pending_footers_.pop ();
119
121
} else {
120
122
break ;
0 commit comments