Skip to content

Commit 67535ef

Browse files
pmusau17Joshua Whitley
authored andcommitted
replace ROSTIME
Signed-off-by: Patrick Musau <[email protected]>
1 parent b2874c6 commit 67535ef

File tree

1 file changed

+3
-3
lines changed

1 file changed

+3
-3
lines changed

image_view/src/video_recorder_node.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,7 @@ namespace image_view
3434
VideoRecorderNode::VideoRecorderNode(const rclcpp::NodeOptions & options)
3535
: rclcpp::Node("video_recorder_node", options),
3636
g_count(0),
37-
g_last_wrote_time(rclcpp::Time((int64_t) 0, RCL_SYSTEM_TIME)),
37+
g_last_wrote_time(rclcpp::Time((int64_t) 0, RCL_ROS_TIME)),
3838
recording_started(false)
3939
{
4040
bool stamped_filename;
@@ -112,7 +112,7 @@ void VideoRecorderNode::callback(const sensor_msgs::msg::Image::ConstSharedPtr &
112112
}
113113

114114
if (
115-
(rclcpp::Time(image_msg->header.stamp, RCL_SYSTEM_TIME) - g_last_wrote_time) <
115+
(rclcpp::Time(image_msg->header.stamp, RCL_ROS_TIME) - g_last_wrote_time) <
116116
rclcpp::Duration::from_seconds(1.0 / fps))
117117
{
118118
// Skip to get video with correct fps
@@ -133,7 +133,7 @@ void VideoRecorderNode::callback(const sensor_msgs::msg::Image::ConstSharedPtr &
133133
outputVideo << image;
134134
RCLCPP_INFO(this->get_logger(), "Recording frame %i\x1b[1F", g_count);
135135
g_count++;
136-
g_last_wrote_time = rclcpp::Time(image_msg->header.stamp, RCL_SYSTEM_TIME);
136+
g_last_wrote_time = rclcpp::Time(image_msg->header.stamp, RCL_ROS_TIME);
137137
} else {
138138
RCLCPP_WARN(this->get_logger(), "Frame skipped, no data!");
139139
}

0 commit comments

Comments
 (0)