File size: 8,084 Bytes
b98ffbb |
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 |
#![allow(clippy::borrow_deref_ref)] // clippy warns about code generated by #[pymethods]
use std::time::Duration;
use arrow::pyarrow::{FromPyArrow, ToPyArrow};
use dora_node_api::merged::{MergeExternalSend, MergedEvent};
use dora_node_api::{DoraNode, EventStream};
use dora_operator_api_python::{pydict_to_metadata, PyEvent};
use dora_ros2_bridge_python::Ros2Subscription;
use eyre::Context;
use futures::{Stream, StreamExt};
use pyo3::prelude::*;
use pyo3::types::{PyBytes, PyDict};
/// 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()
/// ```
///
#[pyclass]
pub struct Node {
events: Events,
node: DoraNode,
}
#[pymethods]
impl Node {
#[new]
pub fn new() -> eyre::Result<Self> {
let (node, events) = DoraNode::init_from_env()?;
Ok(Node {
events: Events::Dora(events),
node,
})
}
/// `.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":
/// ```
///
/// :type timeout: float, optional
/// :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)));
Ok(event)
}
/// You can iterate over the event stream with a loop
///
/// ```python
/// for event in node:
/// match event["type"]:
/// case "INPUT":
/// match event["id"]:
/// case "image":
/// ```
///
/// :rtype: dora.PyEvent
pub fn __next__(&mut self, py: Python) -> PyResult<Option<PyEvent>> {
let event = py.allow_threads(|| self.events.recv(None));
Ok(event)
}
/// You can iterate over the event stream with a loop
///
/// ```python
/// for event in node:
/// match event["type"]:
/// case "INPUT":
/// match event["id"]:
/// case "image":
/// ```
///
/// :rtype: dora.PyEvent
fn __iter__(slf: PyRef<'_, Self>) -> PyRef<'_, Self> {
slf
}
/// `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"})
/// ```
///
/// :type output_id: str
/// :type data: pyarrow.Array
/// :type metadata: dict, optional
/// :rtype: None
pub fn send_output(
&mut self,
output_id: String,
data: PyObject,
metadata: Option<Bound<'_, PyDict>>,
py: Python,
) -> eyre::Result<()> {
let parameters = pydict_to_metadata(metadata)?;
if let Ok(py_bytes) = data.downcast_bound::<PyBytes>(py) {
let data = py_bytes.as_bytes();
self.node
.send_output_bytes(output_id.into(), parameters, data.len(), data)
.wrap_err("failed to send output")?;
} else if let Ok(arrow_array) = arrow::array::ArrayData::from_pyarrow_bound(data.bind(py)) {
self.node.send_output(
output_id.into(),
parameters,
arrow::array::make_array(arrow_array),
)?;
} else {
eyre::bail!("invalid `data` type, must by `PyBytes` or arrow array")
}
Ok(())
}
/// 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())
}
/// Returns the dataflow id.
///
/// :rtype: str
pub fn dataflow_id(&self) -> String {
self.node.dataflow_id().to_string()
}
/// Merge an external event stream with dora main loop.
/// This currently only work with ROS2.
///
/// :type subscription: dora.Ros2Subscription
/// :rtype: None
pub fn merge_external_events(
&mut self,
subscription: &mut Ros2Subscription,
) -> eyre::Result<()> {
let subscription = subscription.into_stream()?;
let stream = futures::stream::poll_fn(move |cx| {
let s = subscription.as_stream().map(|item| {
match item.context("failed to read ROS2 message") {
Ok((value, _info)) => Python::with_gil(|py| {
value
.to_pyarrow(py)
.context("failed to convert value to pyarrow")
.unwrap_or_else(|err| PyErr::from(err).to_object(py))
}),
Err(err) => Python::with_gil(|py| PyErr::from(err).to_object(py)),
}
});
futures::pin_mut!(s);
s.poll_next_unpin(cx)
});
// take out the event stream and temporarily replace it with a dummy
let events = std::mem::replace(
&mut self.events,
Events::Merged(Box::new(futures::stream::empty())),
);
// update self.events with the merged stream
self.events = Events::Merged(events.merge_external_send(Box::pin(stream)));
Ok(())
}
}
enum Events {
Dora(EventStream),
Merged(Box<dyn Stream<Item = MergedEvent<PyObject>> + Unpin + Send>),
}
impl Events {
fn recv(&mut self, timeout: Option<Duration>) -> Option<PyEvent> {
match self {
Events::Dora(events) => match timeout {
Some(timeout) => events.recv_timeout(timeout).map(PyEvent::from),
None => events.recv().map(PyEvent::from),
},
Events::Merged(events) => futures::executor::block_on(events.next()).map(PyEvent::from),
}
}
}
impl<'a> MergeExternalSend<'a, PyObject> for Events {
type Item = MergedEvent<PyObject>;
fn merge_external_send(
self,
external_events: impl Stream<Item = PyObject> + Unpin + Send + 'a,
) -> Box<dyn Stream<Item = Self::Item> + Unpin + Send + 'a> {
match self {
Events::Dora(events) => events.merge_external_send(external_events),
Events::Merged(events) => {
let merged = events.merge_external_send(external_events);
Box::new(merged.map(|event| match event {
MergedEvent::Dora(e) => MergedEvent::Dora(e),
MergedEvent::External(e) => MergedEvent::External(e.flatten()),
}))
}
}
}
}
impl Node {
pub fn id(&self) -> String {
self.node.id().to_string()
}
}
/// Start a runtime for Operators
///
/// :rtype: None
#[pyfunction]
pub fn start_runtime() -> eyre::Result<()> {
dora_runtime::main().wrap_err("Dora Runtime raised an error.")
}
#[pymodule]
fn dora(_py: Python, m: Bound<'_, 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.setattr("__version__", env!("CARGO_PKG_VERSION"))?;
m.setattr("__author__", "Dora-rs Authors")?;
Ok(())
}
|