Skip to content

Commit

Permalink
PEP 585 compliance (#67)
Browse files Browse the repository at this point in the history
  • Loading branch information
Flova authored Jan 20, 2025
1 parent 595b5d6 commit 7c3536e
Show file tree
Hide file tree
Showing 3 changed files with 9 additions and 9 deletions.
6 changes: 3 additions & 3 deletions ipm_image_node/test/test_ipm.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
# See the License for the specific language governing permissions and
# limitations under the License.

from typing import List, Optional, Tuple
from typing import Optional

from cv_bridge import CvBridge
from geometry_msgs.msg import TransformStamped
Expand Down Expand Up @@ -48,7 +48,7 @@ def standard_ipm_image_test_case(
input_topic: str,
input_msg: Image,
output_topic: str,
mode: str = 'mask') -> Tuple[PointCloud2, Image]:
mode: str = 'mask') -> tuple[PointCloud2, Image]:
# Init ros
rclpy.init()
# Create IPM node
Expand All @@ -64,7 +64,7 @@ def standard_ipm_image_test_case(
TFMessage, 'tf', 10)

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

# Create a callback with sets this reference
def callback(msg):
Expand Down
4 changes: 2 additions & 2 deletions ipm_library/ipm_library/ipm.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
# See the License for the specific language governing permissions and
# limitations under the License.

from typing import Optional, Tuple
from typing import Optional

from builtin_interfaces.msg import Time
from ipm_library import utils
Expand Down Expand Up @@ -130,7 +130,7 @@ def map_points(
points: np.ndarray,
time: Time,
plane_frame_id: Optional[str] = None,
output_frame_id: Optional[str] = None) -> Tuple[Header, np.ndarray]:
output_frame_id: Optional[str] = None) -> tuple[Header, np.ndarray]:
"""
Map image points onto a given plane using the latest CameraInfo intrinsics.
Expand Down
8 changes: 4 additions & 4 deletions ipm_library/ipm_library/utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
# See the License for the specific language governing permissions and
# limitations under the License.

from typing import Optional, Tuple
from typing import Optional

from builtin_interfaces.msg import Time
import cv2
Expand All @@ -25,7 +25,7 @@
import tf2_ros


def plane_general_to_point_normal(plane: Plane) -> Tuple[np.ndarray, np.ndarray]:
def plane_general_to_point_normal(plane: Plane) -> tuple[np.ndarray, np.ndarray]:
"""
Convert general plane form to point normal form.
Expand All @@ -44,12 +44,12 @@ def plane_general_to_point_normal(plane: Plane) -> Tuple[np.ndarray, np.ndarray]


def transform_plane_to_frame(
plane: Tuple[np.ndarray, np.ndarray],
plane: tuple[np.ndarray, np.ndarray],
input_frame: str,
output_frame: str,
time: Time,
buffer: tf2_ros.Buffer,
timeout: Optional[Duration] = None) -> Tuple[np.ndarray, np.ndarray]:
timeout: Optional[Duration] = None) -> tuple[np.ndarray, np.ndarray]:
"""
Transform a plane from one frame to another.
Expand Down

0 comments on commit 7c3536e

Please sign in to comment.