diff --git a/perception_dataset/rosbag2/rosbag2_to_non_annotated_t4_converter.py b/perception_dataset/rosbag2/rosbag2_to_non_annotated_t4_converter.py index 29df6c0c..67ff9478 100644 --- a/perception_dataset/rosbag2/rosbag2_to_non_annotated_t4_converter.py +++ b/perception_dataset/rosbag2/rosbag2_to_non_annotated_t4_converter.py @@ -351,9 +351,6 @@ def _convert(self) -> None: if self._with_vehicle_status: self._convert_vehicle_state() - if self._with_vehicle_status: - self._convert_vehicle_state() - def _calc_start_timestamp(self) -> float: if self._start_timestamp < sys.float_info.epsilon: start_timestamp = self._bag_reader.start_timestamp + self._skip_timestamp diff --git a/perception_dataset/utils/rosbag2.py b/perception_dataset/utils/rosbag2.py index 1e8ed149..a98fc8fc 100644 --- a/perception_dataset/utils/rosbag2.py +++ b/perception_dataset/utils/rosbag2.py @@ -169,8 +169,7 @@ def pointcloud_msg_to_numpy(pointcloud_msg: PointCloud2) -> NDArray: points = point_cloud2_to_array(pointcloud_msg) # Extract the x, y, z coordinates and additional fields if available - xyz = points["xyz"] - points_arr = xyz + points_arr = points["xyz"] if "intensity" in points.keys(): intensity = points["intensity"].astype(np.float32) points_arr = np.hstack((points_arr, intensity))