Skip to content

Commit

Permalink
Fix received typos
Browse files Browse the repository at this point in the history
  • Loading branch information
Kotochleb committed Oct 30, 2024
1 parent 4c0f666 commit 0975852
Showing 1 changed file with 7 additions and 7 deletions.
14 changes: 7 additions & 7 deletions happypose_ros/happypose_ros/camera_wrapper.py
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,7 @@ def __init__(
# Register callback depending on the configuration
self._image_approx_time_sync.registerCallback(self._on_image_data_cb)

def data_recieved_guarded(func: Callable[..., RetType]) -> Callable[..., RetType]:
def data_received_guarded(func: Callable[..., RetType]) -> Callable[..., RetType]:
"""Decorator, checks if data was already received.
:param func: Function to wrap.
Expand All @@ -101,14 +101,14 @@ def data_recieved_guarded(func: Callable[..., RetType]) -> Callable[..., RetType
:rtype: Callable[..., RetType]
"""

def _data_recieved_guarded_inner(self, *args, **kwargs) -> RetType:
def _data_received_guarded_inner(self, *args, **kwargs) -> RetType:
if self._image is None and self._camera_info is None:
raise RuntimeError(
f"No data received yet from the camera '{self._camera_name}'!"
)
return func(self, *args, **kwargs)

return _data_recieved_guarded_inner
return _data_received_guarded_inner

def _validate_k_matrix(self, k_arr: npt.NDArray[np.float64]) -> bool:
"""Performs basic check of the structure of intrinsic matrix.
Expand Down Expand Up @@ -156,7 +156,7 @@ def ready(self) -> bool:
"""
return self._image is not None

@data_recieved_guarded
@data_received_guarded
def get_last_image_frame_id(self) -> str:
"""Returns frame id associated with the last received image.
Expand All @@ -166,7 +166,7 @@ def get_last_image_frame_id(self) -> str:
"""
return self._image.header.frame_id

@data_recieved_guarded
@data_received_guarded
def get_last_image_stamp(self) -> Time:
"""Returns time stamp associated with last received image.
Expand All @@ -176,7 +176,7 @@ def get_last_image_stamp(self) -> Time:
"""
return Time.from_msg(self._image.header.stamp)

@data_recieved_guarded
@data_received_guarded
def get_last_rgb_image(self) -> npt.NDArray[np.uint8]:
"""Returns last received color image.
Expand All @@ -197,7 +197,7 @@ def get_last_rgb_image(self) -> npt.NDArray[np.uint8]:
)
return encoder(self._image, desired_encoding)

@data_recieved_guarded
@data_received_guarded
def get_last_k_matrix(self) -> npt.NDArray[np.float64]:
"""Returns intrinsic matrix associated with last received camera info message.
Expand Down

0 comments on commit 0975852

Please sign in to comment.