Skip to content

Commit

Permalink
added time synchronizer
Browse files Browse the repository at this point in the history
  • Loading branch information
paul-shuvo committed Mar 2, 2021
1 parent 1e625ae commit 639d73e
Show file tree
Hide file tree
Showing 3 changed files with 12 additions and 13 deletions.
4 changes: 2 additions & 2 deletions src/config.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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
Expand Down
19 changes: 9 additions & 10 deletions src/object_detection.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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):
"""
Expand Down
2 changes: 1 addition & 1 deletion src/planar_pose_estimation.py
Original file line number Diff line number Diff line change
Expand Up @@ -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 = {}
Expand Down

0 comments on commit 639d73e

Please sign in to comment.