| @@ -16,6 +16,6 @@ maturin develop | |||
| Type hinting requires to run a second step | |||
| ```bash | |||
| python dora/generate_stubs.py dora dora/__init__.pyi | |||
| python generate_stubs.py dora dora/__init__.pyi | |||
| maturin develop | |||
| ``` | |||
| @@ -0,0 +1,28 @@ | |||
| """ | |||
| # dora-rs | |||
| This is the dora python client for interacting with dora dataflow. | |||
| You can install it via: | |||
| ```bash | |||
| pip install dora-rs | |||
| ``` | |||
| """ | |||
| from enum import Enum | |||
| from .dora import ( | |||
| Node, | |||
| PyEvent, | |||
| DoraStatus, | |||
| Ros2Context, | |||
| Ros2Node, | |||
| Ros2NodeOptions, | |||
| Ros2Topic, | |||
| Ros2Publisher, | |||
| Ros2Subscription, | |||
| start_runtime, | |||
| __version__, | |||
| __author__, | |||
| Ros2QosPolicies, | |||
| Ros2Durability, | |||
| Ros2Liveliness, | |||
| ) | |||
| @@ -3,6 +3,7 @@ import typing | |||
| @typing.final | |||
| class DoraStatus: | |||
| """Dora Status for dora python operators.""" | |||
| def __eq__(self, value: typing.Any, /) -> bool: | |||
| """Return self==value.""" | |||
| @@ -31,6 +32,13 @@ class DoraStatus: | |||
| STOP: DoraStatus = ... | |||
| STOP_ALL: DoraStatus = ... | |||
| @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. | |||
| @@ -56,9 +64,14 @@ from dora import Node | |||
| node = Node() | |||
| ```""" | |||
| def dataflow_descriptor(self, /) -> dict:... | |||
| def dataflow_descriptor(self, /) -> dict: | |||
| """Returns the full dataflow descriptor that this node is part of. | |||
| def merge_external_events(self, /, subscription: Ros2Subscription) -> None:... | |||
| This method returns the parsed dataflow YAML file.""" | |||
| def merge_external_events(self, /, subscription: Ros2Subscription) -> None: | |||
| """Merge an external event stream with dora main loop. | |||
| This currently only work with ROS2.""" | |||
| def next(self, /, timeout: float=None) -> PyEvent: | |||
| """`.next()` gives you the next input that the node has received. | |||
| @@ -102,6 +115,7 @@ node.send_output("string", b"string", {"open_telemetry_context": "7632e76"}) | |||
| @typing.final | |||
| class PyEvent: | |||
| """Dora Event""" | |||
| def inner(self, /):... | |||
| @@ -123,9 +137,7 @@ You can also use `ros_paths` if you don't want to use env variable. | |||
| ```python | |||
| context = Ros2Context() | |||
| ``` | |||
| list of paths to search for ROS2 message types defintion""" | |||
| ```""" | |||
| def __init__(self, /, ros_paths: List[str]=None) -> None: | |||
| """ROS2 Context holding all messages definition for receiving and sending messages to ROS2. | |||
| @@ -141,9 +153,7 @@ You can also use `ros_paths` if you don't want to use env variable. | |||
| ```python | |||
| context = Ros2Context() | |||
| ``` | |||
| list of paths to search for ROS2 message types defintion""" | |||
| ```""" | |||
| def new_node(self, /, name: str, namespace: str, options: Ros2NodeOptions) -> Ros2Node: | |||
| """Create a new ROS2 node | |||
| @@ -154,11 +164,7 @@ ros2_node = ros2_context.new_node( | |||
| "/ros2_demo", | |||
| dora.experimental.ros2_bridge.Ros2NodeOptions(rosout=True), | |||
| ) | |||
| ``` | |||
| name of the node | |||
| name of the namespace | |||
| options for the node""" | |||
| ```""" | |||
| @typing.final | |||
| class Ros2Durability: | |||
| @@ -236,18 +242,14 @@ See: https://github.com/jhelovuo/ros2-client/issues/4""" | |||
| ```python | |||
| pose_publisher = ros2_node.create_publisher(turtle_pose_topic) | |||
| ``` | |||
| QoS policies for the topic""" | |||
| ```""" | |||
| def create_subscription(self, /, topic: Ros2Topic, qos: Ros2QosPolicies=None) -> Ros2Subscription: | |||
| """Create a ROS2 subscription | |||
| ```python | |||
| pose_reader = ros2_node.create_subscription(turtle_pose_topic) | |||
| ``` | |||
| QoS policies for the topic""" | |||
| ```""" | |||
| def create_topic(self, /, name: str, message_type: str, qos: Ros2QosPolicies) -> Ros2Topic: | |||
| """Create a ROS2 topic to connect to. | |||
| @@ -256,20 +258,14 @@ QoS policies for the topic""" | |||
| turtle_twist_topic = ros2_node.create_topic( | |||
| "/turtle1/cmd_vel", "geometry_msgs/Twist", topic_qos | |||
| ) | |||
| ``` | |||
| name of the topic. e.g. "pose" | |||
| message type of the topic. e.g. "std_msgs::UInt8MultiArray" | |||
| QoS policies for the topic""" | |||
| ```""" | |||
| @typing.final | |||
| class Ros2NodeOptions: | |||
| """ROS2 Node Options | |||
| enable rosout logging""" | |||
| """ROS2 Node Options""" | |||
| def __init__(self, /, rosout: bool=None) -> None: | |||
| """ROS2 Node Options | |||
| enable rosout logging""" | |||
| """ROS2 Node Options""" | |||
| @typing.final | |||
| class Ros2Publisher: | |||
| @@ -309,8 +305,7 @@ class Ros2Subscription: | |||
| @typing.final | |||
| class Ros2Topic: | |||
| """ROS2 Topic | |||
| enable rosout logging""" | |||
| """ROS2 Topic""" | |||
| def start_runtime() -> None: | |||
| """Start a runtime for Operators""" | |||
| @@ -59,6 +59,7 @@ impl Node { | |||
| /// match event["id"]: | |||
| /// case "image": | |||
| /// ``` | |||
| /// | |||
| /// :type timeout: float, optional | |||
| /// :rtype: PyEvent | |||
| #[allow(clippy::should_implement_trait)] | |||
| @@ -141,17 +142,17 @@ impl Node { | |||
| Ok(()) | |||
| } | |||
| // Returns the full dataflow descriptor that this node is part of. | |||
| // | |||
| // This method returns the parsed dataflow YAML file. | |||
| /// Returns the full dataflow descriptor that this node is part of. | |||
| /// | |||
| /// This method returns the parsed dataflow YAML file. | |||
| /// | |||
| /// :rtype: dict | |||
| pub fn dataflow_descriptor(&self, py: Python) -> pythonize::Result<PyObject> { | |||
| pythonize::pythonize(py, self.node.dataflow_descriptor()) | |||
| } | |||
| // Merge an external event stream with dora main loop. | |||
| // This currently only work with ROS2. | |||
| /// Merge an external event stream with dora main loop. | |||
| /// This currently only work with ROS2. | |||
| /// | |||
| /// :type subscription: Ros2Subscription | |||
| /// :rtype: None | |||
| @@ -239,6 +240,7 @@ pub fn start_runtime() -> eyre::Result<()> { | |||
| dora_runtime::main().wrap_err("Dora Runtime raised an error.") | |||
| } | |||
| /// Dora Status for dora python operators. | |||
| /// :rtype: DoraStatus | |||
| #[derive(Copy, Clone, Debug, PartialEq)] | |||
| #[pyclass] | |||
| @@ -3,13 +3,14 @@ use dora_node_api::{merged::MergedEvent, Event, Metadata, MetadataParameters}; | |||
| use eyre::{Context, Result}; | |||
| use pyo3::{exceptions::PyLookupError, prelude::*, types::PyDict}; | |||
| // Dora Event | |||
| /// Dora Event | |||
| #[pyclass] | |||
| pub struct PyEvent { | |||
| event: MergedEvent<PyObject>, | |||
| data: Option<ArrayRef>, | |||
| } | |||
| // Dora Event | |||
| #[pymethods] | |||
| impl PyEvent { | |||
| /// | |||
| @@ -39,7 +39,6 @@ pub mod typed; | |||
| /// ``` | |||
| /// | |||
| /// :type ros_paths: List[str], optional | |||
| /// list of paths to search for ROS2 message types defintion | |||
| /// | |||
| #[pyclass] | |||
| pub struct Ros2Context { | |||
| @@ -101,11 +100,8 @@ impl Ros2Context { | |||
| /// ``` | |||
| /// | |||
| /// :type name: str | |||
| /// name of the node | |||
| /// :type namespace: str | |||
| /// name of the namespace | |||
| /// :type options: Ros2NodeOptions | |||
| /// options for the node | |||
| /// :rtype: Ros2Node | |||
| pub fn new_node( | |||
| &self, | |||
| @@ -148,11 +144,8 @@ impl Ros2Node { | |||
| /// ``` | |||
| /// | |||
| /// :type name: str | |||
| /// name of the topic. e.g. "pose" | |||
| /// :type message_type: str | |||
| /// message type of the topic. e.g. "std_msgs::UInt8MultiArray" | |||
| /// :type qos: Ros2QosPolicies | |||
| /// QoS policies for the topic | |||
| /// :rtype: Ros2Topic | |||
| pub fn create_topic( | |||
| &self, | |||
| @@ -190,7 +183,6 @@ impl Ros2Node { | |||
| /// | |||
| /// :type topic: Ros2Topic | |||
| /// :type qos: Ros2QosPolicies, optional | |||
| /// QoS policies for the topic | |||
| /// :rtype: Ros2Publisher | |||
| pub fn create_publisher( | |||
| &mut self, | |||
| @@ -214,7 +206,6 @@ impl Ros2Node { | |||
| /// | |||
| /// :type topic: Ros2Topic | |||
| /// :type qos: Ros2QosPolicies, optional | |||
| /// QoS policies for the topic | |||
| /// :rtype: Ros2Subscription | |||
| pub fn create_subscription( | |||
| &mut self, | |||
| @@ -233,7 +224,6 @@ impl Ros2Node { | |||
| /// ROS2 Node Options | |||
| /// :type rosout: bool, optional | |||
| /// enable rosout logging | |||
| /// | |||
| #[derive(Debug, Clone, Default)] | |||
| #[pyclass] | |||
| @@ -260,7 +250,6 @@ impl From<Ros2NodeOptions> for ros2_client::NodeOptions { | |||
| /// ROS2 Topic | |||
| /// :type rosout: bool, optional | |||
| /// enable rosout logging | |||
| /// | |||
| #[pyclass] | |||
| #[non_exhaustive] | |||
| @@ -0,0 +1,17 @@ | |||
| from dora import ( | |||
| Node, | |||
| PyEvent, | |||
| DoraStatus, | |||
| Ros2Context, | |||
| Ros2Node, | |||
| Ros2NodeOptions, | |||
| Ros2Topic, | |||
| Ros2Publisher, | |||
| Ros2Subscription, | |||
| start_runtime, | |||
| __version__, | |||
| __author__, | |||
| Ros2QosPolicies, | |||
| Ros2Durability, | |||
| Ros2Liveliness, | |||
| ) | |||