From 739cfd57f7eedb2c54eea980e2a30fe275ec2bd9 Mon Sep 17 00:00:00 2001 From: haixuanTao Date: Fri, 27 Oct 2023 15:04:24 +0200 Subject: [PATCH] Change type hinting frfom Uint8 only array to any array --- .../src/template/python/operator/operator-template.py | 8 +++----- binaries/runtime/src/operator/python.rs | 2 +- examples/python-operator-dataflow/object_detection.py | 10 +++++----- examples/python-operator-dataflow/plot.py | 8 ++++---- examples/python-operator-dataflow/webcam.py | 2 +- 5 files changed, 14 insertions(+), 16 deletions(-) diff --git a/binaries/cli/src/template/python/operator/operator-template.py b/binaries/cli/src/template/python/operator/operator-template.py index 88452221..e6d6e87d 100644 --- a/binaries/cli/src/template/python/operator/operator-template.py +++ b/binaries/cli/src/template/python/operator/operator-template.py @@ -30,10 +30,10 @@ class Operator: Args: dora_input (dict): Input dict containing an `id`, `data` and `metadata`. - send_output Callable[[str, bytes | pa.UInt8Array, Optional[dict]], None]: + send_output Callable[[str, bytes | pa.Array, Optional[dict]], None]: Function for sending output to the dataflow: - First argument is the `output_id` - - Second argument is the data as either bytes or `pa.UInt8Array` + - Second argument is the data as either bytes or `pa.Array` - Third argument is dora metadata dict e.g.: `send_output("bbox", pa.array([100], type=pa.uint8()), dora_event["metadata"])` @@ -44,9 +44,7 @@ class Operator: STOP means that the operator stop listening for inputs. """ - print( - f"Received input {dora_input['id']}, with data: {dora_input['value']}" - ) + print(f"Received input {dora_input['id']}, with data: {dora_input['value']}") return DoraStatus.CONTINUE diff --git a/binaries/runtime/src/operator/python.rs b/binaries/runtime/src/operator/python.rs index e9a2f936..1d415a67 100644 --- a/binaries/runtime/src/operator/python.rs +++ b/binaries/runtime/src/operator/python.rs @@ -287,7 +287,7 @@ mod callback_impl { /// Send an output from the operator: /// - the first argument is the `output_id` as defined in your dataflow. - /// - the second argument is the data as either bytes or pyarrow.UInt8Array for zero copy. + /// - the second argument is the data as either bytes or pyarrow.Array for zero copy. /// - the third argument is dora metadata if you want ot link the tracing from one input into an output. /// `e.g.: send_output("bbox", pa.array([100], type=pa.uint8()), dora_event["metadata"])` #[pymethods] diff --git a/examples/python-operator-dataflow/object_detection.py b/examples/python-operator-dataflow/object_detection.py index 77c4e355..fcd3a213 100755 --- a/examples/python-operator-dataflow/object_detection.py +++ b/examples/python-operator-dataflow/object_detection.py @@ -27,7 +27,7 @@ class Operator: def on_event( self, dora_event: dict, - send_output: Callable[[str, bytes | pa.UInt8Array, Optional[dict]], None], + send_output: Callable[[str, bytes | pa.Array, Optional[dict]], None], ) -> DoraStatus: if dora_event["type"] == "INPUT": return self.on_input(dora_event, send_output) @@ -36,15 +36,15 @@ class Operator: def on_input( self, dora_input: dict, - send_output: Callable[[str, bytes | pa.UInt8Array, Optional[dict]], None], + send_output: Callable[[str, bytes | pa.Array, Optional[dict]], None], ) -> DoraStatus: """Handle image Args: - dora_input (dict): Dict containing the "id", "data", and "metadata" - send_output Callable[[str, bytes | pa.UInt8Array, Optional[dict]], None]: + dora_input (dict): Dict containing the "id", value, and "metadata" + send_output Callable[[str, bytes | pa.Array, Optional[dict]], None]: Function for sending output to the dataflow: - First argument is the `output_id` - - Second argument is the data as either bytes or `pa.UInt8Array` + - Second argument is the data as either bytes or `pa.Array` - Third argument is dora metadata dict e.g.: `send_output("bbox", pa.array([100], type=pa.uint8()), dora_event["metadata"])` """ diff --git a/examples/python-operator-dataflow/plot.py b/examples/python-operator-dataflow/plot.py index e7c32f29..1d240373 100755 --- a/examples/python-operator-dataflow/plot.py +++ b/examples/python-operator-dataflow/plot.py @@ -34,7 +34,7 @@ class Operator: def on_event( self, dora_event: dict, - send_output: Callable[[str, bytes | pa.UInt8Array, Optional[dict]], None], + send_output: Callable[[str, bytes | pa.Array, Optional[dict]], None], ) -> DoraStatus: if dora_event["type"] == "INPUT": return self.on_input(dora_event, send_output) @@ -43,7 +43,7 @@ class Operator: def on_input( self, dora_input: dict, - send_output: Callable[[str, bytes | pa.UInt8Array, Optional[dict]], None], + send_output: Callable[[str, bytes | pa.Array, Optional[dict]], None], ) -> DoraStatus: """ Put image and bounding box on cv2 window. @@ -51,10 +51,10 @@ class Operator: Args: dora_input["id"] (str): Id of the dora_input declared in the yaml configuration dora_input["value"] (arrow array): message of the dora_input - send_output Callable[[str, bytes | pa.UInt8Array, Optional[dict]], None]: + send_output Callable[[str, bytes | pa.Array, Optional[dict]], None]: Function for sending output to the dataflow: - First argument is the `output_id` - - Second argument is the data as either bytes or `pa.UInt8Array` + - Second argument is the data as either bytes or `pa.Array` - Third argument is dora metadata dict e.g.: `send_output("bbox", pa.array([100], type=pa.uint8()), dora_event["metadata"])` """ diff --git a/examples/python-operator-dataflow/webcam.py b/examples/python-operator-dataflow/webcam.py index ae2fbb77..037b34aa 100755 --- a/examples/python-operator-dataflow/webcam.py +++ b/examples/python-operator-dataflow/webcam.py @@ -32,7 +32,7 @@ class Operator: def on_event( self, dora_event: str, - send_output: Callable[[str, bytes | pa.UInt8Array, Optional[dict]], None], + send_output: Callable[[str, bytes | pa.Array, Optional[dict]], None], ) -> DoraStatus: match dora_event["type"]: case "INPUT":