Skip to content

Commit

Permalink
Update extract_images_sync to add sec_per_frame parameter (ros-percep…
Browse files Browse the repository at this point in the history
…tion#920)

Added sec_per_frame parameter to allow decimation of frames being
synchronized and captured.
fixes ros-perception#726

---------

Co-authored-by: Michael Ferguson <mfergs7@gmail.com>
  • Loading branch information
2 people authored and Krzysztof Wojciechowski committed May 27, 2024
1 parent b742261 commit 39dd27d
Showing 1 changed file with 22 additions and 1 deletion.
23 changes: 22 additions & 1 deletion image_view/scripts/extract_images_sync
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@ import cv_bridge
import rclpy

from rclpy.node import Node
from rclpy.duration import Duration
from sensor_msgs.msg import Image
from message_filters import ApproximateTimeSynchronizer, TimeSynchronizer, Subscriber

Expand All @@ -51,10 +52,19 @@ class ExtractImagesSync(Node):
super().__init__('extract_images_sync')
self.get_logger().info('Extract_Images_Sync Node has been started')
self.seq = 0
self.last_frame_time = self.get_clock().now()

self.fname_fmt = self.declare_parameter(
'filename_format', 'frame%04i_%i.jpg').value
'filename_format', 'frame%04i_%i.jpg').value

# Do not scale dynamically by default.
self.do_dynamic_scaling = self.declare_parameter(
'do_dynamic_scaling', False).value

# Limit the throughput to 10fps by default.
self.sec_per_frame = self.declare_parameter(
'sec_per_frame', 0.0).value

img_topics = self.declare_parameter('inputs', None).value

if img_topics is None:
Expand All @@ -80,6 +90,17 @@ Typical command-line usage:
sync.registerCallback(self.save)

def save(self, *imgmsgs):
delay = self.get_clock().now() - self.last_frame_time

# Decimation is enabled if it is set to greater than
# zero. If it is enabled, exit if delay is less than
# the decimation rate specified.
if (self.sec_per_frame > 0) and (delay < Duration(seconds=self.sec_per_frame)):
return

# Update the current time
self.last_frame_time = self.get_clock().now()

seq = self.seq
bridge = cv_bridge.CvBridge()
for i, imgmsg in enumerate(imgmsgs):
Expand Down

0 comments on commit 39dd27d

Please sign in to comment.