Skip to content

Commit

Permalink
Use chrono in png snapshot streamer
Browse files Browse the repository at this point in the history
  • Loading branch information
bjsowa committed Nov 11, 2024
1 parent f87ddd0 commit 526572a
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 3 deletions.
2 changes: 1 addition & 1 deletion include/web_video_server/png_streamers.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@ class PngSnapshotStreamer : public ImageTransportImageStreamer
~PngSnapshotStreamer();

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

private:
Expand Down
8 changes: 6 additions & 2 deletions src/png_streamers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -120,7 +120,9 @@ cv::Mat PngSnapshotStreamer::decodeImage(const sensor_msgs::msg::Image::ConstSha
}
}

void PngSnapshotStreamer::sendImage(const cv::Mat & img, const rclcpp::Time & time)
void PngSnapshotStreamer::sendImage(
const cv::Mat & img,
const std::chrono::steady_clock::time_point & time)
{
std::vector<int> encode_params;
encode_params.push_back(cv::IMWRITE_PNG_COMPRESSION);
Expand All @@ -130,7 +132,9 @@ void PngSnapshotStreamer::sendImage(const cv::Mat & img, const rclcpp::Time & ti
cv::imencode(".png", img, encoded_buffer, encode_params);

char stamp[20];
snprintf(stamp, sizeof(stamp), "%.06lf", time.seconds());
snprintf(
stamp, sizeof(stamp), "%.06lf",
std::chrono::duration_cast<std::chrono::duration<double>>(time.time_since_epoch()).count());
async_web_server_cpp::HttpReply::builder(async_web_server_cpp::HttpReply::ok)
.header("Connection", "close")
.header("Server", "web_video_server")
Expand Down

0 comments on commit 526572a

Please sign in to comment.