def __process_s3_pcl_files(self, ros_topic=None, files=None, resp=None, frame_id=None, s3_client=None, lidar_view=None, vehicle_transform_matrix=None): for f in files: try: path = resp.get(block=True).split(" ", 1)[0] npz = np.load(path) pcl_ts = int(f[2]) points, reflectance = RosUtil.parse_pcl_npz( npz=npz, lidar_view=lidar_view, vehicle_transform_matrix=vehicle_transform_matrix) if not np.isnan(points).any(): self.__record_pcl_msg(ros_topic=ros_topic, points=points, reflectance=reflectance, pcl_ts=pcl_ts, frame_id=frame_id, s3_client=s3_client) os.remove(path) except BaseException as _: exc_type, exc_value, exc_traceback = sys.exc_info() traceback.print_tb(exc_traceback, limit=20, file=sys.stdout) self.logger.error(str(exc_type)) self.logger.error(str(exc_value))
def __record_pcl_from_fs(self, manifest=None, ros_topic=None, sensor=None, frame_id=None): pcl_reader = dict() pcl_ts = dict() npz = dict() lidar_view = self.request.get("lidar_view", "camera") vehicle_transform_matrix = self.__sensor_to_vehicle_matrix( sensor=sensor) if lidar_view == "vehicle" else None while True: files = None while not files and manifest.is_open(): files = manifest.fetch() if not files: break count = read_pcl_from_fs(data_store=self.data_store, files=files, pcl_reader=pcl_reader, pcl_ts=pcl_ts, npz=npz) for i in range(0, count): pcl_reader[i].join() points, reflectance = RosUtil.parse_pcl_npz( npz=npz[i], lidar_view=lidar_view, vehicle_transform_matrix=vehicle_transform_matrix) if not np.isnan(points).any(): self.__record_pcl_msg(ros_topic=ros_topic, points=points, reflectance=reflectance, pcl_ts=pcl_ts[i], frame_id=frame_id) if self.request['preview']: break self.topic_active[ros_topic] = False