OakCamera¶
The OakCamera class abstracts:
DepthAI API pipeline building with Components.
Debugging features (such as
oak.show_graph()
).AI model sourcing and decoding.
Message syncing & visualization, and much more.
Note
This class will be in alpha stage until depthai-sdk 2.0.0, so there will likely be some API changes.
Interoperability with DepthAI API¶
DepthAI SDK was developed with DepthAI API interoperability in mind.
Users can access all depthai API nodes inside components, and after oak.build()
also the dai.Pipeline
and dai.Device objects.
from depthai_sdk import OakCamera
import depthai as dai
with OakCamera() as oak:
color = oak.create_camera('color')
nn = oak.create_nn('mobilenet-ssd', color)
oak.visualize([nn.out.passthrough, nn], fps=True)
# Build the pipeline, connect to the oak, update components. Place interop logic AFTER oak.build()
pipeline = oak.build()
nn.node.setNumInferenceThreads(2) # Configure components' nodes
features = pipeline.create(dai.node.FeatureTracker) # Create new pipeline nodes
color.node.video.link(features.inputImage)
out = pipeline.create(dai.node.XLinkOut)
out.setStreamName('features')
features.outputFeatures.link(out.input)
oak.start() # Start the pipeline (upload it to the OAK)
q = oak.device.getOutputQueue('features') # Create output queue after calling start()
while oak.running():
if q.has():
result = q.get()
print(result)
# Since we are not in blocking mode, we have to poll oak camera to
# visualize frames, call callbacks, process keyboard keys, etc.
oak.poll()
Examples¶
Below there are a few basic examples. See all examples here.
Here are a few demos that have been developed with DepthAI SDK:
yolo.
Preview color and mono cameras¶
from depthai_sdk import OakCamera
with OakCamera() as oak:
color = oak.create_camera('color')
left = oak.create_camera('left')
right = oak.create_camera('right')
oak.visualize([color, left, right], fps=True)
oak.start(blocking=True)
Run MobilenetSSD on color camera¶
Run face-detection-retail-0004 on left camera¶
from depthai_sdk import OakCamera
with OakCamera() as oak:
left = oak.create_camera('left')
nn = oak.create_nn('face-detection-retail-0004', left)
oak.visualize([nn.out.main, nn.out.passthrough], scale=2/3, fps=True)
oak.start(blocking=True)
Deploy models from Roboflow and Roboflow Universe with Depth SDK¶
from depthai_sdk import OakCamera
# Download & deploy a model from Roboflow universe:
# # https://universe.roboflow.com/david-lee-d0rhs/american-sign-language-letters/dataset/6
with OakCamera() as oak:
color = oak.create_camera('color')
model_config = {
'source': 'roboflow', # Specify that we are downloading the model from Roboflow
'model':'american-sign-language-letters/6',
'key':'181b0f6e43d59ee5ea421cd77f6d9ea2a4b059f8' # Fake API key, replace with your own!
}
nn = oak.create_nn(model_config, color)
oak.visualize(nn, fps=True)
oak.start(blocking=True)
Reference¶
- class depthai_sdk.OakCamera¶
OakCamera improves ease of use when developing apps for OAK devices.
It abstracts DepthAI API pipeline building, different camera permutations, stream recording/replaying, it adds debugging features, does AI model handling, message syncing & visualization, and much more.
It was designed with interoperability with depthai API in mind.
- __init__(device=None, usb_speed=None, replay=None, rotation=0, config=None, args=True)¶
Initializes OakCamera
- Parameters
device (str, optional) – OAK device we want to connect to, either MxId, IP, or USB port
usb_speed (str, optional) – USB speed we want to use. Defaults to ‘auto’.
replay (str, optional) – Replay a depthai-recording - either local path, or from depthai-recordings repo
rotation (int, optional) – Rotate the camera output by this amount of degrees, 0 by default, 90, 180, 270 are supported.
args (None, bool, Dict) – Use user defined arguments when constructing the pipeline
config (Optional[depthai.Device.Config]) –
- create_camera(source, resolution=None, fps=None, encode=None, name=None)¶
Creates Camera component. This abstracts ColorCamera/MonoCamera nodes and supports mocking the camera when recording is passed during OakCamera initialization. Mocking the camera will send frames from the host to the OAK device (via XLinkIn node).
- Parameters
source (str / dai.CameraBoardSocket) – Camera source
resolution (str/SensorResolution) – Sensor resolution of the camera.
fps (float) – Sensor FPS
encode (bool/str/Profile) – Whether we want to enable video encoding (accessible via cameraComponent.out_encoded). If True, it will use MJPEG
name (str) – Name used to identify the X-out stream. This name will also be associated with the frame in the callback function.
- Return type
- create_all_cameras(resolution=None, fps=None, encode=None)¶
Creates Camera component for each camera sensors on the OAK camera.
- Parameters
resolution (str/SensorResolution) – Sensor resolution of the camera.
fps (float) – Sensor FPS
encode (bool/str/Profile) – Whether we want to enable video encoding (accessible via cameraComponent.out_encoded). If True, it will use MJPEG
- Return type
List[depthai_sdk.components.camera_component.CameraComponent]
- create_nn(model, input, nn_type=None, tracker=False, spatial=None, decode_fn=None, name=None)¶
Creates Neural Network component.
- Parameters
model (str / Path) – str for SDK supported model or Path to custom model’s json/blob
input (CameraComponent/NNComponent) – Input to the model. If NNComponent (detector), it creates 2-stage NN
nn_type (str) – Type of the network (yolo/mobilenet) for on-device NN result decoding (only needed if blob path was specified)
tracker (bool) – Enable object tracker, if model is object detector (yolo/mobilenet)
spatial (Union[None, bool, depthai_sdk.components.stereo_component.StereoComponent]) – Calculate 3D spatial coordinates, if model is object detector (yolo/mobilenet) and depth stream is available
decode_fn (Optional[Callable]) – Custom decoding function for the model’s output
name (str) – Name used to identify the X-out stream. This name will also be associated with the frame in the callback function.
- Return type
- create_stereo(resolution=None, fps=None, left=None, right=None, name=None, encode=None)¶
Create Stereo camera component. If left/right cameras/component aren’t specified they will get created internally.
- Parameters
resolution (str/SensorResolution) – If monochrome cameras aren’t already passed, create them and set specified resolution
fps (float) – If monochrome cameras aren’t already passed, create them and set specified FPS
left (CameraComponent/dai.node.MonoCamera) – Pass the camera object (component/node) that will be used for stereo camera.
right (CameraComponent/dai.node.MonoCamera) – Pass the camera object (component/node) that will be used for stereo camera.
name (str) – Name used to identify the X-out stream. This name will also be associated with the frame in the callback function.
encode (bool/str/Profile) – Whether we want to enable video encoding (accessible via StereoComponent.out.encoded). If True, it will use h264 codec.
- Return type
- create_imu()¶
Create IMU component
- config_pipeline(xlink_chunk=None, calib=None, tuning_blob=None, openvino_version=None)¶
Configures DepthAI pipeline. @param xlink_chunk: Chunk size of XLink messages. 0 can result in lower latency @param calib: Calibration data to be uploaded to OAK @param tuning_blob: Camera tuning blob @param openvino_version: Force specific OpenVINO version
- Parameters
xlink_chunk (Optional[int]) –
calib (Optional[depthai.CalibrationHandler]) –
tuning_blob (Optional[str]) –
openvino_version (Union[None, str, depthai.OpenVINO.Version]) –
- start(blocking=False)¶
Start the application - upload the pipeline to the OAK device. :param blocking: Continuously loop and call oak.poll() until program exits :type blocking: bool
- running()¶
Check if camera is running. :returns: True if camera is running, False otherwise.
- Return type
- poll()¶
Poll events; cv2.waitKey, send controls to OAK (if controls are enabled), update, check syncs.
Returns: key pressed from cv2.waitKey, or None if
- Return type
Optional[int]
- build()¶
Connect to the device and build the pipeline based on previously provided configuration. Configure XLink queues, upload the pipeline to the device. This function must only be called once! build() is also called by start(). :returns: Built dai.Pipeline
- Return type
- sync(outputs, callback, visualize=False)¶
Synchronize multiple components outputs forward them to the callback. :param outputs: Component output(s) :param callback: Where to send synced streams :param visualize: Whether to draw on the frames (like with visualize())
- Parameters
outputs (Union[Callable, List[Callable]]) –
callback (Callable) –
- record(outputs, path, record_type=RecordType.VIDEO)¶
Record component outputs. This handles syncing multiple streams (eg. left, right, color, depth) and saving them to the computer in desired format (raw, mp4, mcap, bag..). :param outputs: Component output(s) to be recorded :type outputs: Component/Component output :param path: Folder path where to save these streams :param record_type: Record type
- Parameters
outputs (Union[Callable, List[Callable]]) –
path (str) –
record_type (depthai_sdk.record.RecordType) –
- show_graph()¶
Shows DepthAI Pipeline graph, which can be useful when debugging. Builds the pipeline (oak.build()).
- visualize(output, record_path=None, scale=None, fps=False, callback=None)¶
Visualize component output(s). This handles output streaming (OAK->host), message syncing, and visualizing. :param output: Component output(s) to be visualized. If component is passed, SDK will visualize its default output (out()) :type output: Component/Component output :param record_path: Path where to store the recording (visualization window name gets appended to that path), supported formats: mp4, avi :param scale: Scale the output window by this factor :param fps: Whether to show FPS on the output window :param callback: Instead of showing the frame, pass the Packet to the callback function, where it can be displayed
- callback(output, callback, enable_visualizer=False)¶
Create a callback for the component output(s). This handles output streaming (OAK->Host) and message syncing. :param output: Component output(s) to be visualized. If component is passed, SDK will visualize its default output. :param callback: Handler function to which the Packet will be sent. :param enable_visualizer: Whether to enable visualizer for this output.
- Parameters
output (Union[List, Callable, depthai_sdk.components.component.Component]) –
callback (Callable) –
enable_visualizer (bool) –
- ros_stream(output)¶
- Parameters
output (Union[List, Callable, depthai_sdk.components.component.Component]) –
- trigger_action(trigger, action)¶
- Parameters
trigger (depthai_sdk.trigger_action.triggers.abstract_trigger.Trigger) –
action (Union[depthai_sdk.trigger_action.actions.abstract_action.Action, Callable]) –
- set_max_queue_size(size)¶
Set maximum queue size for all outputs. This is the maximum number of frames that can be stored in the queue. :param size: Maximum queue size for all outputs.
- Parameters
size (int) –
- property device: depthai.Device¶
Returns dai.Device object. oak.built() has to be called before querying this property!
- property sensors: List[depthai.CameraBoardSocket]¶
Returns list of all sensors added to the pipeline.