diff --git a/bitbots_behavior/bitbots_blackboard/bitbots_blackboard/capsules/costmap_capsule.py b/bitbots_behavior/bitbots_blackboard/bitbots_blackboard/capsules/costmap_capsule.py index 466381dc0..acd35029e 100644 --- a/bitbots_behavior/bitbots_blackboard/bitbots_blackboard/capsules/costmap_capsule.py +++ b/bitbots_behavior/bitbots_blackboard/bitbots_blackboard/capsules/costmap_capsule.py @@ -1,5 +1,5 @@ import math -from typing import List, Optional, Tuple +from typing import Optional import numpy as np import tf2_ros as tf2 @@ -132,7 +132,7 @@ def get_pass_regions(self) -> np.ndarray: # Smooth obstacle map return gaussian_filter(costmap, pass_smooth) - def field_2_costmap_coord(self, x: float, y: float) -> Tuple[int, int]: + def field_2_costmap_coord(self, x: float, y: float) -> tuple[int, int]: """ Converts a field position to the corresponding indices for the costmap. @@ -209,7 +209,7 @@ def calc_base_costmap(self) -> None: 0 : self.field_width + self.map_margin * 2 : (self.field_width + self.map_margin * 2) * 10j, # type: ignore[misc] ] - fix_points: List[Tuple[Tuple[float, float], float]] = [] + fix_points: list[tuple[tuple[float, float], float]] = [] # Add base points fix_points.extend( @@ -284,7 +284,7 @@ def calc_base_costmap(self) -> None: self.base_costmap = base_costmap self.costmap = self.base_costmap.copy() - def get_gradient_at_field_position(self, x: float, y: float) -> Tuple[float, float]: + def get_gradient_at_field_position(self, x: float, y: float) -> tuple[float, float]: """ Gets the gradient tuple at a given field position :param x: Field coordinate in the x direction diff --git a/bitbots_behavior/bitbots_blackboard/bitbots_blackboard/capsules/team_data_capsule.py b/bitbots_behavior/bitbots_blackboard/bitbots_blackboard/capsules/team_data_capsule.py index 3fea4f71f..98d459fe6 100644 --- a/bitbots_behavior/bitbots_blackboard/bitbots_blackboard/capsules/team_data_capsule.py +++ b/bitbots_behavior/bitbots_blackboard/bitbots_blackboard/capsules/team_data_capsule.py @@ -1,4 +1,4 @@ -from typing import List, Literal, Optional, Tuple +from typing import Literal, Optional import numpy as np from bitbots_utils.utils import get_parameters_from_other_node @@ -142,7 +142,7 @@ def set_action(self, action: int) -> None: self.strategy.action = action self.action_update = self._node.get_clock().now().nanoseconds / 1e9 - def get_action(self) -> Tuple[int, float]: + def get_action(self) -> tuple[int, float]: return self.strategy.action, self.action_update def set_role(self, role: Literal["goalie", "offense", "defense"]) -> None: @@ -154,7 +154,7 @@ def set_role(self, role: Literal["goalie", "offense", "defense"]) -> None: self.strategy.role = self.roles_mapping[role] self.role_update = self._node.get_clock().now().nanoseconds / 1e9 - def get_role(self) -> Tuple[int, float]: + def get_role(self) -> tuple[int, float]: return self.strategy.role, self.role_update def set_kickoff_strategy( @@ -164,10 +164,10 @@ def set_kickoff_strategy( self.strategy.offensive_side = strategy self.strategy_update = self._node.get_clock().now().nanoseconds / 1e9 - def get_kickoff_strategy(self) -> Tuple[int, float]: + def get_kickoff_strategy(self) -> tuple[int, float]: return self.strategy.offensive_side, self.strategy_update - def get_active_teammate_poses(self, count_goalies: bool = False) -> List[Pose]: + def get_active_teammate_poses(self, count_goalies: bool = False) -> list[Pose]: """Returns the poses of all playing robots""" poses = [] data: TeamData diff --git a/bitbots_behavior/bitbots_blackboard/bitbots_blackboard/capsules/world_model_capsule.py b/bitbots_behavior/bitbots_blackboard/bitbots_blackboard/capsules/world_model_capsule.py index 6f382ee8c..d1a9f47ab 100644 --- a/bitbots_behavior/bitbots_blackboard/bitbots_blackboard/capsules/world_model_capsule.py +++ b/bitbots_behavior/bitbots_blackboard/bitbots_blackboard/capsules/world_model_capsule.py @@ -1,5 +1,4 @@ import math -from typing import Tuple import numpy as np import tf2_ros as tf2 @@ -90,7 +89,7 @@ def ball_has_been_seen(self) -> bool: """Returns true if we or a teammate are reasonably sure that we have seen the ball""" return self.ball_seen_self() or self._blackboard.team_data.teammate_ball_is_valid() - def get_ball_position_xy(self) -> Tuple[float, float]: + def get_ball_position_xy(self) -> tuple[float, float]: """Return the ball saved in the map frame, meaning the absolute position of the ball on the field""" ball = self.get_best_ball_point_stamped() return ball.point.x, ball.point.y @@ -117,7 +116,7 @@ def get_best_ball_point_stamped(self) -> PointStamped: self.debug_publisher_which_ball.publish(Header(stamp=own_ball.header.stamp, frame_id="own_ball_map")) return own_ball - def get_ball_position_uv(self) -> Tuple[float, float]: + def get_ball_position_uv(self) -> tuple[float, float]: """ Returns the ball position relative to the robot in the base_footprint frame. U and V are returned, where positive U is forward, positive V is to the left. @@ -183,18 +182,18 @@ def forget_ball(self) -> None: # Goal # ######## - def get_map_based_opp_goal_center_uv(self) -> Tuple[float, float]: + def get_map_based_opp_goal_center_uv(self) -> tuple[float, float]: x, y = self.get_map_based_opp_goal_center_xy() return self.get_uv_from_xy(x, y) - def get_map_based_opp_goal_center_xy(self) -> Tuple[float, float]: + def get_map_based_opp_goal_center_xy(self) -> tuple[float, float]: return self.field_length / 2, 0.0 - def get_map_based_own_goal_center_uv(self) -> Tuple[float, float]: + def get_map_based_own_goal_center_uv(self) -> tuple[float, float]: x, y = self.get_map_based_own_goal_center_xy() return self.get_uv_from_xy(x, y) - def get_map_based_own_goal_center_xy(self) -> Tuple[float, float]: + def get_map_based_own_goal_center_xy(self) -> tuple[float, float]: return -self.field_length / 2, 0.0 def get_map_based_opp_goal_angle_from_ball(self) -> float: @@ -210,11 +209,11 @@ def get_map_based_opp_goal_angle(self) -> float: x, y = self.get_map_based_opp_goal_center_uv() return math.atan2(y, x) - def get_map_based_opp_goal_left_post_uv(self) -> Tuple[float, float]: + def get_map_based_opp_goal_left_post_uv(self) -> tuple[float, float]: x, y = self.get_map_based_opp_goal_center_xy() return self.get_uv_from_xy(x, y - self.goal_width / 2) - def get_map_based_opp_goal_right_post_uv(self) -> Tuple[float, float]: + def get_map_based_opp_goal_right_post_uv(self) -> tuple[float, float]: x, y = self.get_map_based_opp_goal_center_xy() return self.get_uv_from_xy(x, y + self.goal_width / 2) @@ -222,7 +221,7 @@ def get_map_based_opp_goal_right_post_uv(self) -> Tuple[float, float]: # Pose # ######## - def get_current_position(self) -> Tuple[float, float, float]: + def get_current_position(self) -> tuple[float, float, float]: """ Returns the current position on the field as determined by the localization. 0,0,0 is the center of the field looking in the direction of the opponent goal. @@ -261,7 +260,7 @@ def get_current_position_transform(self) -> TransformStamped: # Common # ########## - def get_uv_from_xy(self, x: float, y: float) -> Tuple[float, float]: + def get_uv_from_xy(self, x: float, y: float) -> tuple[float, float]: """Returns the relativ positions of the robot to this absolute position""" current_position = self.get_current_position() x2 = x - current_position[0] @@ -271,7 +270,7 @@ def get_uv_from_xy(self, x: float, y: float) -> Tuple[float, float]: v = math.cos(theta) * y2 - math.sin(theta) * x2 return u, v - def get_xy_from_uv(self, u: float, v: float) -> Tuple[float, float]: + def get_xy_from_uv(self, u: float, v: float) -> tuple[float, float]: """Returns the absolute position from the given relative position to the robot""" pos_x, pos_y, theta = self.get_current_position() angle = math.atan2(v, u) + theta diff --git a/bitbots_misc/bitbots_tts/bitbots_tts/tts.py b/bitbots_misc/bitbots_tts/bitbots_tts/tts.py index 9d5931bd3..8a8afd0c5 100755 --- a/bitbots_misc/bitbots_tts/bitbots_tts/tts.py +++ b/bitbots_misc/bitbots_tts/bitbots_tts/tts.py @@ -4,7 +4,6 @@ import subprocess import time import traceback -from typing import List, Tuple import rclpy import requests @@ -44,7 +43,7 @@ def __init__(self) -> None: super().__init__("tts_speaker") # Class Variables - self.prio_queue: List[Tuple[str, int]] = [] + self.prio_queue: list[tuple[str, int]] = [] self.speak_enabled = None self.print_say = None self.message_level = None @@ -77,7 +76,7 @@ def __init__(self) -> None: # Start processing the queue self.create_timer(0.1, self.run_speaker, callback_group=MutuallyExclusiveCallbackGroup()) - def on_set_parameters(self, parameters: List[Parameter]) -> SetParametersResult: + def on_set_parameters(self, parameters: list[Parameter]) -> SetParametersResult: """Callback for parameter changes.""" for parameter in parameters: if parameter.name == "print": diff --git a/bitbots_misc/bitbots_utils/bitbots_utils/utils.py b/bitbots_misc/bitbots_utils/bitbots_utils/utils.py index 2a187488b..ac338987a 100644 --- a/bitbots_misc/bitbots_utils/bitbots_utils/utils.py +++ b/bitbots_misc/bitbots_utils/bitbots_utils/utils.py @@ -1,5 +1,5 @@ import os -from typing import Any, Dict, List +from typing import Any import rclpy import yaml @@ -24,7 +24,7 @@ def read_urdf(robot_name: str) -> str: return urdf -def load_moveit_parameter(robot_name: str) -> List[ParameterMsg]: +def load_moveit_parameter(robot_name: str) -> list[ParameterMsg]: moveit_parameters = get_parameters_from_plain_yaml( f"{get_package_share_directory(f'{robot_name}_moveit_config')}/config/kinematics.yaml", "robot_description_kinematics.", @@ -44,7 +44,7 @@ def load_moveit_parameter(robot_name: str) -> List[ParameterMsg]: return moveit_parameters -def get_parameters_from_ros_yaml(node_name: str, parameter_file: str, use_wildcard: bool) -> List[ParameterMsg]: +def get_parameters_from_ros_yaml(node_name: str, parameter_file: str, use_wildcard: bool) -> list[ParameterMsg]: # Remove leading slash and namespaces with open(parameter_file) as f: param_file = yaml.safe_load(f) @@ -70,24 +70,21 @@ def get_parameters_from_ros_yaml(node_name: str, parameter_file: str, use_wildca return parse_parameter_dict(namespace="", parameter_dict=param_dict) -def get_parameters_from_plain_yaml(parameter_file, namespace="") -> List[ParameterMsg]: +def get_parameters_from_plain_yaml(parameter_file, namespace="") -> list[ParameterMsg]: with open(parameter_file) as f: param_dict = yaml.safe_load(f) return parse_parameter_dict(namespace=namespace, parameter_dict=param_dict) -def get_parameter_dict(node: Node, prefix: str) -> Dict: +def get_parameter_dict(node: Node, prefix: str) -> dict: """ Get a dictionary of parameters from a node. :param node: Node to get parameters from - :type node: Node :param prefix: Prefix for the nesting of the parameter query (e.g. 'body.nice_param.index' could have the prefix 'body') - :type prefix: str :return: Dictionary of parameters without prefix nesting - :rtype: Dict """ - parameter_config: Dict[str, Parameter] = node.get_parameters_by_prefix(prefix) + parameter_config: dict[str, Parameter] = node.get_parameters_by_prefix(prefix) config = dict() for param in parameter_config.values(): # Split separated keys into nested dicts @@ -112,8 +109,8 @@ def get_parameter_dict(node: Node, prefix: str) -> Dict: def get_parameters_from_other_node( - own_node: Node, other_node_name: str, parameter_names: List[str], service_timeout_sec: float = 20.0 -) -> Dict: + own_node: Node, other_node_name: str, parameter_names: list[str], service_timeout_sec: float = 20.0 +) -> dict: """ Used to receive parameters from other running nodes. Returns a dict with requested parameter name as dict key and parameter value as dict value. @@ -135,8 +132,8 @@ def get_parameters_from_other_node( def get_parameters_from_other_node_sync( - own_node: Node, other_node_name: str, parameter_names: List[str], service_timeout_sec: float = 20.0 -) -> Dict: + own_node: Node, other_node_name: str, parameter_names: list[str], service_timeout_sec: float = 20.0 +) -> dict: """ Used to receive parameters from other running nodes. It does not use async internally. It should not be used in callback functions, but it is a bit more reliable than the async version. @@ -159,10 +156,10 @@ def get_parameters_from_other_node_sync( def set_parameters_of_other_node( own_node: Node, other_node_name: str, - parameter_names: List[str], - parameter_values: List[Any], + parameter_names: list[str], + parameter_values: list[Any], service_timeout_sec: float = 20.0, -) -> List[bool]: +) -> list[bool]: """ Used to set parameters of another running node. Returns a list of booleans indicating success or failure. diff --git a/bitbots_motion/bitbots_hcm/bitbots_hcm/hcm_dsd/hcm_blackboard.py b/bitbots_motion/bitbots_hcm/bitbots_hcm/hcm_dsd/hcm_blackboard.py index b0ae2b7e9..3ac8d4dae 100644 --- a/bitbots_motion/bitbots_hcm/bitbots_hcm/hcm_dsd/hcm_blackboard.py +++ b/bitbots_motion/bitbots_hcm/bitbots_hcm/hcm_dsd/hcm_blackboard.py @@ -1,4 +1,4 @@ -from typing import List, Optional +from typing import Optional import numpy from bitbots_utils.utils import get_parameters_from_other_node_sync @@ -117,8 +117,8 @@ def __init__(self, node: Node): # Pressure sensors # Initialize values high to prevent wrongly thinking the robot is picked up during start or in simulation - self.pressures: List[float] = [100.0] * 8 - self.previous_pressures: List[float] = self.pressures.copy() + self.pressures: list[float] = [100.0] * 8 + self.previous_pressures: list[float] = self.pressures.copy() self.last_different_pressure_state_time: Optional[Time] = None # Diagnostics state diff --git a/bitbots_team_communication/bitbots_team_communication/bitbots_team_communication/bitbots_team_communication.py b/bitbots_team_communication/bitbots_team_communication/bitbots_team_communication/bitbots_team_communication.py index 79675e5a6..210164c33 100755 --- a/bitbots_team_communication/bitbots_team_communication/bitbots_team_communication/bitbots_team_communication.py +++ b/bitbots_team_communication/bitbots_team_communication/bitbots_team_communication/bitbots_team_communication.py @@ -3,7 +3,7 @@ import socket import struct import threading -from typing import List, Optional, Tuple +from typing import Optional import rclpy from ament_index_python.packages import get_package_share_directory @@ -84,8 +84,8 @@ def set_state_defaults(self): self.cmd_vel: Optional[Twist] = None self.cmd_vel_time = Time(clock_type=self.node.get_clock().clock_type) self.ball: Optional[PointStamped] = None - self.ball_velocity: Tuple[float, float, float] = (0.0, 0.0, 0.0) - self.ball_covariance: List[double] = [] + self.ball_velocity: tuple[float, float, float] = (0.0, 0.0, 0.0) + self.ball_covariance: list[double] = [] self.strategy: Optional[Strategy] = None self.strategy_time = Time(clock_type=self.node.get_clock().clock_type) self.time_to_ball: Optional[float] = None diff --git a/bitbots_team_communication/bitbots_team_communication/bitbots_team_communication/communication.py b/bitbots_team_communication/bitbots_team_communication/bitbots_team_communication/communication.py index e9ea7c535..a72e4835a 100644 --- a/bitbots_team_communication/bitbots_team_communication/bitbots_team_communication/communication.py +++ b/bitbots_team_communication/bitbots_team_communication/bitbots_team_communication/communication.py @@ -1,6 +1,6 @@ import socket from ipaddress import IPv4Address -from typing import List, Optional +from typing import Optional from rclpy.node import Node @@ -15,7 +15,7 @@ def __init__(self, node: Node, logger, team_id, robot_id): if self.target_ip.is_loopback: # local mode on loopback device, bind to port depending on bot id and team id - local_target_ports: List[int] = node.get_parameter("local_target_ports").value + local_target_ports: list[int] = node.get_parameter("local_target_ports").value self.target_ports = [port + 10 * team_id for port in local_target_ports] self.receive_port = self.target_ports[robot_id - 1] else: diff --git a/bitbots_team_communication/bitbots_team_communication/bitbots_team_communication/converter/message_to_team_data_converter.py b/bitbots_team_communication/bitbots_team_communication/bitbots_team_communication/converter/message_to_team_data_converter.py index 5f5d2fe62..e08e22b4c 100644 --- a/bitbots_team_communication/bitbots_team_communication/bitbots_team_communication/converter/message_to_team_data_converter.py +++ b/bitbots_team_communication/bitbots_team_communication/bitbots_team_communication/converter/message_to_team_data_converter.py @@ -1,4 +1,4 @@ -from typing import Iterable, Sequence, Tuple +from typing import Iterable, Sequence import numpy as np import transforms3d @@ -85,7 +85,7 @@ def convert_robot_pose(self, message_robot_pose: Proto.Robot) -> PoseWithCovaria return robot - def convert_to_quat(self, euler_angles: Tuple[float, float, float]): + def convert_to_quat(self, euler_angles: tuple[float, float, float]): return transforms3d.euler.euler2quat(*euler_angles) def convert_to_row_major_covariance( diff --git a/bitbots_team_communication/bitbots_team_communication/bitbots_team_communication/converter/state_to_message_converter.py b/bitbots_team_communication/bitbots_team_communication/bitbots_team_communication/converter/state_to_message_converter.py index e913d27df..e41d2e9a0 100644 --- a/bitbots_team_communication/bitbots_team_communication/bitbots_team_communication/converter/state_to_message_converter.py +++ b/bitbots_team_communication/bitbots_team_communication/bitbots_team_communication/converter/state_to_message_converter.py @@ -1,5 +1,5 @@ import math -from typing import Callable, Optional, Tuple +from typing import Callable, Optional import numpy as np import transforms3d @@ -67,7 +67,7 @@ def convert_target_position(target_position: Optional[PoseStamped], message): def convert_ball_position( ball_position: Optional[PointStamped], - ball_velocity: Tuple[float, float, float], + ball_velocity: tuple[float, float, float], ball_covariance: Float64[np.ndarray, "36"], message, ): diff --git a/bitbots_vision/bitbots_vision/vision.py b/bitbots_vision/bitbots_vision/vision.py index 988121470..a2c45bd48 100755 --- a/bitbots_vision/bitbots_vision/vision.py +++ b/bitbots_vision/bitbots_vision/vision.py @@ -1,6 +1,5 @@ #! /usr/bin/env python3 from copy import deepcopy -from typing import Dict, List import numpy as np import rclpy @@ -43,12 +42,12 @@ def __init__(self) -> None: yoeo.YOEOObjectManager.set_package_directory(self._package_path) - self._config: Dict = {} + self._config: dict = {} self._cv_bridge = CvBridge() self._sub_image = None - self._vision_components: List[yoeo.IVisionComponent] = [] + self._vision_components: list[yoeo.IVisionComponent] = [] # Setup reconfiguration gen.declare_params(self) @@ -76,19 +75,19 @@ def _dynamic_reconfigure_callback(self, params) -> SetParametersResult: return SetParametersResult(successful=True) - def _get_updated_config_with(self, params) -> Dict: + def _get_updated_config_with(self, params) -> dict: new_config = deepcopy(self._config) for param in params: new_config[param.name] = param.value return new_config - def _configure_vision(self, new_config: Dict) -> None: + def _configure_vision(self, new_config: dict) -> None: yoeo.YOEOObjectManager.configure(new_config) self._set_up_vision_components(new_config) self._register_subscribers(new_config) - def _set_up_vision_components(self, new_config: Dict) -> None: + def _set_up_vision_components(self, new_config: dict) -> None: self._vision_components = [] self._vision_components.append(yoeo.YOEOComponent()) @@ -111,7 +110,7 @@ def _set_up_vision_components(self, new_config: Dict) -> None: for vision_component in self._vision_components: vision_component.configure(new_config, new_config["component_debug_image_active"]) - def _register_subscribers(self, config: Dict) -> None: + def _register_subscribers(self, config: dict) -> None: self._sub_image = ros_utils.create_or_update_subscriber( self, self._config, diff --git a/bitbots_vision/bitbots_vision/vision_modules/yoeo/model_config.py b/bitbots_vision/bitbots_vision/vision_modules/yoeo/model_config.py index 32a1f6fbe..8088bb896 100644 --- a/bitbots_vision/bitbots_vision/vision_modules/yoeo/model_config.py +++ b/bitbots_vision/bitbots_vision/vision_modules/yoeo/model_config.py @@ -1,23 +1,23 @@ from os.path import join -from typing import Dict, List, Optional +from typing import Optional import yaml # type: ignore[import-untyped] class ModelConfig: - def __init__(self, config: Optional[Dict] = None): - self._config: Dict = config if config else {} + def __init__(self, config: Optional[dict] = None): + self._config: dict = config if config else {} - def get_detection_classes(self) -> List[str]: + def get_detection_classes(self) -> list[str]: return self._config["detection"]["classes"] - def get_segmentation_classes(self) -> List[str]: + def get_segmentation_classes(self) -> list[str]: return self._config["segmentation"]["classes"] def team_colors_are_provided(self) -> bool: return self._config["detection"].get("team_colors", False) - def get_robot_class_ids(self) -> List[int]: + def get_robot_class_ids(self) -> list[int]: ids = [] for i, c in enumerate(self.get_detection_classes()): if "robot" in c: diff --git a/bitbots_vision/bitbots_vision/vision_modules/yoeo/object_manager.py b/bitbots_vision/bitbots_vision/vision_modules/yoeo/object_manager.py index ea76a1026..aeb9e28d9 100644 --- a/bitbots_vision/bitbots_vision/vision_modules/yoeo/object_manager.py +++ b/bitbots_vision/bitbots_vision/vision_modules/yoeo/object_manager.py @@ -1,5 +1,5 @@ import os.path as osp -from typing import Dict, Optional, Type +from typing import Optional, Type import rclpy @@ -23,7 +23,7 @@ class YOEOObjectManager: "tvm": yoeo_handlers.YOEOHandlerTVM, } - _config: Dict = {} + _config: dict = {} _framework: str = "" _model_config: ModelConfig = ModelConfig() _model_path: str = "" @@ -72,7 +72,7 @@ def is_team_color_detection_supported(cls) -> bool: return cls._model_config.team_colors_are_provided() @classmethod - def configure(cls, config: Dict) -> None: + def configure(cls, config: dict) -> None: if not cls._package_directory_set: logger.error("Package directory not set!") @@ -107,7 +107,7 @@ def _model_files_exist(cls, framework: str, model_path: str) -> bool: return cls._HANDLERS_BY_NAME[framework].model_files_exist(model_path) @classmethod - def _configure_yoeo_instance(cls, config: Dict, framework: str, model_path: str) -> None: + def _configure_yoeo_instance(cls, config: dict, framework: str, model_path: str) -> None: if cls._new_yoeo_handler_is_needed(framework, model_path): cls._load_model_config(model_path) cls._instantiate_new_yoeo_handler(config, framework, model_path) @@ -124,7 +124,7 @@ def _load_model_config(cls, model_path: str) -> None: cls._model_config = ModelConfigLoader.load_from(model_path) @classmethod - def _instantiate_new_yoeo_handler(cls, config: Dict, framework: str, model_path: str) -> None: + def _instantiate_new_yoeo_handler(cls, config: dict, framework: str, model_path: str) -> None: cls._yoeo_instance = cls._HANDLERS_BY_NAME[framework]( config, model_path, @@ -135,5 +135,5 @@ def _instantiate_new_yoeo_handler(cls, config: Dict, framework: str, model_path: logger.info(f"Using {cls._yoeo_instance.__class__.__name__}") @classmethod - def _yoeo_parameters_have_changed(cls, new_config: Dict) -> bool: + def _yoeo_parameters_have_changed(cls, new_config: dict) -> bool: return ros_utils.config_param_change(cls._config, new_config, r"yoeo_") diff --git a/bitbots_vision/bitbots_vision/vision_modules/yoeo/utils.py b/bitbots_vision/bitbots_vision/vision_modules/yoeo/utils.py index a1a4a4c4d..15a11301d 100644 --- a/bitbots_vision/bitbots_vision/vision_modules/yoeo/utils.py +++ b/bitbots_vision/bitbots_vision/vision_modules/yoeo/utils.py @@ -1,6 +1,6 @@ from abc import ABC, abstractmethod from dataclasses import dataclass -from typing import List, Optional, Tuple +from typing import Optional import cv2 import numpy as np @@ -16,15 +16,10 @@ class ImagePreProcessorData: This dataclass is used to exchange relevant parameters of the applied image preprocessing between instances of type IImagePreProcessor and instances of type ISegmentationPostProcessor and IDetectionPostProcessor, respectively. :param padding_top: applied padding (number of pixels) at the top of the image - :type padding_top: int :param padding_bottom: applied padding (number of pixels) at the bottom of the image - :type padding_bottom: int :param padding_left: applied padding (number of pixels) at the left-hand side of the image - :type padding_left: int :param padding_right: applied padding (number of pixels) at the right-hand side of the image - :type padding_right: int :param max_dim: the larger of the two dimensions of the original unprocessed image (number of pixels) - :type max_dim: int """ padding_top: int @@ -41,12 +36,11 @@ class IImagePreProcessor(ABC): """ @abstractmethod - def configure(self, network_input_shape: Tuple[int, int]) -> None: + def configure(self, network_input_shape: tuple[int, int]) -> None: """ Allows to (re-) configure the current instance. :param network_input_shape: input shape of the YOEO network (height, width) - :type network_input_shape: Tuple[int, int] """ ... @@ -66,9 +60,7 @@ def process(self, image: np.ndarray) -> np.ndarray: Run the image pre-processing on the method's argument. :param image: the image to pre-process (axis order: height, width, channels) - :type image: np.ndarray :return: the pre-processed image (axis order: channels, height, width) - :rtype: np.ndarray """ ... @@ -92,7 +84,6 @@ def configure(self, image_preprocessor: IImagePreProcessor) -> None: Allows to (re-) configure the current instance. :param image_preprocessor: instance of IImagePreProcessor that handles the image pre-processing - :type image_preprocessor: IImagePreProcessor """ ... @@ -102,9 +93,7 @@ def process(self, segmentation: np.ndarray) -> np.ndarray: Run the segmentation post-processing on the method's argument. :param segmentation: YOEO segmentation network output (axis order: channels, height, width) - :type segmentation: np.ndarray :return: the post-processed segmentation output (axis order: height, width) - :rtype: np.ndarray """ ... @@ -122,21 +111,16 @@ def configure( output_img_size: int, conf_thresh: float, nms_thresh: float, - robot_class_ids: List[int], + robot_class_ids: list[int], ) -> None: """ Allows to (re-) configure the current instance. :param image_preprocessor: instance of IImagePreProcessor that handles the image pre-processing - :type image_preprocessor: IImagePreProcessor :param output_img_size: image size (1D) for which the detections are calculated by the YOEO network - :type output_img_size: int :param conf_thresh: class confidence threshold used in non-maximum suppression - :type conf_thresh: float :param nms_thresh: threshold used in non-maximum suppression - :type nms_thresh: float :param robot_class_ids: class ids of robot classes (required for nms across all robot classes) - :type robot_class_ids: List[int] """ ... @@ -147,26 +131,24 @@ def process(self, detections: np.ndarray) -> np.ndarray: :param detections: YOEO detection network output (axis layout: 1, number of boxes, boxes), (boxes layout: x, y, w, h, obj_conf, cond_class_conf_1, cond_class_conf_2, ...) - :type detections: np.ndarray :return: the post-processed detection output - :rtype: np.ndarray """ ... class DefaultImagePreProcessor(IImagePreProcessor): def __init__(self, network_input_shape): - self._network_input_shape_WH: Optional[Tuple[int, int]] = None # (width, height) + self._network_input_shape_WH: Optional[tuple[int, int]] = None # (width, height) self.configure(network_input_shape) # these attributes change for every image! - self._image_dimensions_HW: Tuple[int, int] = (0, 0) # (height, width) + self._image_dimensions_HW: tuple[int, int] = (0, 0) # (height, width) self._padding_top: int = 0 self._padding_bottom: int = 0 self._padding_left: int = 0 self._padding_right: int = 0 - def configure(self, network_input_shape: Tuple[int, int]) -> None: + def configure(self, network_input_shape: tuple[int, int]) -> None: # change layout from (height, width) to (width, height) self._network_input_shape_WH = network_input_shape[::-1] @@ -285,7 +267,7 @@ def __init__( output_img_size: int, conf_thresh: float, nms_thresh: float, - robot_class_ids: List[int], + robot_class_ids: list[int], ): self._image_preprocessor: IImagePreProcessor = image_preprocessor self._output_img_size: int = output_img_size @@ -313,7 +295,7 @@ def configure( output_img_size: int, conf_thresh: float, nms_thresh: float, - robot_class_ids: List[int], + robot_class_ids: list[int], ) -> None: self._image_preprocessor = image_preprocessor self._output_img_size = output_img_size @@ -379,7 +361,7 @@ def _pin_down_last_dimension_to_6(self, detections: np.ndarray) -> np.ndarray: return x - def _get_boxes_and_scores_for_nms(self, detections: np.ndarray) -> Tuple: + def _get_boxes_and_scores_for_nms(self, detections: np.ndarray) -> tuple: if self._robot_class_ids: class_offsets = np.where( self._is_robot_class(detections[:, 5:6]), self._robot_class_ids[0], detections[:, 5:6] diff --git a/bitbots_vision/bitbots_vision/vision_modules/yoeo/yoeo_handlers.py b/bitbots_vision/bitbots_vision/vision_modules/yoeo/yoeo_handlers.py index 76cd313d0..a621fe7b7 100644 --- a/bitbots_vision/bitbots_vision/vision_modules/yoeo/yoeo_handlers.py +++ b/bitbots_vision/bitbots_vision/vision_modules/yoeo/yoeo_handlers.py @@ -93,7 +93,7 @@ class YOEOHandlerTemplate(IYOEOHandler): Abstract base implementation of the IYOEOHandler interface. Actual YOEO handlers need to only implement the following two hook methods if they inherit from this template: - model_files_exist(model_directory: str) -> bool: - - _compute_new_prediction_for(self, image) -> Tuple: + - _compute_new_prediction_for(self, image) -> tuple: """ def __init__( @@ -197,9 +197,7 @@ def _compute_new_prediction_for(self, image: np.ndarray) -> tuple[np.ndarray, np Hook method to be implemented by actual YOEO handlers. :param image: the image that should be input into the network - :type image: np.ndarray :return: post-processed YOEO detections and segmentations (in this order) - :rtype: Tuple[np.ndarray, np.ndarray] """ ...