From 325ff03dfc28059b6f1dfd4ea807fee5ab85b41f Mon Sep 17 00:00:00 2001 From: ChipTheCincoze Date: Thu, 30 Nov 2023 18:10:22 -0500 Subject: [PATCH] Bug fix for check all data --- .../src/perceptions/perceptions/ros/utils/DataNode.py | 7 +------ 1 file changed, 1 insertion(+), 6 deletions(-) diff --git a/driverless_ws/src/perceptions/perceptions/ros/utils/DataNode.py b/driverless_ws/src/perceptions/perceptions/ros/utils/DataNode.py index a3bbf176c..a17e88d37 100644 --- a/driverless_ws/src/perceptions/perceptions/ros/utils/DataNode.py +++ b/driverless_ws/src/perceptions/perceptions/ros/utils/DataNode.py @@ -34,25 +34,20 @@ def __init__(self, required_data=list(DataType), name="data_node", visualize=Fal self.visualize = visualize if DataType.ZED_LEFT_COLOR in self.required_data: - print("need zed left") self.left_color_subscriber = self.create_subscription(Image, LEFT_IMAGE_TOPIC, self.left_color_callback, qos_profile=BEST_EFFORT_QOS_PROFILE) if DataType.ZED_RIGHT_COLOR in self.required_data: - print("need zed right") self.right_color_subscriber = self.create_subscription(Image, RIGHT_IMAGE_TOPIC, self.right_color_callback, qos_profile=BEST_EFFORT_QOS_PROFILE) if DataType.ZED_XYZ_IMG in self.required_data: - print("need zed xyz") self.xyz_image_subscriber = self.create_subscription(Image, XYZ_IMAGE_TOPIC, self.xyz_image_callback, qos_profile=BEST_EFFORT_QOS_PROFILE) if self.visualize: self.xyz_image_window = vis.init_visualizer_window() if DataType.ZED_DEPTH_IMG in self.required_data: - print("need zed depth") self.depth_subscriber = self.create_subscription(Image, DEPTH_IMAGE_TOPIC, self.depth_image_callback, qos_profile=BEST_EFFORT_QOS_PROFILE) if DataType.HESAI_POINTCLOUD in self.required_data: - print("need hesai") self.point_subscriber = self.create_subscription(PointCloud2, POINT_TOPIC, self.points_callback, qos_profile=BEST_EFFORT_QOS_PROFILE) if self.visualize: self.window = vis.init_visualizer_window() @@ -69,7 +64,7 @@ def __init__(self, required_data=list(DataType), name="data_node", visualize=Fal def got_all_data(self): # returns whether data node has all pieces of data - return all([(data_type in self.required_data) for data_type in self.data.keys()]) + return all([(data_type in self.data.keys()) for data_type in self.required_data]) def left_color_callback(self, msg): self.data[DataType.ZED_LEFT_COLOR] = conv.img_to_npy(msg)