Skip to content

Commit

Permalink
Merge pull request #18 from ros-sports/typing/PEP585_compliance
Browse files Browse the repository at this point in the history
PEP585 compliance
  • Loading branch information
Flova authored Jan 20, 2025
2 parents 3cea93e + d3bc2c4 commit efa4d84
Show file tree
Hide file tree
Showing 5 changed files with 12 additions and 20 deletions.
4 changes: 1 addition & 3 deletions soccer_ipm/soccer_ipm/msgs/goalpost.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,6 @@
# See the License for the specific language governing permissions and
# limitations under the License.

from typing import Tuple

from ipm_library.exceptions import NoIntersectionError
from ipm_library.ipm import IPM
from rclpy.impl.rcutils_logger import RcutilsLogger
Expand All @@ -28,7 +26,7 @@ def map_goalpost_array(
output_frame: str,
logger: RcutilsLogger,
footpoint_out_of_image_threshold: float,
object_default_dimensions: Tuple[float, float, float]) -> sv3dm.GoalpostArray:
object_default_dimensions: tuple[float, float, float]) -> sv3dm.GoalpostArray:
"""
Map a given array of 2D goal post detections onto the field plane.
Expand Down
14 changes: 6 additions & 8 deletions soccer_ipm/soccer_ipm/msgs/markings.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,6 @@
# See the License for the specific language governing permissions and
# limitations under the License.

from typing import List

from geometry_msgs.msg import Vector3
from ipm_library.exceptions import NoIntersectionError
from ipm_library.ipm import IPM
Expand Down Expand Up @@ -66,10 +64,10 @@ def map_marking_array(

def map_marking_intersections(
header: Header,
intersections_2d: List[sv2dm.MarkingIntersection],
intersections_2d: list[sv2dm.MarkingIntersection],
ipm: IPM,
output_frame: str,
logger: RcutilsLogger) -> List[sv3dm.MarkingIntersection]:
logger: RcutilsLogger) -> list[sv3dm.MarkingIntersection]:
"""
Map a given list of 2D field marking intersections onto the field plane.
Expand Down Expand Up @@ -132,10 +130,10 @@ def map_marking_intersections(

def map_marking_segments(
header: Header,
marking_segments_2d: List[sv2dm.MarkingSegment],
marking_segments_2d: list[sv2dm.MarkingSegment],
ipm: IPM,
output_frame: str,
logger: RcutilsLogger) -> List[sv3dm.MarkingSegment]:
logger: RcutilsLogger) -> list[sv3dm.MarkingSegment]:
"""
Map a given list of 2D field marking segments onto the field plane.
Expand Down Expand Up @@ -187,10 +185,10 @@ def map_marking_segments(

def map_marking_ellipses(
header: Header,
ellipses_2d: List[sv2dm.MarkingEllipse],
ellipses_2d: list[sv2dm.MarkingEllipse],
ipm: IPM,
output_frame: str,
logger: RcutilsLogger) -> List[sv3dm.MarkingEllipse]:
logger: RcutilsLogger) -> list[sv3dm.MarkingEllipse]:
"""
Map a given list of 2D field marking ellipses onto the field plane.
Expand Down
4 changes: 1 addition & 3 deletions soccer_ipm/soccer_ipm/msgs/obstacles.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,6 @@
# See the License for the specific language governing permissions and
# limitations under the License.

from typing import Tuple

from ipm_library.exceptions import NoIntersectionError
from ipm_library.ipm import IPM
from rclpy.impl.rcutils_logger import RcutilsLogger
Expand All @@ -28,7 +26,7 @@ def map_obstacle_array(
output_frame: str,
logger: RcutilsLogger,
footpoint_out_of_image_threshold: float,
object_default_dimensions: Tuple[float, float, float]) -> sv3dm.ObstacleArray:
object_default_dimensions: tuple[float, float, float]) -> sv3dm.ObstacleArray:
"""
Map a given array of 2D obstacle detections onto the field plane.
Expand Down
4 changes: 1 addition & 3 deletions soccer_ipm/soccer_ipm/msgs/robots.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,6 @@
# See the License for the specific language governing permissions and
# limitations under the License.

from typing import Tuple

from ipm_library.exceptions import NoIntersectionError
from ipm_library.ipm import IPM
from rclpy.impl.rcutils_logger import RcutilsLogger
Expand All @@ -28,7 +26,7 @@ def map_robot_array(
output_frame: str,
logger: RcutilsLogger,
footpoint_out_of_image_threshold: float,
object_default_dimensions: Tuple[float, float, float]) -> sv3dm.RobotArray:
object_default_dimensions: tuple[float, float, float]) -> sv3dm.RobotArray:
"""
Map a given array of 2D robot detections onto the field plane.
Expand Down
6 changes: 3 additions & 3 deletions soccer_ipm/test/test_ipm.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
# limitations under the License.

import math
from typing import List, Optional, Tuple, Union
from typing import Optional, Union

from geometry_msgs.msg import TransformStamped
import numpy as np
Expand Down Expand Up @@ -67,7 +67,7 @@ def standard_ipm_test_case(
input_topic: str,
input_msg: SV2DARR,
output_msg_type: type,
output_topic: str) -> Tuple[SV3DARR, SV2DARR]:
output_topic: str) -> tuple[SV3DARR, SV2DARR]:
# Init ros
rclpy.init()
# Create IPM node
Expand All @@ -83,7 +83,7 @@ def standard_ipm_test_case(
TFMessage, 'tf', 10)

# Create a shared reference to the recived message in the local scope
received_msg: List[Optional[output_msg_type]] = [None]
received_msg: list[Optional[output_msg_type]] = [None]

# Create a callback with sets this reference
def callback(msg):
Expand Down

0 comments on commit efa4d84

Please sign in to comment.