Skip to content

Commit

Permalink
Add types to qos.py (#1255)
Browse files Browse the repository at this point in the history
* Add types to qos.py

Signed-off-by: Michael Carlstrom <[email protected]>

* Add missing default value

Signed-off-by: Michael Carlstrom <[email protected]>

* TypeAlias 3.8

Signed-off-by: Michael Carlstrom <[email protected]>

* Flake8 fixes and simplification

Signed-off-by: Michael Carlstrom <[email protected]>

* Fix depth=0 error

Signed-off-by: Michael Carlstrom <[email protected]>

* Fix depth=0 error

Signed-off-by: Michael Carlstrom <[email protected]>

* combine error message

Signed-off-by: Michael Carlstrom <[email protected]>

* revert to is None

Signed-off-by: Michael Carlstrom <[email protected]>

* revert to is None

Signed-off-by: Michael Carlstrom <[email protected]>

* Fix 0 falsey

Signed-off-by: Michael Carlstrom <[email protected]>

* flip self.depth

Signed-off-by: Michael Carlstrom <[email protected]>

* replace or with ternary

Signed-off-by: Michael Carlstrom <[email protected]>

---------

Signed-off-by: Michael Carlstrom <[email protected]>
Signed-off-by: Michael Carlstrom <[email protected]>
Co-authored-by: Shane Loretz <[email protected]>
  • Loading branch information
InvincibleRMC and sloretz authored Aug 7, 2024
1 parent 8999302 commit 63145fe
Show file tree
Hide file tree
Showing 2 changed files with 99 additions and 76 deletions.
6 changes: 3 additions & 3 deletions rclpy/rclpy/duration.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy


class DurationType(Protocol):
class DurationHandle(Protocol):
"""Type alias of _rclpy.rcl_duration_t."""

nanoseconds: int
Expand All @@ -41,7 +41,7 @@ def __init__(self, *, seconds: Union[int, float] = 0, nanoseconds: int = 0):
# pybind11 would raise TypeError, but we want OverflowError
raise OverflowError(
'Total nanoseconds value is too large to store in C duration.')
self._duration_handle: DurationType = _rclpy.rcl_duration_t(total_nanoseconds)
self._duration_handle: DurationHandle = _rclpy.rcl_duration_t(total_nanoseconds)

@property
def nanoseconds(self) -> int:
Expand Down Expand Up @@ -106,7 +106,7 @@ def from_msg(cls, msg: builtin_interfaces.msg.Duration) -> 'Duration':
raise TypeError('Must pass a builtin_interfaces.msg.Duration object')
return cls(seconds=msg.sec, nanoseconds=msg.nanosec)

def get_c_duration(self) -> DurationType:
def get_c_duration(self) -> DurationHandle:
return self._duration_handle


Expand Down
Loading

0 comments on commit 63145fe

Please sign in to comment.