| @@ -1,3 +1,4 @@ | |||
| import dora | |||
| import pyarrow | |||
| import typing | |||
| @@ -38,11 +39,11 @@ node = Node() | |||
| This method returns the parsed dataflow YAML file.""" | |||
| def merge_external_events(self, /, subscription: Ros2Subscription) -> None: | |||
| 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) -> PyEvent: | |||
| 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. | |||
| @@ -62,16 +63,18 @@ match event["id"]: | |||
| case "image": | |||
| ```""" | |||
| def send_output(self, /, output_id: str, data: pyarrow.Array, metadata: dict=None) -> None: | |||
| 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: Bytes|Arrow, | |||
| data: pyarrow.Array, | |||
| metadata: Option[Dict], | |||
| ``` | |||
| ex: | |||
| ```python | |||
| node.send_output("string", b"string", {"open_telemetry_context": "7632e76"}) | |||
| ```""" | |||
| @@ -108,7 +111,7 @@ You can also use `ros_paths` if you don't want to use env variable. | |||
| context = Ros2Context() | |||
| ```""" | |||
| def __init__(self, /, ros_paths: List[str]=None) -> None: | |||
| 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. | |||
| @@ -124,7 +127,7 @@ You can also use `ros_paths` if you don't want to use env variable. | |||
| context = Ros2Context() | |||
| ```""" | |||
| def new_node(self, /, name: str, namespace: str, options: Ros2NodeOptions) -> Ros2Node: | |||
| def new_node(self, /, name: str, namespace: str, options: dora.Ros2NodeOptions) -> dora.Ros2Node: | |||
| """Create a new ROS2 node | |||
| ```python | |||
| @@ -206,21 +209,21 @@ 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: Ros2Topic, qos: Ros2QosPolicies=None) -> Ros2Publisher: | |||
| 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: Ros2Topic, qos: Ros2QosPolicies=None) -> Ros2Subscription: | |||
| 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: Ros2QosPolicies) -> Ros2Topic: | |||
| def create_topic(self, /, name: str, message_type: str, qos: dora.Ros2QosPolicies) -> dora.Ros2Topic: | |||
| """Create a ROS2 topic to connect to. | |||
| ```python | |||
| @@ -263,7 +266,7 @@ pa.array( | |||
| class Ros2QosPolicies: | |||
| """ROS2 QoS Policy""" | |||
| def __init__(self, /, durability: Ros2Durability=None, liveliness: Ros2Liveliness=None, reliable: bool=None, keep_all: bool=None, lease_duration: float=None, max_blocking_time: float=None, keep_last: int=None) -> Ros2QoSPolicies: | |||
| 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 | |||
| @@ -421,6 +421,8 @@ def parse_type_to_ast( | |||
| # TODO: Fix sequence | |||
| if "Ros" in sequence and "2" in sequence: | |||
| sequence = ["".join(sequence)] | |||
| elif "dora.Ros" in sequence and "2" in sequence: | |||
| sequence = ["".join(sequence)] | |||
| for e in sequence: | |||
| if e == "or": | |||
| @@ -61,7 +61,7 @@ impl Node { | |||
| /// ``` | |||
| /// | |||
| /// :type timeout: float, optional | |||
| /// :rtype: PyEvent | |||
| /// :rtype: dora.PyEvent | |||
| #[allow(clippy::should_implement_trait)] | |||
| pub fn next(&mut self, py: Python, timeout: Option<f32>) -> PyResult<Option<PyEvent>> { | |||
| let event = py.allow_threads(|| self.events.recv(timeout.map(Duration::from_secs_f32))); | |||
| @@ -78,7 +78,7 @@ impl Node { | |||
| /// case "image": | |||
| /// ``` | |||
| /// | |||
| /// :rtype: PyEvent | |||
| /// :rtype: dora.PyEvent | |||
| pub fn __next__(&mut self, py: Python) -> PyResult<Option<PyEvent>> { | |||
| let event = py.allow_threads(|| self.events.recv(None)); | |||
| Ok(event) | |||
| @@ -94,7 +94,7 @@ impl Node { | |||
| /// case "image": | |||
| /// ``` | |||
| /// | |||
| /// :rtype: PyEvent | |||
| /// :rtype: dora.PyEvent | |||
| fn __iter__(slf: PyRef<'_, Self>) -> PyRef<'_, Self> { | |||
| slf | |||
| } | |||
| @@ -104,13 +104,16 @@ impl Node { | |||
| /// ```python | |||
| /// Args: | |||
| /// output_id: str, | |||
| /// data: Bytes|Arrow, | |||
| /// data: pyarrow.Array, | |||
| /// metadata: Option[Dict], | |||
| /// ``` | |||
| /// | |||
| /// ex: | |||
| /// | |||
| /// ```python | |||
| /// node.send_output("string", b"string", {"open_telemetry_context": "7632e76"}) | |||
| /// ``` | |||
| /// | |||
| /// :type output_id: str | |||
| /// :type data: pyarrow.Array | |||
| /// :type metadata: dict, optional | |||
| @@ -154,7 +157,7 @@ impl Node { | |||
| /// Merge an external event stream with dora main loop. | |||
| /// This currently only work with ROS2. | |||
| /// | |||
| /// :type subscription: Ros2Subscription | |||
| /// :type subscription: dora.Ros2Subscription | |||
| /// :rtype: None | |||
| pub fn merge_external_events( | |||
| &mut self, | |||
| @@ -240,34 +243,12 @@ 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] | |||
| pub enum DoraStatus { | |||
| CONTINUE, | |||
| STOP, | |||
| STOP_ALL, | |||
| } | |||
| impl DoraStatus { | |||
| /// :rtype: int | |||
| pub fn value(self) -> i32 { | |||
| match self { | |||
| DoraStatus::CONTINUE => 0, | |||
| DoraStatus::STOP => 1, | |||
| DoraStatus::STOP_ALL => 2, | |||
| } | |||
| } | |||
| } | |||
| #[pymodule] | |||
| fn dora(_py: Python, m: &PyModule) -> PyResult<()> { | |||
| dora_ros2_bridge_python::create_dora_ros2_bridge_module(m)?; | |||
| m.add_function(wrap_pyfunction!(start_runtime, m)?)?; | |||
| m.add_class::<Node>()?; | |||
| m.add_class::<PyEvent>()?; | |||
| m.add_class::<DoraStatus>()?; | |||
| m.setattr("__version__", env!("CARGO_PKG_VERSION"))?; | |||
| m.setattr("__author__", "Dora-rs Authors")?; | |||
| @@ -14,7 +14,7 @@ pub struct PyEvent { | |||
| #[pymethods] | |||
| impl PyEvent { | |||
| /// | |||
| /// :rtype: PyObject | |||
| /// :rtype: dora.PyObject | |||
| pub fn __getitem__(&self, key: &str, py: Python<'_>) -> PyResult<Option<PyObject>> { | |||
| if key == "kind" { | |||
| let kind = match &self.event { | |||
| @@ -38,7 +38,7 @@ pub mod typed; | |||
| /// context = Ros2Context() | |||
| /// ``` | |||
| /// | |||
| /// :type ros_paths: List[str], optional | |||
| /// :type ros_paths: typing.List[str], optional | |||
| /// | |||
| #[pyclass] | |||
| pub struct Ros2Context { | |||
| @@ -101,8 +101,8 @@ impl Ros2Context { | |||
| /// | |||
| /// :type name: str | |||
| /// :type namespace: str | |||
| /// :type options: Ros2NodeOptions | |||
| /// :rtype: Ros2Node | |||
| /// :type options: dora.Ros2NodeOptions | |||
| /// :rtype: dora.Ros2Node | |||
| pub fn new_node( | |||
| &self, | |||
| name: &str, | |||
| @@ -145,8 +145,8 @@ impl Ros2Node { | |||
| /// | |||
| /// :type name: str | |||
| /// :type message_type: str | |||
| /// :type qos: Ros2QosPolicies | |||
| /// :rtype: Ros2Topic | |||
| /// :type qos: dora.Ros2QosPolicies | |||
| /// :rtype: dora.Ros2Topic | |||
| pub fn create_topic( | |||
| &self, | |||
| name: &str, | |||
| @@ -181,9 +181,9 @@ impl Ros2Node { | |||
| /// pose_publisher = ros2_node.create_publisher(turtle_pose_topic) | |||
| /// ``` | |||
| /// | |||
| /// :type topic: Ros2Topic | |||
| /// :type qos: Ros2QosPolicies, optional | |||
| /// :rtype: Ros2Publisher | |||
| /// :type topic: dora.Ros2Topic | |||
| /// :type qos: dora.Ros2QosPolicies, optional | |||
| /// :rtype: dora.Ros2Publisher | |||
| pub fn create_publisher( | |||
| &mut self, | |||
| topic: &Ros2Topic, | |||
| @@ -204,9 +204,9 @@ impl Ros2Node { | |||
| /// pose_reader = ros2_node.create_subscription(turtle_pose_topic) | |||
| /// ``` | |||
| /// | |||
| /// :type topic: Ros2Topic | |||
| /// :type qos: Ros2QosPolicies, optional | |||
| /// :rtype: Ros2Subscription | |||
| /// :type topic: dora.Ros2Topic | |||
| /// :type qos: dora.Ros2QosPolicies, optional | |||
| /// :rtype: dora.Ros2Subscription | |||
| pub fn create_subscription( | |||
| &mut self, | |||
| topic: &Ros2Topic, | |||
| @@ -3,14 +3,14 @@ use pyo3::prelude::{pyclass, pymethods}; | |||
| /// ROS2 QoS Policy | |||
| /// | |||
| /// :type durability: Ros2Durability, optional | |||
| /// :type liveliness: Ros2Liveliness, optional | |||
| /// :type durability: dora.Ros2Durability, optional | |||
| /// :type liveliness: dora.Ros2Liveliness, optional | |||
| /// :type reliable: bool, optional | |||
| /// :type keep_all: bool, optional | |||
| /// :type lease_duration: float, optional | |||
| /// :type max_blocking_time: float, optional | |||
| /// :type keep_last: int, optional | |||
| /// :rtype: Ros2QoSPolicies | |||
| /// :rtype: dora.Ros2QoSPolicies | |||
| /// | |||
| #[derive(Debug, Clone)] | |||
| #[pyclass] | |||
| @@ -76,7 +76,7 @@ impl From<Ros2QosPolicies> for rustdds::QosPolicies { | |||
| /// DDS 2.2.3.4 DURABILITY | |||
| /// | |||
| /// :rtype: Ros2Durability | |||
| /// :rtype: dora.Ros2Durability | |||
| #[derive(Copy, Clone, Debug, PartialEq, Eq, PartialOrd, Ord, Hash)] | |||
| #[pyclass] | |||
| pub enum Ros2Durability { | |||
| @@ -86,11 +86,11 @@ pub enum Ros2Durability { | |||
| Persistent, | |||
| } | |||
| /// :type value: Ros2Durability | |||
| /// :rtype: Ros2Durability | |||
| /// :type value: dora.Ros2Durability | |||
| /// :rtype: dora.Ros2Durability | |||
| impl From<Ros2Durability> for policy::Durability { | |||
| /// :type value: Ros2Durability | |||
| /// :rtype: Ros2Durability | |||
| /// :type value: dora.Ros2Durability | |||
| /// :rtype: dora.Ros2Durability | |||
| fn from(value: Ros2Durability) -> Self { | |||
| match value { | |||
| Ros2Durability::Volatile => policy::Durability::Volatile, | |||
| @@ -102,7 +102,7 @@ impl From<Ros2Durability> for policy::Durability { | |||
| } | |||
| /// DDS 2.2.3.11 LIVELINESS | |||
| /// :rtype: Ros2Liveliness | |||
| /// :rtype: dora.Ros2Liveliness | |||
| #[derive(Copy, Clone, Debug, PartialEq)] | |||
| #[pyclass] | |||
| pub enum Ros2Liveliness { | |||
| @@ -113,7 +113,7 @@ pub enum Ros2Liveliness { | |||
| impl Ros2Liveliness { | |||
| /// :type lease_duration: float | |||
| /// :rtype: Ros2Liveliness | |||
| /// :rtype: dora.Ros2Liveliness | |||
| fn convert(self, lease_duration: f64) -> policy::Liveliness { | |||
| let lease_duration = if lease_duration.is_infinite() { | |||
| rustdds::Duration::INFINITE | |||