Skip to content

Commit

Permalink
Docstring specifying proper destruction and creation of Rate, Timer a…
Browse files Browse the repository at this point in the history
…nd GuardCondition (#1286)

* timer docstring

Signed-off-by: elian-WSL22H <[email protected]>

* rate docstring

Signed-off-by: elian-WSL22H <[email protected]>

* guard_condition docstring

Signed-off-by: elian-WSL22H <[email protected]>

* for happy flake8

Signed-off-by: elian-WSL22H <[email protected]>

* guard_condition with indent fixes

Co-authored-by: Tomoya Fujita <[email protected]>
Signed-off-by: Elian NEPPEL <[email protected]>

* GuardCondition create with indent fixes

Co-authored-by: Tomoya Fujita <[email protected]>
Signed-off-by: Elian NEPPEL <[email protected]>

* Revert "GuardCondition create with indent fixes"

This reverts commit fd61446.

Signed-off-by: elian-WSL22H <[email protected]>

* Revert "Revert "GuardCondition create with indent fixes""

This reverts commit 0fb83ca.

Co-authored-by: Tomoya Fujita <[email protected]>
Signed-off-by: elian-WSL22H <[email protected]>

---------

Signed-off-by: elian-WSL22H <[email protected]>
Signed-off-by: Elian NEPPEL <[email protected]>
Co-authored-by: Tomoya Fujita <[email protected]>
  • Loading branch information
2lian and fujitatomoya authored Jun 14, 2024
1 parent 8db266a commit 0926b34
Show file tree
Hide file tree
Showing 3 changed files with 41 additions and 1 deletion.
12 changes: 12 additions & 0 deletions rclpy/rclpy/guard_condition.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,12 @@
class GuardCondition:

def __init__(self, callback, callback_group, context=None):
"""
Create a GuardCondition.
.. warning:: Users should not create a guard condition with this constructor, instead they
should call :meth:`.Node.create_guard_condition`.
"""
self._context = get_default_context() if context is None else context
with self._context.handle:
self.__gc = _rclpy.GuardCondition(self._context.handle)
Expand All @@ -38,4 +44,10 @@ def handle(self):
return self.__gc

def destroy(self):
"""
Destroy a container for a ROS guard condition.
.. warning:: Users should not destroy a guard condition with this method, instead
they should call :meth:`.Node.destroy_guard_condition`.
"""
self.handle.destroy_when_not_in_use()
9 changes: 8 additions & 1 deletion rclpy/rclpy/node.py
Original file line number Diff line number Diff line change
Expand Up @@ -1781,7 +1781,12 @@ def create_guard_condition(
callback: Callable,
callback_group: Optional[CallbackGroup] = None
) -> GuardCondition:
"""Create a new guard condition."""
"""
Create a new guard condition.
.. warning:: Users should call :meth:`.Node.destroy_guard_condition` to destroy
the GuardCondition object.
"""
if callback_group is None:
callback_group = self.default_callback_group
guard = GuardCondition(callback, callback_group, context=self.context)
Expand All @@ -1799,6 +1804,8 @@ def create_rate(
"""
Create a Rate object.
.. warning:: Users should call :meth:`.Node.destroy_rate` to destroy the Rate object.
:param frequency: The frequency the Rate runs at (Hz).
:param clock: The clock the Rate gets time from.
"""
Expand Down
21 changes: 21 additions & 0 deletions rclpy/rclpy/timer.py
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,9 @@ def __init__(
If autostart is ``False``, the timer will be created but not started; it can then be
started by calling ``reset()`` on the timer object.
.. warning:: Users should not create a timer with this constructor, instead they
should call :meth:`.Node.create_timer`.
:param callback: A user-defined callback function that is called when the timer expires.
:param callback_group: The callback group for the timer. If ``None``, then the
default callback group for the node is used.
Expand All @@ -72,6 +75,12 @@ def handle(self):
return self.__timer

def destroy(self):
"""
Destroy a container for a ROS timer.
.. warning:: Users should not destroy a timer with this method, instead they should
call :meth:`.Node.destroy_timer`.
"""
self.__timer.destroy_when_not_in_use()

@property
Expand Down Expand Up @@ -132,6 +141,12 @@ class Rate:
"""A utility for sleeping at a fixed rate."""

def __init__(self, timer: Timer, *, context):
"""
Create a Rate.
.. warning:: Users should not create a rate with this constructor, instead they
should call :meth:`.Node.create_rate`.
"""
# Rate is a wrapper around a timer
self._timer = timer
self._is_shutdown = False
Expand All @@ -153,6 +168,12 @@ def _on_shutdown(self):
self.destroy()

def destroy(self):
"""
Destroy a container for a ROS rate.
.. warning:: Users should not destroy a rate with this method, instead they should
call :meth:`.Node.destroy_rate`.
"""
self._is_destroyed = True
self._event.set()

Expand Down

0 comments on commit 0926b34

Please sign in to comment.