Skip to content

Commit

Permalink
Get rosdoc2 to build
Browse files Browse the repository at this point in the history
Signed-off-by: Michel Hidalgo <[email protected]>
  • Loading branch information
mhidalgo-bdai committed Nov 27, 2024
1 parent 67fc03c commit b099d1e
Show file tree
Hide file tree
Showing 5 changed files with 73 additions and 61 deletions.
28 changes: 10 additions & 18 deletions rainbows/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -283,12 +283,11 @@ These APIs wrap those in [`rclpy.client`](https://github.com/ros2/rclpy/tree/rol

Actionable and serviced APIs abstract ROS 2 action and service calls behind an interface that resembles that of remote procedure calls. These can be invoked either synchronously or asynchronously. When used asynchronously, serviced APIs return plain futures whereas actionable APIs return action futures. Action futures build on the notion of a future to track actions' feedback, status, and result.

Both abstractions are well integrated with [ROS 2 aware scopes and processes](Process‐wide-APIs).
Both abstractions are well integrated with [ROS 2 aware scopes and processes](#process-wide-apis).

#### Common use cases

> [!NOTE]
> The following snippets make use of standard ROS 2 [`examples`](https://index.ros.org/r/examples/github-ros2-examples) and [`example_interfaces`](https://index.ros.org/p/example_interfaces).
The following snippets make use of standard ROS 2 [`examples`](https://index.ros.org/r/examples/github-ros2-examples) and [`example_interfaces`](https://index.ros.org/p/example_interfaces).

##### Invoking a service synchronously

Expand Down Expand Up @@ -327,8 +326,7 @@ if __name__ == "__main__":
main()
```

> [!NOTE]
> You may use servers in the `examples_rclpy_minimal_service` package to test this.
**Note**: you may use servers in the `examples_rclpy_minimal_service` package to test this.

Serviced API calls are synchronous by default. This can also be made explicit by calling `synchronously()` on them instead e.g. `add_two_ints.synchronously()`.
All service outcomes other than nominal success are signaled using exceptions. An optional timeout prevents calling (and blocking on) a service request indefinitely.
Expand Down Expand Up @@ -371,8 +369,7 @@ if __name__ == "__main__":
main()
```

> [!NOTE]
> You may use servers in the `examples_rclpy_minimal_service` package to test this.
**Note**: you may use servers in the `examples_rclpy_minimal_service` package to test this.

Service response must be waited on, either explicitly and with a timeout or implicitly by early result request.
Note fetching the future call result may raise.
Expand Down Expand Up @@ -420,8 +417,7 @@ if __name__ == "__main__":
main()
```

> [!NOTE]
> You may use servers in the `examples_rclpy_minimal_action_server` package to test this.
**Note**: you may use servers in the `examples_rclpy_minimal_action_server` package to test this.

Actionable API calls are synchronous by default. This can also be made explicit by calling `synchronously()` on them instead e.g. `compute_fibonacci_sequence.synchronously()`.
All action outcomes other than nominal success are signaled using exceptions. Action feedback is ignored unless a callback is specified on call.
Expand Down Expand Up @@ -478,8 +474,7 @@ if __name__ == "__main__":
main()
```

> [!NOTE]
> You may use servers in the `examples_rclpy_minimal_action_server` package to test this.
**Note**: you may use servers in the `examples_rclpy_minimal_action_server` package to test this.

Action status must be checked explicitly, and timely before attempting to access an action's result or feedback (which may not be there yet).
Action acknowledgement and finalization futures can help synchronization. Action feedback streaming simplifies (soft) real-time action monitoring.
Expand All @@ -498,15 +493,12 @@ Message feeds are the stateful generalization of standard ROS 2 message filters.

Like message filters, most message feeds can be chained. This is true for all but those that externally source messages, ROS 2 topic subscriptions being the prime example of this. Other message feeds built into `rainbows` offer a vehicle for generic map-filter-reduce patterns, time synchronization across multiple message feeds, and synchronized `tf` lookups.

> [!IMPORTANT]
> While any message filter can become a feed, standard ROS 2 message filters are usually not thread-safe.
> See [`rainbows.filters`](https://github.com/bdaiinstitute/ros_utilities/tree/main/rainbows/rainbows/filters.py) for thread-safe (re)implementations.
On word of caution. While any message filter can become a feed, standard ROS 2 message filters are usually not thread-safe. See [`rainbows.filters`](https://github.com/bdaiinstitute/ros_utilities/tree/main/rainbows/rainbows/filters.py) for thread-safe (re)implementations.

#### Common use cases

> [!NOTE]
> The following snippets make use of standard ROS 2 [`examples`](https://index.ros.org/r/examples/github-ros2-examples).
> You may use the publishers in the `examples_rclpy_minimal_publisher` package to test these.
The following snippets make use of standard ROS 2 [`examples`](https://index.ros.org/r/examples/github-ros2-examples).
You may use the publishers in the `examples_rclpy_minimal_publisher` package to test these.

##### Looping over topic messages

Expand Down Expand Up @@ -769,7 +761,7 @@ Unit testing ROS 2 code is no different from unit testing any other software, bu
#### Considerations for integration testing
* Data transport in ROS 2 is non-deterministic. So is callback execution when multi-threaded executors are in place. This is true for ROS 2 code in general, and for [process-wide APIs](Process-wide-APIs) in particular, for which non-determinism is the price to pay for a synchronous programming model. As such, time sensitive and execution order dependent tests are bound to fail, even if only sporadically. Synchronization is necessary to avoid these issues, and fortunately the very same process-wide APIs enable safe use of synchronization primitives (e.g. via a multi-threaded executor spinning in a background thread, as provided by [`bdai_ros_wrappers.scope`](https://github.com/bdaiinstitute/ros_utilities/blob/main/rainbows/rainbows/scope.py) functionality).
* Data transport in ROS 2 is non-deterministic. So is callback execution when multi-threaded executors are in place. This is true for ROS 2 code in general, and for [process-wide APIs](#process-wide-apis) in particular, for which non-determinism is the price to pay for a synchronous programming model. As such, time sensitive and execution order dependent tests are bound to fail, even if only sporadically. Synchronization is necessary to avoid these issues, and fortunately the very same process-wide APIs enable safe use of synchronization primitives (e.g. via a multi-threaded executor spinning in a background thread, as provided by [`bdai_ros_wrappers.scope`](https://github.com/bdaiinstitute/ros_utilities/blob/main/rainbows/rainbows/scope.py) functionality).
* ROS 2 middlewares perform peer discovery by default. This allows distributed architectures in production but leads to cross-talk during parallelized testing. [`domain_coordinator`](https://github.com/ros2/ament_cmake_ros/tree/rolling/domain_coordinator) functionality simplifies [ROS domain ID](https://docs.ros.org/en/rolling/Concepts/Intermediate/About-Domain-ID.html) assignment enforcing host-wide uniqueness and with it, middleware isolation.
Therefore, as rules of thumb consider:
Expand Down
16 changes: 8 additions & 8 deletions rainbows/rainbows/action_client.py
Original file line number Diff line number Diff line change
Expand Up @@ -46,8 +46,8 @@ def send_goal_and_wait(
Args:
action_name (str): A representative name of the action for logging
goal (Any): The Action Goal sent to the action server
timeout_sec (Optional[float]): A timeout for waiting on a response/result from the action server. Setting to
None creates no timeout
timeout_sec (Optional[float]): A timeout for waiting on a response/result
from the action server. Setting to None creates no timeout
Returns:
Optional[Any]:
Expand Down Expand Up @@ -94,12 +94,12 @@ def send_goal_async_handle(
Args:
action_name (str): A representative name of the action for logging
goal (Action.Goal): The Action Goal sent to the action server
result_callback (Optional[Callable[[Action.Result], None]]): A callback to process/handle the resulting
feedback from executing the command
feedback_callback (Optional[Callable[[Action.Feedback], None]]): A callback to process/handle the feedback
received during the execution of the command
on_failure_callback (Optional[Callable[[None], None]]): A callback to process/handle when the action fails
for various reasons
result_callback (Optional[Callable[[Action.Result], None]]): A callback to process/handle
the resulting feedback from executing the command
feedback_callback (Optional[Callable[[Action.Feedback], None]]): A callback to process/handle
the feedback received during the execution of the command
on_failure_callback (Optional[Callable[[None], None]]): A callback to process/handle when
the action fails for various reasons
Returns:
ActionHandle: An object to manage the asynchronous lifecycle of the action request
Expand Down
4 changes: 2 additions & 2 deletions rainbows/rainbows/executors.py
Original file line number Diff line number Diff line change
Expand Up @@ -411,8 +411,8 @@ def submit( # type: ignore
"""Submits work to the pool.
Args:
fn: a callable to execute. Must be immutable and hashable for
the pool to track concurrent submissions and apply quotas.
fn: a callable to execute. Must be immutable and hashable
for the pool to track concurrent submissions and apply quotas.
args: optional positional arguments to forward.
kwargs: optional keyword arguments to forward.
Expand Down
44 changes: 27 additions & 17 deletions rainbows/rainbows/tf_listener_wrapper.py
Original file line number Diff line number Diff line change
Expand Up @@ -40,16 +40,20 @@ def from_time_like(obj: Union[StampLike, TimeLike]) -> Time:


class TFListenerWrapper:
"""A `tf2_ros` lookup device, wrapping both a buffer and a listener.
"""A ``tf2_ros`` lookup device, wrapping both a buffer and a listener.
When using process-wide machinery:
.. code-block:: python
tf_listener = TFListenerWrapper()
tf_listener.wait_for_a_tform_b(target_frame, source_frame)
tf_listener.lookup_a_tform_b(target_frame, source_frame)
When composed by a ROS 2 node:
.. code-block:: python
class MyNode(Node):
def __init__(self, **kwargs: Any) -> None:
Expand Down Expand Up @@ -103,7 +107,8 @@ def wait_for_a_tform_b_async(
frame_a: Base frame for transform. The transform returned will be frame_a_t_frame_b
frame_b: Tip frame for transform. The transform returned will be frame_a_t_frame_b
transform_time: The time at which to look up the transform. If left at None, the most
recent transform available will used.
recent transform available will used.
Returns:
A future that will tell if a transform between frame_a and frame_b is available at the time specified.
"""
Expand All @@ -126,10 +131,11 @@ def wait_for_a_tform_b(
frame_a: Base frame for transform. The transform returned will be frame_a_t_frame_b
frame_b: Tip frame for transform. The transform returned will be frame_a_t_frame_b
transform_time: The time at which to look up the transform. If left at None, the most
recent transform available will used.
recent transform available will used.
timeout_sec: The time to wait for the transform to become available if the requested time is beyond
the most recent transform in the buffer. If set to 0, it will not wait. If left at None, it will
wait indefinitely.
the most recent transform in the buffer. If set to 0, it will not wait. If left at None, it will
wait indefinitely.
Returns:
Whether a transform between frame_a and frame_b is available at the specified time.
"""
Expand Down Expand Up @@ -157,17 +163,19 @@ def lookup_a_tform_b(
Args:
frame_a: Base frame for transform. The transform returned will be frame_a_t_frame_b
frame_b: Tip frame for transform. The transform returned will be frame_a_t_frame_b
transform_time: The time at which to look up the transform. If left at None, the most
recent transform available will used.
transform_time: The time at which to look up the transform. If left at None,
the most recent transform available will used.
timeout_sec: The time to wait for the transform to become available if the requested time is beyond
the most recent transform in the buffer. If set to 0, it will not wait. If left at None, it will
wait indefinitely.
the most recent transform in the buffer. If set to 0, it will not wait. If left at None, it will
wait indefinitely.
wait_for_frames: If true, it will wait for a path to exist from frame_a to frame_b in the
buffer. If false, lookup will fail immediately if a path between frames does not exist,
regardless of what timeout was set. Note that wait_for_a_tform_b can also be used to
wait for a transform to become available.
buffer. If false, lookup will fail immediately if a path between frames does not exist,
regardless of what timeout was set. Note that wait_for_a_tform_b can also be used to
wait for a transform to become available.
Returns:
The transform frame_a_t_frame_b at the time specified.
Raises:
All the possible TransformExceptions.
"""
Expand Down Expand Up @@ -205,14 +213,16 @@ def lookup_latest_timestamp(
frame_a: Base frame for transform. The transform returned will be frame_a_t_frame_b
frame_b: Tip frame for transform. The transform returned will be frame_a_t_frame_b
timeout_sec: The time to wait for the transform to become available if the requested time is beyond
the most recent transform in the buffer. If set to 0, it will not wait. If left at None, it will
wait indefinitely.
the most recent transform in the buffer. If set to 0, it will not wait. If left at None, it will
wait indefinitely.
wait_for_frames: If true, it will wait for a path to exist from frame_a to frame_b in the
buffer. If false, lookup will fail immediately if a path between frames does not exist,
regardless of what timeout was set. Note that wait_for_a_tform_b can also be used to
wait for a transform to become available.
buffer. If false, lookup will fail immediately if a path between frames does not exist,
regardless of what timeout was set. Note that wait_for_a_tform_b can also be used to
wait for a transform to become available.
Returns:
The timestamp from the latest recorded transform frame_a_t_frame_b
Raises:
All the possible TransformExceptions.
"""
Expand Down
42 changes: 26 additions & 16 deletions rainbows/rainbows/utilities.py
Original file line number Diff line number Diff line change
Expand Up @@ -404,15 +404,19 @@ def synchronized(
This function can be used as a decorator, like:
@synchronized
def my_function(...):
...
.. code-block:: python
or
@synchronized
def my_function(...):
...
@synchronized(lock=my_lock)
def my_function(...):
...
or:
.. code-block:: python
@synchronized(lock=my_lock)
def my_function(...):
...
"""
if lock is None:
lock = threading.Lock()
Expand All @@ -436,21 +440,27 @@ def functional_decorator(base_decorator: Callable) -> Callable:
As an example, consider the following decorator example:
@functional_decorator
def my_decorator(func, some_flag=None):
...
.. code-block:: python
@functional_decorator
def my_decorator(func, some_flag=None):
...
This decorator can then be used like this:
@my_decorator
def my_function(*args):
...
.. code-block:: python
@my_decorator
def my_function(*args):
...
and also like this:
@my_decorator(some_flag=True)
def my_function(*args):
...
.. code-block:: python
@my_decorator(some_flag=True)
def my_function(*args):
...
"""

@functools.wraps(base_decorator)
Expand Down

0 comments on commit b099d1e

Please sign in to comment.