Skip to content

Commit 87da6fd

Browse files
committed
Merge branch 'main' into feature/jazzy-ubuntu2404-devcontainer
2 parents 573a192 + 29f0423 commit 87da6fd

File tree

15 files changed

+75
-101
lines changed

15 files changed

+75
-101
lines changed

bitbots_behavior/bitbots_blackboard/bitbots_blackboard/capsules/costmap_capsule.py

+4-4
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
import math
2-
from typing import List, Optional, Tuple
2+
from typing import Optional
33

44
import numpy as np
55
import tf2_ros as tf2
@@ -132,7 +132,7 @@ def get_pass_regions(self) -> np.ndarray:
132132
# Smooth obstacle map
133133
return gaussian_filter(costmap, pass_smooth)
134134

135-
def field_2_costmap_coord(self, x: float, y: float) -> Tuple[int, int]:
135+
def field_2_costmap_coord(self, x: float, y: float) -> tuple[int, int]:
136136
"""
137137
Converts a field position to the corresponding indices for the costmap.
138138
@@ -209,7 +209,7 @@ def calc_base_costmap(self) -> None:
209209
0 : self.field_width + self.map_margin * 2 : (self.field_width + self.map_margin * 2) * 10j, # type: ignore[misc]
210210
]
211211

212-
fix_points: List[Tuple[Tuple[float, float], float]] = []
212+
fix_points: list[tuple[tuple[float, float], float]] = []
213213

214214
# Add base points
215215
fix_points.extend(
@@ -284,7 +284,7 @@ def calc_base_costmap(self) -> None:
284284
self.base_costmap = base_costmap
285285
self.costmap = self.base_costmap.copy()
286286

287-
def get_gradient_at_field_position(self, x: float, y: float) -> Tuple[float, float]:
287+
def get_gradient_at_field_position(self, x: float, y: float) -> tuple[float, float]:
288288
"""
289289
Gets the gradient tuple at a given field position
290290
:param x: Field coordinate in the x direction

bitbots_behavior/bitbots_blackboard/bitbots_blackboard/capsules/team_data_capsule.py

+5-5
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
from typing import List, Literal, Optional, Tuple
1+
from typing import Literal, Optional
22

33
import numpy as np
44
from bitbots_utils.utils import get_parameters_from_other_node
@@ -142,7 +142,7 @@ def set_action(self, action: int) -> None:
142142
self.strategy.action = action
143143
self.action_update = self._node.get_clock().now().nanoseconds / 1e9
144144

145-
def get_action(self) -> Tuple[int, float]:
145+
def get_action(self) -> tuple[int, float]:
146146
return self.strategy.action, self.action_update
147147

148148
def set_role(self, role: Literal["goalie", "offense", "defense"]) -> None:
@@ -154,7 +154,7 @@ def set_role(self, role: Literal["goalie", "offense", "defense"]) -> None:
154154
self.strategy.role = self.roles_mapping[role]
155155
self.role_update = self._node.get_clock().now().nanoseconds / 1e9
156156

157-
def get_role(self) -> Tuple[int, float]:
157+
def get_role(self) -> tuple[int, float]:
158158
return self.strategy.role, self.role_update
159159

160160
def set_kickoff_strategy(
@@ -164,10 +164,10 @@ def set_kickoff_strategy(
164164
self.strategy.offensive_side = strategy
165165
self.strategy_update = self._node.get_clock().now().nanoseconds / 1e9
166166

167-
def get_kickoff_strategy(self) -> Tuple[int, float]:
167+
def get_kickoff_strategy(self) -> tuple[int, float]:
168168
return self.strategy.offensive_side, self.strategy_update
169169

170-
def get_active_teammate_poses(self, count_goalies: bool = False) -> List[Pose]:
170+
def get_active_teammate_poses(self, count_goalies: bool = False) -> list[Pose]:
171171
"""Returns the poses of all playing robots"""
172172
poses = []
173173
data: TeamData

bitbots_behavior/bitbots_blackboard/bitbots_blackboard/capsules/world_model_capsule.py

+11-12
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,4 @@
11
import math
2-
from typing import Tuple
32

43
import numpy as np
54
import tf2_ros as tf2
@@ -90,7 +89,7 @@ def ball_has_been_seen(self) -> bool:
9089
"""Returns true if we or a teammate are reasonably sure that we have seen the ball"""
9190
return self.ball_seen_self() or self._blackboard.team_data.teammate_ball_is_valid()
9291

93-
def get_ball_position_xy(self) -> Tuple[float, float]:
92+
def get_ball_position_xy(self) -> tuple[float, float]:
9493
"""Return the ball saved in the map frame, meaning the absolute position of the ball on the field"""
9594
ball = self.get_best_ball_point_stamped()
9695
return ball.point.x, ball.point.y
@@ -117,7 +116,7 @@ def get_best_ball_point_stamped(self) -> PointStamped:
117116
self.debug_publisher_which_ball.publish(Header(stamp=own_ball.header.stamp, frame_id="own_ball_map"))
118117
return own_ball
119118

120-
def get_ball_position_uv(self) -> Tuple[float, float]:
119+
def get_ball_position_uv(self) -> tuple[float, float]:
121120
"""
122121
Returns the ball position relative to the robot in the base_footprint frame.
123122
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:
183182
# Goal #
184183
########
185184

186-
def get_map_based_opp_goal_center_uv(self) -> Tuple[float, float]:
185+
def get_map_based_opp_goal_center_uv(self) -> tuple[float, float]:
187186
x, y = self.get_map_based_opp_goal_center_xy()
188187
return self.get_uv_from_xy(x, y)
189188

190-
def get_map_based_opp_goal_center_xy(self) -> Tuple[float, float]:
189+
def get_map_based_opp_goal_center_xy(self) -> tuple[float, float]:
191190
return self.field_length / 2, 0.0
192191

193-
def get_map_based_own_goal_center_uv(self) -> Tuple[float, float]:
192+
def get_map_based_own_goal_center_uv(self) -> tuple[float, float]:
194193
x, y = self.get_map_based_own_goal_center_xy()
195194
return self.get_uv_from_xy(x, y)
196195

197-
def get_map_based_own_goal_center_xy(self) -> Tuple[float, float]:
196+
def get_map_based_own_goal_center_xy(self) -> tuple[float, float]:
198197
return -self.field_length / 2, 0.0
199198

200199
def get_map_based_opp_goal_angle_from_ball(self) -> float:
@@ -210,19 +209,19 @@ def get_map_based_opp_goal_angle(self) -> float:
210209
x, y = self.get_map_based_opp_goal_center_uv()
211210
return math.atan2(y, x)
212211

213-
def get_map_based_opp_goal_left_post_uv(self) -> Tuple[float, float]:
212+
def get_map_based_opp_goal_left_post_uv(self) -> tuple[float, float]:
214213
x, y = self.get_map_based_opp_goal_center_xy()
215214
return self.get_uv_from_xy(x, y - self.goal_width / 2)
216215

217-
def get_map_based_opp_goal_right_post_uv(self) -> Tuple[float, float]:
216+
def get_map_based_opp_goal_right_post_uv(self) -> tuple[float, float]:
218217
x, y = self.get_map_based_opp_goal_center_xy()
219218
return self.get_uv_from_xy(x, y + self.goal_width / 2)
220219

221220
########
222221
# Pose #
223222
########
224223

225-
def get_current_position(self) -> Tuple[float, float, float]:
224+
def get_current_position(self) -> tuple[float, float, float]:
226225
"""
227226
Returns the current position on the field as determined by the localization.
228227
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:
261260
# Common #
262261
##########
263262

264-
def get_uv_from_xy(self, x: float, y: float) -> Tuple[float, float]:
263+
def get_uv_from_xy(self, x: float, y: float) -> tuple[float, float]:
265264
"""Returns the relativ positions of the robot to this absolute position"""
266265
current_position = self.get_current_position()
267266
x2 = x - current_position[0]
@@ -271,7 +270,7 @@ def get_uv_from_xy(self, x: float, y: float) -> Tuple[float, float]:
271270
v = math.cos(theta) * y2 - math.sin(theta) * x2
272271
return u, v
273272

274-
def get_xy_from_uv(self, u: float, v: float) -> Tuple[float, float]:
273+
def get_xy_from_uv(self, u: float, v: float) -> tuple[float, float]:
275274
"""Returns the absolute position from the given relative position to the robot"""
276275
pos_x, pos_y, theta = self.get_current_position()
277276
angle = math.atan2(v, u) + theta

bitbots_misc/bitbots_tts/bitbots_tts/tts.py

+2-3
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,6 @@
44
import subprocess
55
import time
66
import traceback
7-
from typing import List, Tuple
87

98
import rclpy
109
import requests
@@ -44,7 +43,7 @@ def __init__(self) -> None:
4443
super().__init__("tts_speaker")
4544

4645
# Class Variables
47-
self.prio_queue: List[Tuple[str, int]] = []
46+
self.prio_queue: list[tuple[str, int]] = []
4847
self.speak_enabled = None
4948
self.print_say = None
5049
self.message_level = None
@@ -77,7 +76,7 @@ def __init__(self) -> None:
7776
# Start processing the queue
7877
self.create_timer(0.1, self.run_speaker, callback_group=MutuallyExclusiveCallbackGroup())
7978

80-
def on_set_parameters(self, parameters: List[Parameter]) -> SetParametersResult:
79+
def on_set_parameters(self, parameters: list[Parameter]) -> SetParametersResult:
8180
"""Callback for parameter changes."""
8281
for parameter in parameters:
8382
if parameter.name == "print":

bitbots_misc/bitbots_utils/bitbots_utils/utils.py

+13-16
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
import os
2-
from typing import Any, Dict, List
2+
from typing import Any
33

44
import rclpy
55
import yaml
@@ -24,7 +24,7 @@ def read_urdf(robot_name: str) -> str:
2424
return urdf
2525

2626

27-
def load_moveit_parameter(robot_name: str) -> List[ParameterMsg]:
27+
def load_moveit_parameter(robot_name: str) -> list[ParameterMsg]:
2828
moveit_parameters = get_parameters_from_plain_yaml(
2929
f"{get_package_share_directory(f'{robot_name}_moveit_config')}/config/kinematics.yaml",
3030
"robot_description_kinematics.",
@@ -44,7 +44,7 @@ def load_moveit_parameter(robot_name: str) -> List[ParameterMsg]:
4444
return moveit_parameters
4545

4646

47-
def get_parameters_from_ros_yaml(node_name: str, parameter_file: str, use_wildcard: bool) -> List[ParameterMsg]:
47+
def get_parameters_from_ros_yaml(node_name: str, parameter_file: str, use_wildcard: bool) -> list[ParameterMsg]:
4848
# Remove leading slash and namespaces
4949
with open(parameter_file) as f:
5050
param_file = yaml.safe_load(f)
@@ -70,24 +70,21 @@ def get_parameters_from_ros_yaml(node_name: str, parameter_file: str, use_wildca
7070
return parse_parameter_dict(namespace="", parameter_dict=param_dict)
7171

7272

73-
def get_parameters_from_plain_yaml(parameter_file, namespace="") -> List[ParameterMsg]:
73+
def get_parameters_from_plain_yaml(parameter_file, namespace="") -> list[ParameterMsg]:
7474
with open(parameter_file) as f:
7575
param_dict = yaml.safe_load(f)
7676
return parse_parameter_dict(namespace=namespace, parameter_dict=param_dict)
7777

7878

79-
def get_parameter_dict(node: Node, prefix: str) -> Dict:
79+
def get_parameter_dict(node: Node, prefix: str) -> dict:
8080
"""
8181
Get a dictionary of parameters from a node.
8282
8383
:param node: Node to get parameters from
84-
:type node: Node
8584
:param prefix: Prefix for the nesting of the parameter query (e.g. 'body.nice_param.index' could have the prefix 'body')
86-
:type prefix: str
8785
:return: Dictionary of parameters without prefix nesting
88-
:rtype: Dict
8986
"""
90-
parameter_config: Dict[str, Parameter] = node.get_parameters_by_prefix(prefix)
87+
parameter_config: dict[str, Parameter] = node.get_parameters_by_prefix(prefix)
9188
config = dict()
9289
for param in parameter_config.values():
9390
# Split separated keys into nested dicts
@@ -112,8 +109,8 @@ def get_parameter_dict(node: Node, prefix: str) -> Dict:
112109

113110

114111
def get_parameters_from_other_node(
115-
own_node: Node, other_node_name: str, parameter_names: List[str], service_timeout_sec: float = 20.0
116-
) -> Dict:
112+
own_node: Node, other_node_name: str, parameter_names: list[str], service_timeout_sec: float = 20.0
113+
) -> dict:
117114
"""
118115
Used to receive parameters from other running nodes.
119116
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(
135132

136133

137134
def get_parameters_from_other_node_sync(
138-
own_node: Node, other_node_name: str, parameter_names: List[str], service_timeout_sec: float = 20.0
139-
) -> Dict:
135+
own_node: Node, other_node_name: str, parameter_names: list[str], service_timeout_sec: float = 20.0
136+
) -> dict:
140137
"""
141138
Used to receive parameters from other running nodes. It does not use async internally.
142139
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(
159156
def set_parameters_of_other_node(
160157
own_node: Node,
161158
other_node_name: str,
162-
parameter_names: List[str],
163-
parameter_values: List[Any],
159+
parameter_names: list[str],
160+
parameter_values: list[Any],
164161
service_timeout_sec: float = 20.0,
165-
) -> List[bool]:
162+
) -> list[bool]:
166163
"""
167164
Used to set parameters of another running node.
168165
Returns a list of booleans indicating success or failure.

bitbots_motion/bitbots_hcm/bitbots_hcm/hcm_dsd/hcm_blackboard.py

+3-3
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
from typing import List, Optional
1+
from typing import Optional
22

33
import numpy
44
from bitbots_utils.utils import get_parameters_from_other_node_sync
@@ -117,8 +117,8 @@ def __init__(self, node: Node):
117117

118118
# Pressure sensors
119119
# Initialize values high to prevent wrongly thinking the robot is picked up during start or in simulation
120-
self.pressures: List[float] = [100.0] * 8
121-
self.previous_pressures: List[float] = self.pressures.copy()
120+
self.pressures: list[float] = [100.0] * 8
121+
self.previous_pressures: list[float] = self.pressures.copy()
122122
self.last_different_pressure_state_time: Optional[Time] = None
123123

124124
# Diagnostics state

bitbots_team_communication/bitbots_team_communication/bitbots_team_communication/bitbots_team_communication.py

+3-3
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@
33
import socket
44
import struct
55
import threading
6-
from typing import List, Optional, Tuple
6+
from typing import Optional
77

88
import rclpy
99
from ament_index_python.packages import get_package_share_directory
@@ -84,8 +84,8 @@ def set_state_defaults(self):
8484
self.cmd_vel: Optional[Twist] = None
8585
self.cmd_vel_time = Time(clock_type=self.node.get_clock().clock_type)
8686
self.ball: Optional[PointStamped] = None
87-
self.ball_velocity: Tuple[float, float, float] = (0.0, 0.0, 0.0)
88-
self.ball_covariance: List[double] = []
87+
self.ball_velocity: tuple[float, float, float] = (0.0, 0.0, 0.0)
88+
self.ball_covariance: list[double] = []
8989
self.strategy: Optional[Strategy] = None
9090
self.strategy_time = Time(clock_type=self.node.get_clock().clock_type)
9191
self.time_to_ball: Optional[float] = None

bitbots_team_communication/bitbots_team_communication/bitbots_team_communication/communication.py

+2-2
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
import socket
22
from ipaddress import IPv4Address
3-
from typing import List, Optional
3+
from typing import Optional
44

55
from rclpy.node import Node
66

@@ -15,7 +15,7 @@ def __init__(self, node: Node, logger, team_id, robot_id):
1515

1616
if self.target_ip.is_loopback:
1717
# local mode on loopback device, bind to port depending on bot id and team id
18-
local_target_ports: List[int] = node.get_parameter("local_target_ports").value
18+
local_target_ports: list[int] = node.get_parameter("local_target_ports").value
1919
self.target_ports = [port + 10 * team_id for port in local_target_ports]
2020
self.receive_port = self.target_ports[robot_id - 1]
2121
else:

bitbots_team_communication/bitbots_team_communication/bitbots_team_communication/converter/message_to_team_data_converter.py

+2-2
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
from typing import Iterable, Sequence, Tuple
1+
from typing import Iterable, Sequence
22

33
import numpy as np
44
import transforms3d
@@ -85,7 +85,7 @@ def convert_robot_pose(self, message_robot_pose: Proto.Robot) -> PoseWithCovaria
8585

8686
return robot
8787

88-
def convert_to_quat(self, euler_angles: Tuple[float, float, float]):
88+
def convert_to_quat(self, euler_angles: tuple[float, float, float]):
8989
return transforms3d.euler.euler2quat(*euler_angles)
9090

9191
def convert_to_row_major_covariance(

bitbots_team_communication/bitbots_team_communication/bitbots_team_communication/converter/state_to_message_converter.py

+2-2
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
import math
2-
from typing import Callable, Optional, Tuple
2+
from typing import Callable, Optional
33

44
import numpy as np
55
import transforms3d
@@ -67,7 +67,7 @@ def convert_target_position(target_position: Optional[PoseStamped], message):
6767

6868
def convert_ball_position(
6969
ball_position: Optional[PointStamped],
70-
ball_velocity: Tuple[float, float, float],
70+
ball_velocity: tuple[float, float, float],
7171
ball_covariance: Float64[np.ndarray, "36"],
7272
message,
7373
):

0 commit comments

Comments
 (0)