Skip to content

Commit

Permalink
Update extract_images_sync to add sec_per_frame parameter
Browse files Browse the repository at this point in the history
  • Loading branch information
artineering committed Jan 30, 2024
1 parent d8ada8d commit 38a3116
Showing 1 changed file with 20 additions and 1 deletion.
21 changes: 20 additions & 1 deletion image_view/scripts/extract_images_sync
Original file line number Diff line number Diff line change
Expand Up @@ -51,10 +51,18 @@ class ExtractImagesSync(Node):
super().__init__('extract_images_sync')
self.get_logger().info('Extract_Images_Sync Node has been started')
self.seq = 0
self.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.1).value

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

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

def save(self, *imgmsgs):
delay = self.get_clock().now() - self.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 < self.sec_per_frame):
return

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

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

0 comments on commit 38a3116

Please sign in to comment.