diff --git a/projects/opendr_ws/src/perception/scripts/heart_anomaly_detection.py b/projects/opendr_ws/src/perception/scripts/heart_anomaly_detection.py index f0ff95bbf0..b36ecbdbdb 100755 --- a/projects/opendr_ws/src/perception/scripts/heart_anomaly_detection.py +++ b/projects/opendr_ws/src/perception/scripts/heart_anomaly_detection.py @@ -111,5 +111,7 @@ def callback(self, msg_data): print("Using CPU") device = "cpu" - gesture_node = HeartAnomalyNode(input_ecg_topic=args.input_ecg_topic, model=args.model, device=device) + gesture_node = HeartAnomalyNode(input_ecg_topic=args.input_ecg_topic, + output_heart_anomaly_topic=args.output_heart_anomaly_topic, + model=args.model, device=device) gesture_node.listen() diff --git a/projects/opendr_ws/src/perception/scripts/rgbd_hand_gesture_recognition.py b/projects/opendr_ws/src/perception/scripts/rgbd_hand_gesture_recognition.py index d81f2692ad..a21f10974c 100755 --- a/projects/opendr_ws/src/perception/scripts/rgbd_hand_gesture_recognition.py +++ b/projects/opendr_ws/src/perception/scripts/rgbd_hand_gesture_recognition.py @@ -48,13 +48,10 @@ def __init__(self, input_rgb_image_topic="/kinect2/qhd/image_color_rect", :type device: str """ - self.gesture_publisher = rospy.Publisher(output_gestures_topic, Classification2D, queue_size=10) + self.input_rgb_image_topic = input_rgb_image_topic + self.input_depth_image_topic = input_depth_image_topic - image_sub = message_filters.Subscriber(input_rgb_image_topic, ROS_Image, queue_size=1, buff_size=10000000) - depth_sub = message_filters.Subscriber(input_depth_image_topic, ROS_Image, queue_size=1, buff_size=10000000) - # synchronize image and depth data topics - ts = message_filters.TimeSynchronizer([image_sub, depth_sub], 10) - ts.registerCallback(self.callback) + self.gesture_publisher = rospy.Publisher(output_gestures_topic, Classification2D, queue_size=10) self.bridge = ROSBridge() @@ -74,6 +71,13 @@ def listen(self): Start the node and begin processing input data """ rospy.init_node('opendr_gesture_recognition', anonymous=True) + + image_sub = message_filters.Subscriber(self.input_rgb_image_topic, ROS_Image, queue_size=1, buff_size=10000000) + depth_sub = message_filters.Subscriber(self.input_depth_image_topic, ROS_Image, queue_size=1, buff_size=10000000) + # synchronize image and depth data topics + ts = message_filters.TimeSynchronizer([image_sub, depth_sub], 10) + ts.registerCallback(self.callback) + rospy.loginfo("RGBD gesture recognition node started!") rospy.spin()