Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Adding python IDE typing #493

Merged
merged 13 commits into from
May 2, 2024
16 changes: 16 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -263,6 +263,22 @@ We also have [a contributing guide](CONTRIBUTING.md).
| **Supported Platforms (ARM)** | macOS, Linux |
| **Configuration** | YAML |

### Unstable functionality

Some parts of the public API are marked as **unstable**.
You can recognize this functionality from the warning in the API reference, or from the warning issued when the configuration option `warn_unstable` is active.
haixuanTao marked this conversation as resolved.
Show resolved Hide resolved
There are a number of reasons functionality may be marked as unstable:

- We are unsure about the exact API. The name, function signature, or implementation are likely to change in the future.
- The functionality is not tested extensively yet. Bugs may pop up when used in real-world scenarios.
- The functionality does not integrate well with the full Polars API. You may find it works in one context but not in another.

Releasing functionality as unstable allows us to gather important feedback from users that use Polars in real-world scenarios.
This helps us fine-tune things before giving it the final stamp of approval.
Users are only interested in solid, well-tested functionality can avoid this part of the API.

Functionality marked as unstable may change at any point without it being considered a breaking change.
haixuanTao marked this conversation as resolved.
Show resolved Hide resolved

## License

This project is licensed under Apache-2.0. Check out [NOTICE.md](NOTICE.md) for more information.
9 changes: 9 additions & 0 deletions apis/python/node/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -10,3 +10,12 @@ source .env/bin/activate
pip install maturin
maturin develop
```

## Type hinting

Type hinting requires to run a second step

```bash
python generate_stubs.py dora dora/__init__.pyi
maturin develop
```
22 changes: 16 additions & 6 deletions apis/python/node/dora/__init__.py
Original file line number Diff line number Diff line change
@@ -1,10 +1,7 @@
"""
# dora-rs

This is the dora python client for interacting with dora dataflow.

You can install it via:

```bash
pip install dora-rs
```
Expand All @@ -14,14 +11,27 @@

from .dora import *

__author__ = "Dora-rs Authors"
__version__ = "0.3.3"
from .dora import (
Node,
PyEvent,
Ros2Context,
Ros2Node,
Ros2NodeOptions,
Ros2Topic,
Ros2Publisher,
Ros2Subscription,
start_runtime,
__version__,
__author__,
Ros2QosPolicies,
Ros2Durability,
Ros2Liveliness,
)


class DoraStatus(Enum):
"""Dora status to indicate if operator `on_input` loop
should be stopped.

Args:
Enum (u8): Status signaling to dora operator to
stop or continue the operator.
Expand Down
283 changes: 283 additions & 0 deletions apis/python/node/dora/__init__.pyi
Original file line number Diff line number Diff line change
@@ -0,0 +1,283 @@
import dora
import pyarrow
import typing

@typing.final
class Enum:
"""Generic enumeration.

Derive from this class to define new enumerations."""
__members__: mappingproxy = ...

@typing.final
class Node:
"""The custom node API lets you integrate `dora` into your application.
It allows you to retrieve input and send output in any fashion you want.

Use with:

```python
from dora import Node

node = Node()
```"""

def __init__(self, /) -> None:
"""The custom node API lets you integrate `dora` into your application.
It allows you to retrieve input and send output in any fashion you want.

Use with:

```python
from dora import Node

node = Node()
```"""

def dataflow_descriptor(self, /) -> dict:
"""Returns the full dataflow descriptor that this node is part of.

This method returns the parsed dataflow YAML file."""

def merge_external_events(self, /, subscription: dora.Ros2Subscription) -> None:
"""Merge an external event stream with dora main loop.
This currently only work with ROS2."""

def next(self, /, timeout: float=None) -> dora.PyEvent:
"""`.next()` gives you the next input that the node has received.
It blocks until the next event becomes available.
You can use timeout in seconds to return if no input is available.
It will return `None` when all senders has been dropped.

```python
event = node.next()
```

You can also iterate over the event stream with a loop

```python
for event in node:
match event["type"]:
case "INPUT":
match event["id"]:
case "image":
```"""

def send_output(self, /, output_id: str, data: pyarrow.Array, metadata: typing.Dict[str | str]=None) -> None:
"""`send_output` send data from the node.

```python
Args:
output_id: str,
data: pyarrow.Array,
metadata: Option[Dict],
```

ex:

```python
node.send_output("string", b"string", {"open_telemetry_context": "7632e76"})
```"""

def __iter__(self, /) -> typing.Any:
"""Implement iter(self)."""

def __next__(self, /) -> typing.Any:
"""Implement next(self)."""

@typing.final
class PyEvent:
"""Dora Event"""

def inner(self, /):...

def __getitem__(self, key: typing.Any, /) -> typing.Any:
"""Return self[key]."""

@typing.final
class Ros2Context:
"""ROS2 Context holding all messages definition for receiving and sending messages to ROS2.
phil-opp marked this conversation as resolved.
Show resolved Hide resolved

By default, Ros2Context will use env `AMENT_PREFIX_PATH` to search for message definition.

AMENT_PREFIX_PATH folder structure should be the following:

- For messages: <namespace>/msg/<name>.msg
- For services: <namespace>/srv/<name>.srv

You can also use `ros_paths` if you don't want to use env variable.

```python
context = Ros2Context()
```"""

def __init__(self, /, ros_paths: typing.List[str]=None) -> None:
"""ROS2 Context holding all messages definition for receiving and sending messages to ROS2.

By default, Ros2Context will use env `AMENT_PREFIX_PATH` to search for message definition.

AMENT_PREFIX_PATH folder structure should be the following:

- For messages: <namespace>/msg/<name>.msg
- For services: <namespace>/srv/<name>.srv

You can also use `ros_paths` if you don't want to use env variable.

```python
context = Ros2Context()
```"""

def new_node(self, /, name: str, namespace: str, options: dora.Ros2NodeOptions) -> dora.Ros2Node:
"""Create a new ROS2 node

```python
ros2_node = ros2_context.new_node(
"turtle_teleop",
"/ros2_demo",
Ros2NodeOptions(rosout=True),
)
```"""

@typing.final
class Ros2Durability:
"""DDS 2.2.3.4 DURABILITY"""

def __eq__(self, value: typing.Any, /) -> bool:
"""Return self==value."""

def __ge__(self, value: typing.Any, /) -> bool:
"""Return self>=value."""

def __gt__(self, value: typing.Any, /) -> bool:
"""Return self>value."""

def __int__(self, /) -> None:
"""int(self)"""

def __le__(self, value: typing.Any, /) -> bool:
"""Return self<=value."""

def __lt__(self, value: typing.Any, /) -> bool:
"""Return self<value."""

def __ne__(self, value: typing.Any, /) -> bool:
"""Return self!=value."""

def __repr__(self, /) -> str:
"""Return repr(self)."""
Persistent: Ros2Durability = ...
Transient: Ros2Durability = ...
TransientLocal: Ros2Durability = ...
Volatile: Ros2Durability = ...

@typing.final
class Ros2Liveliness:
"""DDS 2.2.3.11 LIVELINESS"""

def __eq__(self, value: typing.Any, /) -> bool:
"""Return self==value."""

def __ge__(self, value: typing.Any, /) -> bool:
"""Return self>=value."""

def __gt__(self, value: typing.Any, /) -> bool:
"""Return self>value."""

def __int__(self, /) -> None:
"""int(self)"""

def __le__(self, value: typing.Any, /) -> bool:
"""Return self<=value."""

def __lt__(self, value: typing.Any, /) -> bool:
"""Return self<value."""

def __ne__(self, value: typing.Any, /) -> bool:
"""Return self!=value."""

def __repr__(self, /) -> str:
"""Return repr(self)."""
Automatic: Ros2Liveliness = ...
ManualByParticipant: Ros2Liveliness = ...
ManualByTopic: Ros2Liveliness = ...

@typing.final
class Ros2Node:
"""ROS2 Node

Warnings:
- There's a known issue about ROS2 nodes not being discoverable by ROS2
See: https://github.com/jhelovuo/ros2-client/issues/4"""

def create_publisher(self, /, topic: dora.Ros2Topic, qos: dora.Ros2QosPolicies=None) -> dora.Ros2Publisher:
"""Create a ROS2 publisher

```python
pose_publisher = ros2_node.create_publisher(turtle_pose_topic)
```"""

def create_subscription(self, /, topic: dora.Ros2Topic, qos: dora.Ros2QosPolicies=None) -> dora.Ros2Subscription:
"""Create a ROS2 subscription

```python
pose_reader = ros2_node.create_subscription(turtle_pose_topic)
```"""

def create_topic(self, /, name: str, message_type: str, qos: dora.Ros2QosPolicies) -> dora.Ros2Topic:
"""Create a ROS2 topic to connect to.

```python
turtle_twist_topic = ros2_node.create_topic(
"/turtle1/cmd_vel", "geometry_msgs/Twist", topic_qos
)
```"""

@typing.final
class Ros2NodeOptions:
"""ROS2 Node Options"""

def __init__(self, /, rosout: bool=None) -> None:
"""ROS2 Node Options"""

@typing.final
class Ros2Publisher:
"""ROS2 Publisher"""

def publish(self, /, data: pyarrow.Array) -> None:
"""Publish a message into ROS2 topic.

Remember that the data format should respect the structure of the ROS2 message usinng an arrow Structure.

ex:
```python
gripper_command.publish(
pa.array(
[
{
"name": "gripper",
"cmd": np.float32(5),
}
]
),
)
```"""

@typing.final
class Ros2QosPolicies:
"""ROS2 QoS Policy"""

def __init__(self, /, durability: dora.Ros2Durability=None, liveliness: dora.Ros2Liveliness=None, reliable: bool=None, keep_all: bool=None, lease_duration: float=None, max_blocking_time: float=None, keep_last: int=None) -> dora.Ros2QoSPolicies:
"""ROS2 QoS Policy"""

@typing.final
class Ros2Subscription:
"""ROS2 Subscription"""

def next(self, /):...

@typing.final
class Ros2Topic:
"""ROS2 Topic"""

def start_runtime() -> None:
"""Start a runtime for Operators"""
Loading
Loading