From 639d73e6837c1b12edd403742cfa2b78363194ed Mon Sep 17 00:00:00 2001 From: paul-shuvo Date: Mon, 1 Mar 2021 23:34:33 -0800 Subject: [PATCH] added time synchronizer --- src/config.py | 4 ++-- src/object_detection.py | 19 +++++++++---------- src/planar_pose_estimation.py | 2 +- 3 files changed, 12 insertions(+), 13 deletions(-) diff --git a/src/config.py b/src/config.py index cf61162..91a12e3 100644 --- a/src/config.py +++ b/src/config.py @@ -46,7 +46,7 @@ # Name of the objects corresponding to # the files name without the extension # e.g. book-1.jpg corresponds to book-1 -objects = ['book-1'] +objects = ['book-2', 'book-3'] # Minimum match required for an object to be considered detected min_match_count = 15 @@ -62,7 +62,7 @@ # Visualize the detected objects, # if set to True -show_image = True +show_image = False # Visualize the pose of the objects, # if set to True diff --git a/src/object_detection.py b/src/object_detection.py index cb57b6d..419e6e5 100755 --- a/src/object_detection.py +++ b/src/object_detection.py @@ -7,6 +7,7 @@ from time import time import cv2 import json +import message_filters # ROS imports import rospy from std_msgs.msg import String @@ -67,16 +68,14 @@ def __init__(self, config, to_gray: bool = False): String, queue_size=10 ) - - # Starts the subscriber - r = rospy.Rate(self.frame_rate) - while not rospy.is_shutdown(): - rospy.Subscriber( - self.config.image_sub['topic'], - self.config.image_sub['type'], - self.callback - ) - r.sleep() + image_sub = message_filters.Subscriber(self.config.image_sub['topic'], + self.config.image_sub['type']) + ts = message_filters.ApproximateTimeSynchronizer( + [image_sub], 10, 1, allow_headerless=True + ) # Changed code + ts.registerCallback(self.callback) + # spin + rospy.spin() def extract_object_info(self, objects, obj_path: str): """ diff --git a/src/planar_pose_estimation.py b/src/planar_pose_estimation.py index 51eea08..55bbd44 100755 --- a/src/planar_pose_estimation.py +++ b/src/planar_pose_estimation.py @@ -49,7 +49,7 @@ def __init__(self, config): # as `PoseArray`. self.pose_info_pub = rospy.Publisher('/object_pose_info', String, queue_size=10) - self.pose_array_pub = rospy.Publisher('/object_namepose_array', + self.pose_array_pub = rospy.Publisher('/object_pose_array', PoseArray, queue_size=10) self.object_pose_info = {}