Skip to content

Commit

Permalink
ROS 2: Add option to prepend timestamp to image filename in image_sav…
Browse files Browse the repository at this point in the history
…er node (#870)

Related to this PR in ROS 1
https://github.com/ros-perception/image_pipeline/pull/806/files

---------

Signed-off-by: Alejandro Hernández Cordero <ahcorde@gmail.com>
  • Loading branch information
ahcorde committed Jan 19, 2024
1 parent 369ce4b commit fad65d6
Show file tree
Hide file tree
Showing 2 changed files with 10 additions and 0 deletions.
1 change: 1 addition & 0 deletions image_view/include/image_view/image_saver_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,7 @@ class ImageSaverNode

private:
boost::format g_format;
bool stamped_filename_;
bool save_all_image_{false};
bool save_image_service_{false};
std::string encoding_;
Expand Down
9 changes: 9 additions & 0 deletions image_view/src/image_saver_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,7 @@

#include <chrono>
#include <memory>
#include <sstream>
#include <string>

#include "cv_bridge/cv_bridge.hpp"
Expand Down Expand Up @@ -89,6 +90,7 @@ ImageSaverNode::ImageSaverNode(const rclcpp::NodeOptions & options)
format_string = this->declare_parameter("filename_format", std::string("left%04i.%s"));
encoding_ = this->declare_parameter("encoding", std::string("bgr8"));
save_all_image_ = this->declare_parameter("save_all_image", true);
stamped_filename_ = this->declare_parameter("stamped_filename", false);
request_start_end_ = this->declare_parameter("request_start_end", false);
g_format.parse(format_string);

Expand Down Expand Up @@ -142,6 +144,13 @@ bool ImageSaverNode::saveImage(
}

if (save_all_image_ || save_image_service_) {
if (stamped_filename_) {
std::stringstream ss;
ss << this->now().nanoseconds();
std::string timestamp_str = ss.str();
filename.insert(0, timestamp_str);
}

if (cv::imwrite(filename, image)) {
RCLCPP_INFO(this->get_logger(), "Saved image %s", filename.c_str());
} else {
Expand Down

0 comments on commit fad65d6

Please sign in to comment.