OAK-D
Spectacular AI Plugin for Luxonis Depth AI cameras
Supported devices
OAK-D models with IMU sensors are supported. This includes but is not limited to
OAK-D (Pro) W
OAK-D LR
OAK-D PoE
rae (available soon)
OAK-D Lite or OAK-1 are not supported due to the lack of IMU (not because of monocularity). For the PoE models, or devices connected via USB2, there may be issues with reading the data out of the device fast enough.
Installation
First install development dependencies.
Linux only: set up OAK-D udev rules.
For data recording also install FFmpeg.
Note: On Linux, you may also need to sudo apt install python3-tk
to run the Matplotlib-based visualizations
Install from Pip:
pip install spectacularAI[full]
The postfix [full]
will also install the sai-cli tool and the requirements for the visualizations and examples.
In more advanced use of the SDK, it may not be needed.
Quick start
Install the system dependencies:
sudo apt install zlib libstdc++ libusb-1.0-0-dev
Download the the SDK archive from the SDK releases page.
Unpack the archive to a folder and run the following commands in there.
Attach your OAK-D device to a USB3 port, using a USB3 cable
(optional smoke test) Run the JSONL example:
cd bin ./vio_jsonl # or, on Windows: vio_jsonl.exe # Now you should see rapidly flowing JSONL text # press Ctrl+C to exit
Run the Python example (in the bin directory):
pip install matplotlib # install dependencies python vio_visu.py
Move the OAK-D around, avoid pointing at blank walls or covering the cameras. The plotted trajectory should follow the movement of the device.
Installation as a library (Linux)
Select where you want the library installed, e.g.,:
export MY_INSTALL_PREFIX=~/.local # or: export MY_INSTALL_PREFIX=`pwd`/installed
Run
make PREFIX=$MY_INSTALL_PREFIX install
(orsudo make install
)Build the example using CMake:
make PREFIX=$MY_INSTALL_PREFIX examples
Run the example:
./examples/target/vio_jsonl
Installation as a library (Windows)
Build the example:
cd examples mkdir target cd target
To properly pass arguments to cmake in PowerShell we need a bit more elaborate command, depending on the shell you are using pick A) or B).
In PowerShell:
Start-Process cmake -ArgumentList "-G ""Visual Studio 16 2019"" -A x64 -DspectacularAI_depthaiPlugin_DIR=..\lib\cmake\spectacularAI -Ddepthai_DIR=..\lib\cmake\depthai .." -NoNewWindow
In Git Bash or similar:
cmake -G "Visual Studio 16 2019" -A x64 -DspectacularAI_depthaiPlugin_DIR=../lib/cmake/spectacularAI -Ddepthai_DIR=../lib/cmake/depthai ..
Then execute the build:
cmake --build . --config Release -- - m
Running the vio_jsonl.exe should give you the pose of the OAK-D device in real time:
cd Release ./vio_jsonl.exe
Example output:
{"orientation":{"w":0.7068698348716513,"x":0.02283470213352065,"y":-0.011350438374188287,"z":0.7068838521820336},"position":{"x":-0.016812673347013137,"y":-0.0231306465130168,"z":-0.0013136235444364183},"time":61088.131537828,"velocity":{"x":-3.936320861854323e-06,"y":-1.8569468854259723e-06,"z":0.00031940298071614516}}
Examples
A comprehensive set of examples are available at the SDK examples repository:
The main steps for using this SDK are:
Initialize a
depthai.Pipeline
(see Luxonis documentation for more info)Create a
spectacularAI.depthai.Pipeline
using that (with optional configuration as keyword arguments, seespectacularAI.depthai.Configuration
)Create a
spectacularAI.depthai.Session
usingstartSession()
Poll outputs from the VIO session queue using
getOutput()
in a loop wherework()
is also periodically calledUtilize the
spectacularAI.VioOutput
objects with 6-DoF poses and other data
import depthai
import spectacularAI
import time
pipeline = depthai.Pipeline() # -- 1 --
vio_pipeline = spectacularAI.depthai.Pipeline(pipeline) # -- 2 --
# options, e.g.: spectacularAI.depthai.Pipeline(pipeline, useStereo=False)
with depthai.Device(pipeline) as device:
vio_session = vio_pipeline.startSession(device) # -- 3 --
while True:
if vio_session.hasOutput():
out = vio_session.getOutput() # -- 4 --
print(out.asJson()) # -- 5 --
else:
if not vio_session.work():
time.sleep(0.005)
#include <iostream>
#include <depthai/depthai.hpp>
#include <spectacularAI/depthai/plugin.hpp>
int main() {
dai::Pipeline pipeline; // -- 1 --
spectacularAI::daiPlugin::Configuration config; // Optional configuration
// config.useStereo = false;
spectacularAI::daiPlugin::Pipeline vioPipeline(pipeline, config); // -- 2 --
dai::Device device(pipeline);
auto vioSession = vioPipeline.startSession(device); // -- 3 --
while (true) {
auto vioOut = vioSession->waitForOutput(); // -- 4 --
std::cout << vioOut->asJson() << std::endl; // -- 5 --
}
return 0;
}
Recording data
Requirements: install FFmpeg before recording.
To record data for troubleshooting and offline replay, see:
sai-cli record oak --help
To record data without Python, you can use the vio_jsonl
executable built in the Installation / Quick start
section by giving it a second argument as the recording folder:
./vio_jsonl /path/to/recording/folder
# or, on Windows: vio_jsonl.exe /path/to/recording/folder
Troubleshooting and customization
Camera calibration
Rarely, the OAK-D device factory calibration may be inaccurate, which may cause the VIO performance to be always very bad in all environments. If this is the case, the device can be recalibrated following Luxonis’ instructions (see also our instructions for fisheye cameras for extra tips).
Also calibrate the camera according to these instructions, if you have changed the lenses or the device did not include a factory calibration.
Frame rate
The camera frame rate can be controlled with the Depth AI methods:
vio_pipeline = spectacularAI.depthai.Pipeline(pipeline)
changed_fps = 25 # new
vio_pipeline.monoLeft.setFps(changed_fps) # new
vio_pipeline.monoRight.setFps(changed_fps) # new
Reducing the frame rate (the default is 30) can be used to lower power consumption at the expense of accuracy. Depending on the use case (vehicular, hand-held, etc.), frame rates as low as 10 or 15 FPS may yield acceptable performance.
Camera modes
By default, the SDK reads the following types of data from the OAK devices:
Depth map at full FPS (30 FPS)
Sparse image features at full FPS
Rectified monochrome images from two cameras at a reduced FPS (resolution 400p)
IMU data at full frequency (> 200Hz)
This can be controlled with the following configuration flags, which can be modified using the spectacularAI.depthai.Configuration
object, for example:
config = spectacularAI.depthai.Configuration()
config.useStereo = False # example: enable monocular mode
vio_pipeline = spectacularAI.depthai.Pipeline(pipeline, config)
Arbitrary combinations of configuration changes are not supported, and non-default configurations are not guaranteed to be forward-compatible (may break between SDK releases). Changing the configuration is not expected to improve performance in general, but may help in specific use cases. Testing the following modes is encouraged:
useFeatureTracker = False
. Disabled accelerated feature tracking, which can improve accuracy, but also increases CPU consumption. Causes depth map and feature inputs to be replaced with full FPS monochrome image data.
useStereo = False
. Enable monocular mode. Reduces accuracy and robustness but also decreases CPU consumption.
useSlam = False
. Disable loop closures and other related processing. Can make the relative pose changes more predictable. Disables reduced FPS image data input.
useVioAutoExposure = True
. Enable custom auto-exposure to improve low-light scenarios and reduce motion blur (BETA).
Unsupported OAK-D models
Some (less common) OAK models require setting certain parameters manually. Namely, the IMU-to-camera matrix may need to be changed if the device model was not recognized by the SDK. For example:
vio_pipeline = spectacularAI.depthai.Pipeline(pipeline)
# manual IMU-to-camera matrix configuration
vio_pipeline.imuToCameraLeft = [
[0, 1, 0, 0],
[1, 0, 0, 0],
[0, 0,-1, 0],
[0, 0, 0, 1]
]
Running on Jetson
Running on Jetson (Nano) requires some additional steps in order to get the SDK working. Luxonis has more detailed at https://docs.luxonis.com/projects/api/en/latest/install/#jetson, but below are the minimum required steps.
Open a terminal window and run the following commands:
sudo apt update && sudo apt upgrade
sudo reboot now
Change the size of your SWAP. These instructions come from the Getting Started with AI on Jetson from Nvidia:
# Disable ZRAM:
sudo systemctl disable nvzramconfig
# Create 4GB swap file
sudo fallocate -l 4G /mnt/4GB.swap
sudo chmod 600 /mnt/4GB.swap
sudo mkswap /mnt/4GB.swap
(Optional) If you have an issue with the final command, you can try the following:
sudo vi /etc/fstab
# Add this line at the bottom of the file
/mnt/4GB.swap swap swap defaults 0 0
# Reboot
sudo reboot now
API reference
The classes specific to the Depth AI (OAK-D) plugin are documented below. For the main output classes, refer to the C++ documentation in Core SDK.
Configuration
- class spectacularAI.depthai.Configuration(*args, **kwargs)
Plugin and Spectacular AI VIO SDK configuration variables.
Overloaded function.
__init__(self: spectacularAI.depthai.Configuration) -> None
__init__(self: spectacularAI.depthai.Configuration, **kwargs) -> None
- property accFrequencyHz
- property aprilTagPath
Path to .json file with AprilTag information. AprilTag detection is enabled when not empty. For the file format see: https://github.com/SpectacularAI/docs/blob/main/pdf/april_tag_instructions.pdf. Note: sets useSlam=true
- asDict(self: object) dict
Dictionary representation of this configuration.
- property depthQueueSize
- property depthScaleCorrection
DEPRECATED
- property disableCameras
Disables cameras + VIO, only useful for recording.
- property ensureSufficientUsbSpeed
- property extendedDisparity
Use DepthAI extended disparity mode
- property fastImu
- property fastVio
Use more light-weight VIO settings
- property forceRectified
- property forceUnrectified
- property gyroFrequencyHz
- property imuFrequencyHz
DEPRECATED, use accFrequencyHz and gyroFrequencyHz instead
- property imuQueueSize
- property imuToGnss
Vector3d
: (Optional) When using GNSS, translation offset from IMU to GNSS position/antenna
- property inputResolution
- property internalParameters
Internal SDK parameters (key-value pairs converted to string-string). Not safe for unsanitized user input
- property keyframeCandidateEveryNthFrame
When
useSlam = True
,useFeatureTracker = True
andkeyframeCandidateEveryNthFrame > 0
, a mono gray image is captured every N frames for SLAM.
- property lowLatency
When enabled, outputs pose at very low latency on every IMU sample instead of camera frame
- property mapLoadPath
Load existing SLAM map (.bin format required), enables relocalizatin mode. NOTE: requires useSlam=true.
- property mapSavePath
SLAM map is serialized to this path. Supported outputs types: .ply, .csv and .pcd (point cloud), and .bin (Spectacular AI SLAM map). NOTE: requires useSlam=true.
- property meshRectification
DEPRECATED
- property monoQueueSize
- property parameterSets
Parameter sets used, use append unless you really know what you are doing
- property recordingFolder
- property recordingOnly
Disables VIO and only records session when recordingFolder is set.
- property silenceUsbWarnings
- update(self: object, **kwargs) None
Update the contents of this object with kwargs corresponding to a subset of the member names
- property useColor
Use DepthAI color camera for tracking. Only supported for OAK-D series 2.
- property useColorStereoCameras
When device has stereo color cameras
- property useEncodedVideo
Encode stereo camera video on the OAK-D device, cannot be used for live tracking
- property useFeatureTracker
Use Movidius VPU-accelelerated feature tracking
- property useGrayDepth
Use one gray frame and depth for tracking
- property useReaderThread
DEPRECATED
- property useSlam
Enable the SLAM module
- property useStereo
Use stereo vision. Set to false for monocular mode (i.e., using one camera only).
- property useVioAutoExposure
Enable SpectacularAI auto exposure which optimizes exposure parameters for VIO performance (BETA)
Defined in #include <spectacularAI/depthai/configuration.hpp>
-
namespace spectacularAI
-
namespace daiPlugin
-
struct Configuration
Plugin and Spectacular AI VIO SDK configuration variables.
Public Members
-
bool useStereo = true
-
bool useSlam = true
-
bool useFeatureTracker = true
-
bool fastVio = false
-
bool lowLatency = false
-
bool forceRectified = false
-
bool forceUnrectified = false
-
bool useColor = false
-
bool useColorStereoCameras = false
-
bool useEncodedVideo = false
-
bool useGrayDepth = false
-
std::string mapSavePath = ""
-
std::string mapLoadPath = ""
-
bool useVioAutoExposure = false
-
std::string aprilTagPath = ""
-
bool meshRectification = false
-
bool depthScaleCorrection = false
-
bool extendedDisparity = false
-
bool fastImu = false
-
bool useReaderThread = true
-
unsigned imuFrequencyHz = 0
-
unsigned accFrequencyHz = 500
-
unsigned gyroFrequencyHz = 400
-
bool ensureSufficientUsbSpeed = true
-
bool silenceUsbWarnings = false
-
unsigned monoQueueSize = 8
-
unsigned depthQueueSize = 20
-
unsigned imuQueueSize = 50
-
int keyframeCandidateEveryNthFrame = 6
-
std::string inputResolution = "400p"
-
std::string recordingFolder = ""
-
bool recordingOnly = false
-
bool disableCameras = false
-
std::shared_ptr<Vector3d> imuToGnss
-
std::vector<std::string> parameterSets = {"wrapper-base", "oak-d", "live"}
-
std::map<std::string, std::string> internalParameters
Internal SDK parameter overrides (key-value pairs). Not safe for unsanitized user input.
-
bool useStereo = true
-
struct Configuration
-
namespace daiPlugin
Pipeline
- class spectacularAI.depthai.Pipeline(*args, **kwargs)
Spectacular AI pipeline for Depth AI API. It is recommended to build this using the constructors provided, but it is also possible to replace or configure all parts manually. The class properties correspond to Depth AI objects created by the Spetacular AI SDK and it is possbile to share them, e.g., by creating new output links from them, but modifying their settings (e.g., changing camera FPS), might affect VIO performance.
Overloaded function.
__init__(self: spectacularAI.depthai.Pipeline, arg0: object) -> None
__init__(self: spectacularAI.depthai.Pipeline, arg0: object, arg1: spectacularAI.depthai.Configuration) -> None
Initialize with a
depthai.Pipeline
and customConfiguration
__init__(self: spectacularAI.depthai.Pipeline, arg0: object, arg1: spectacularAI.depthai.Configuration, arg2: Callable[[spectacularAI.mapping.MapperOutput], None]) -> None
Initialize with a
depthai.Pipeline
and customConfiguration
with a mapper callback function__init__(self: spectacularAI.depthai.Pipeline, arg0: object, **kwargs) -> None
Initialize with a
depthai.Pipeline
and custom kwargs (seeConfiguration
)- property color
DepthAI color camera node. Requires OAK-D Series 2 and
useColor=true
(seeConfiguration
).
- property colorLeft
DepthAI left color stereo camera node
- property colorPrimary
DepthAI primary color stereo camera node
- property colorRight
DepthAI right color stereo camera node
- property colorSecondary
DepthAI secondary color stereo camera node
- property featureTracker
DepthAI feature tracker node
- property hooks
Hooks to access raw data received from DepthAI such as IMU, tracked features and depth frames
- property imu
DepthAI IMU node
- property imuToCameraLeft
IMU to left camera extrinsic matrix
- property monoLeft
DepthAI left monocular camera node
- property monoPrimary
DepthAI primary monocular camera node
- property monoRight
DepthAI right monocular camera node
- property monoSecondary
DepthAI secondary monocular camera node
- property spectacularAIConfigurationYAML
SDK internal override parameters (do not touch)
- startSession(self: spectacularAI.depthai.Pipeline, arg0: object) spectacularAI::daiPlugin::Session
Start a VIO session. The argument must be a
depthai.Device
- property stereo
DepthAI stereo depth node
- property xoutDepth
- property xoutFeatures
- property xoutImu
- property xoutLeft
- property xoutRight
Defined in #include <spectacularAI/depthai/pipeline.hpp>
-
namespace dai
-
namespace spectacularAI
-
namespace daiPlugin
-
struct Pipeline
Spectacular AI pipeline for Depth AI API. It is recommended to build this using the constructors provided, but it is also possible to replace or configure all parts manually.
Public Functions
-
Pipeline(DaiPipeline daiPipeline)
Create a pipeline with the default configuration.
-
Pipeline(DaiPipeline daiPipeline, const Configuration &config)
Create a pipeline with custom configuration
-
Pipeline(DaiPipeline daiPipeline, const Configuration &config, std::function<void(mapping::MapperOutputPtr)> onMapperOutput)
Create a pipeline with custom configuration with Mapping API enabled
-
std::unique_ptr<Session> startSession(DaiDevice device)
Start a new VIO session on the given Depth AI device.
Public Members
-
const Configuration configuration
Spectacular AI VIO SDK configuration
-
IMUNode imu
-
MonoCameraNode monoLeft
-
MonoCameraNode monoRight
-
MonoCameraNode monoPrimary
-
MonoCameraNode monoSecondary
-
ColorCameraNode colorLeft
-
ColorCameraNode colorRight
-
ColorCameraNode colorPrimary
-
ColorCameraNode colorSecondary
-
ColorCameraNode color
-
ImageManipNode colorImageManip
-
StereoDepthNode stereo
-
FeatureTrackerNode featureTracker
-
ScriptNode scriptPrimary
-
ScriptNode scriptSecondary
-
VideoEncoderNode videoEncoderPrimary
-
VideoEncoderNode videoEncoderSecondary
-
XLinkInNode xinControl
-
XLinkOutNode xoutImu
-
XLinkOutNode xoutLeft
-
XLinkOutNode xoutRight
-
XLinkOutNode xoutScriptPrimary
-
XLinkOutNode xoutScriptSecondary
-
XLinkOutNode xoutPrimary
-
XLinkOutNode xoutSecondary
-
XLinkOutNode xoutFeatures
-
XLinkOutNode xoutDepth
-
Matrix4d imuToCameraLeft = {}
-
std::string spectacularAIConfigurationYAML
-
Hooks hooks
-
const std::function<void(mapping::MapperOutputPtr)> onMapperOutput
-
Pipeline(DaiPipeline daiPipeline)
-
struct Pipeline
-
namespace daiPlugin
Session
- class spectacularAI.depthai.Session
VIO session. Should be created via
spectacularAI.depthai.Pipeline.startSession()
- addAbsolutePose(self: spectacularAI.depthai.Session, arg0: spectacularAI.Pose, arg1: List[List[float[3]][3]], arg2: float) None
Add external pose information.VIO will correct its estimates to match the pose.
- addGnss(self: spectacularAI.depthai.Session, arg0: float, arg1: spectacularAI.WgsCoordinates, arg2: List[List[float[3]][3]]) None
Add GNSS input (for GNSS-VIO fusion)
- addTrigger(self: spectacularAI.depthai.Session, arg0: float, arg1: int) None
Add an external trigger input. Causes additional output corresponding to a certain timestamp to be generated.
- close(self: spectacularAI.depthai.Session) None
Close VIO session and free resources. Also consider using the
with
statement
- getOutput(self: spectacularAI.depthai.Session) spectacularAI.VioOutput
Removes the first unread output from an internal queue and returns it
- getRgbCameraPose(self: spectacularAI.depthai.Session, arg0: spectacularAI.VioOutput) spectacularAI.CameraPose
Get the
CameraPose
corresponding to the OAK RGB camera at a certainVioOutput
.
- hasOutput(self: spectacularAI.depthai.Session) bool
Check if there is new output available
- waitForOutput(self: spectacularAI.depthai.Session) spectacularAI.VioOutput
Waits until there is new output available and returns it
- work(self: spectacularAI.depthai.Session) bool
DEPRECATED
Defined in #include <spectacularAI/depthai/session.hpp>
-
namespace spectacularAI
-
namespace daiPlugin
-
struct Session
VIO session. Should be created via Pipeline::startSession.
Public Functions
-
virtual bool hasOutput() const = 0
Check if new output is available
-
virtual std::shared_ptr<const VioOutput> getOutput() = 0
Get output from the queue, if available. If not, returns {}
-
virtual std::shared_ptr<const VioOutput> waitForOutput() = 0
Wait until new output is available and then return it.
-
virtual bool work() = 0
DEPRECATED, do not use.
-
virtual void addTrigger(double t, int tag) = 0
Add an external trigger input. Causes additional output corresponding to a certain timestamp to be generated.
- Parameters:
t – timestamp, monotonic float seconds
tag – additonal tag to indentify this particular trigger event. The default outputs corresponding to input camera frames have a tag 0.
-
virtual void addAbsolutePose(const Pose &pose, const Matrix3d &positionCovariance, double orientationVariance = -1) = 0
Add external pose information. VIO will correct its estimates to match the pose.
- Parameters:
pose – pose of the output coordinates in the external world coordinates
positionCovariance – position uncertainty as a covariance matrix in the external world coordinates
orientationVariance – optional orientation uncertainty as variance of angle
-
virtual void addGnss(double timestamp, const WgsCoordinates &coordinates, const Matrix3d &enuPositionCovariance) = 0
Add GNSS input (for GNSS-VIO fusion)
- Parameters:
timestamp – timestamp of the GNSS fix
coordinates – position mean
enuPositionCovariance – position uncertainty as a covariance matrix in an East-North-Up (ENU) coordinate system
-
virtual CameraPose getRgbCameraPose(const VioOutput &vioOut) const = 0
-
virtual ~Session()
-
virtual bool hasOutput() const = 0
-
struct Session
-
namespace daiPlugin
Hooks API
- class spectacularAI.depthai.Hooks
DepthAI data hooks
- property color
DepthAI color images
- property depth
DepthAI depth images
- property imu
DepthAI IMU data
- property monoPrimary
DepthAI primary monocular camera images
- property monoSecondary
DepthAI secondary monocular camera images
- property trackedFeatures
DepthAI tracked features
Defined in #include <spectacularAI/depthai/hooks.hpp>
Defines
-
ImageHook
-
ImuHook
-
FeatureHook
-
namespace spectacularAI
-
namespace daiPlugin
-
struct Hooks
When the plugin pulls something from the Depth AI API, those intermediary outputs can also be accessed through these hooks. Note that an input is not used by the plugin with the given Configuration, the corresponding hook is never triggered.
Depending on the configuration, the hooks may not be invoked from the same thread in which they were created.
Public Members
-
std::function<void(std::shared_ptr<dai::IMUData>)> imu
-
std::function<void(std::shared_ptr<dai::ImgFrame>)> monoPrimary
-
std::function<void(std::shared_ptr<dai::ImgFrame>)> monoSecondary
-
std::function<void(std::shared_ptr<dai::ImgFrame>)> depth
-
std::function<void(std::shared_ptr<dai::ImgFrame>)> color
-
std::function<void(std::shared_ptr<dai::TrackedFeatures>)> trackedFeatures
-
std::function<void(std::shared_ptr<dai::IMUData>)> imu
-
struct Hooks
-
namespace daiPlugin