Skip to content

Commit

Permalink
Merge branch 'v3_develop' into v3_snaps_error_handling
Browse files Browse the repository at this point in the history
  • Loading branch information
Serafadam committed Dec 18, 2024
2 parents 6af1b59 + 353dda8 commit 58f7e4a
Show file tree
Hide file tree
Showing 48 changed files with 794 additions and 172 deletions.
2 changes: 1 addition & 1 deletion 3rdparty/foxglove/ws-protocol
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -162,7 +162,7 @@ endif()
# Create depthai project
project(depthai VERSION "3.0.0" LANGUAGES CXX C)
set(DEPTHAI_PRE_RELEASE_TYPE "alpha") # Valid options are "alpha", "beta", "rc", ""
set(DEPTHAI_PRE_RELEASE_VERSION "10")
set(DEPTHAI_PRE_RELEASE_VERSION "11")

# Set DEPTHAI_VERSION universally, not conditionally
set(DEPTHAI_VERSION ${PROJECT_VERSION}-${DEPTHAI_PRE_RELEASE_TYPE}.${DEPTHAI_PRE_RELEASE_VERSION})
Expand Down
1 change: 1 addition & 0 deletions bindings/python/src/DeviceBindings.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -556,6 +556,7 @@ void DeviceBindings::bind(pybind11::module& m, void* pCallstack){
.def("setTimesync", [](DeviceBase& d, bool e) { py::gil_scoped_release release; return d.setTimesync(e); }, py::arg("enable"), DOC(dai, DeviceBase, setTimesync, 2))
.def("getDeviceName", [](DeviceBase& d) { std::string name; { py::gil_scoped_release release; name = d.getDeviceName(); } return py::bytes(name).attr("decode")("utf-8", "replace"); }, DOC(dai, DeviceBase, getDeviceName))
.def("getProductName", [](DeviceBase& d) { std::string name; { py::gil_scoped_release release; name = d.getProductName(); } return py::bytes(name).attr("decode")("utf-8", "replace"); }, DOC(dai, DeviceBase, getProductName))
.def("crashDevice", [](DeviceBase& d) { py::gil_scoped_release release; return d.crashDevice(); }, DOC(dai, DeviceBase, crashDevice))
;


Expand Down
30 changes: 18 additions & 12 deletions bindings/python/src/MessageQueueBindings.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,15 +40,25 @@ void MessageQueueBindings::bind(pybind11::module& m, void* pCallstack) {

// Bind DataOutputQueue
auto addCallbackLambda = [](MessageQueue& q, py::function cb) -> int {
pybind11::module inspect_module = pybind11::module::import("inspect");
pybind11::object result = inspect_module.attr("signature")(cb).attr("parameters");
pybind11::module inspectModule = pybind11::module::import("inspect");
pybind11::object result = inspectModule.attr("signature")(cb).attr("parameters");
auto numParams = pybind11::len(result);
if(numParams == 2) {
return q.addCallback(cb.cast<std::function<void(std::string, std::shared_ptr<ADatatype>)>>());
} else if(numParams == 1) {
return q.addCallback(cb.cast<std::function<void(std::shared_ptr<ADatatype>)>>());
} else if(numParams == 0) {
return q.addCallback(cb.cast<std::function<void()>>());

if (numParams == 2) {
return q.addCallback([cb](std::string msg, std::shared_ptr<ADatatype> data) {
pybind11::gil_scoped_acquire gil;
cb(msg, data);
});
} else if (numParams == 1) {
return q.addCallback([cb](std::shared_ptr<ADatatype> data) {
pybind11::gil_scoped_acquire gil;
cb(data);
});
} else if (numParams == 0) {
return q.addCallback([cb]() {
pybind11::gil_scoped_acquire gil;
cb();
});
} else {
throw py::value_error("Callback must take either zero, one or two arguments");
}
Expand Down Expand Up @@ -110,10 +120,6 @@ void MessageQueueBindings::bind(pybind11::module& m, void* pCallstack) {
}
if(PyErr_CheckSignals() != 0) throw py::error_already_set();
}
{
py::gil_scoped_release release;
d = obj.get(timeout, timedout);
}
if(PyErr_CheckSignals() != 0) throw py::error_already_set();
return d;
},
Expand Down
6 changes: 3 additions & 3 deletions bindings/python/src/pipeline/CommonBindings.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -192,9 +192,9 @@ void CommonBindings::bind(pybind11::module& m, void* pCallstack){
.def_readwrite("qz", &Quaterniond::qz)
.def_readwrite("qw", &Quaterniond::qw)
;
size2f
.def(py::init<>())
.def(py::init<float, float>())
size2f.def(py::init<>())
.def(py::init<float, float>(), py::arg("width"), py::arg("height"))
.def(py::init<float, float, bool>(), py::arg("width"), py::arg("height"), py::arg("normalized"))
.def_readwrite("width", &Size2f::width)
.def_readwrite("height", &Size2f::height)
.def("isNormalized", &Size2f::isNormalized)
Expand Down
8 changes: 2 additions & 6 deletions bindings/python/src/pipeline/PipelineBindings.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -123,11 +123,7 @@ void PipelineBindings::bind(pybind11::module& m, void* pCallstack){
d.wait();
})
//.def(py::init<const Pipeline&>())
.def("getDefaultDevice", [](Pipeline& p) -> py::object {
auto device = p.getDefaultDevice();
if(!device) return py::none();
return py::cast(device);
}, DOC(dai, Pipeline, getDefaultDevice))
.def("getDefaultDevice", &Pipeline::getDefaultDevice, DOC(dai, Pipeline, getDefaultDevice))
.def("getGlobalProperties", &Pipeline::getGlobalProperties, DOC(dai, Pipeline, getGlobalProperties))
//.def("create", &Pipeline::create<node::XLinkIn>)
.def("remove", &Pipeline::remove, py::arg("node"), DOC(dai, Pipeline, remove))
Expand Down Expand Up @@ -244,7 +240,7 @@ void PipelineBindings::bind(pybind11::module& m, void* pCallstack){
py::gil_scoped_release release;
p.wait();
})
.def("stop", &Pipeline::stop)
.def("stop", &Pipeline::stop, py::call_guard<py::gil_scoped_release>(), DOC(dai, Pipeline, stop))
.def("run",
[](Pipeline& p) {
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,6 @@ void bind_imagemanipconfigv2(pybind11::module& m, void* pCallstack) {
py::arg("rect"),
py::arg("normalizedCoords"),
DOC(dai, ImageManipConfigV2, addCropRotatedRect))
.def("addResize", &ImageManipConfigV2::addResize, py::arg("w"), py::arg("h"), DOC(dai, ImageManipConfigV2, addResize))
.def(
"addScale", [](ImageManipConfigV2& self, float scale) { return self.addScale(scale); }, py::arg("scale"), DOC(dai, ImageManipConfigV2, addScale))
.def(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -152,6 +152,7 @@ void bind_stereodepthconfig(pybind11::module& m, void* pCallstack){
.def(py::init<>())
.def_readwrite("enable", &StereoDepthConfig::PostProcessing::SpeckleFilter::enable, DOC(dai, StereoDepthConfig, PostProcessing, SpeckleFilter, enable))
.def_readwrite("speckleRange", &StereoDepthConfig::PostProcessing::SpeckleFilter::speckleRange, DOC(dai, StereoDepthConfig, PostProcessing, SpeckleFilter, speckleRange))
.def_readwrite("differenceThreshold", &StereoDepthConfig::PostProcessing::SpeckleFilter::differenceThreshold, DOC(dai, StereoDepthConfig, PostProcessing, SpeckleFilter, differenceThreshold))
;

decimationMode
Expand Down Expand Up @@ -183,6 +184,7 @@ void bind_stereodepthconfig(pybind11::module& m, void* pCallstack){

postProcessing
.def(py::init<>())
.def_readwrite("filteringOrder", &StereoDepthConfig::PostProcessing::filteringOrder, DOC(dai, StereoDepthConfig, PostProcessing, filteringOrder))
.def_readwrite("median", &StereoDepthConfig::PostProcessing::median, DOC(dai, StereoDepthConfig, PostProcessing, median))
.def_readwrite("bilateralSigmaValue", &StereoDepthConfig::PostProcessing::bilateralSigmaValue, DOC(dai, StereoDepthConfig, PostProcessing, bilateralSigmaValue))
.def_readwrite("spatialFilter", &StereoDepthConfig::PostProcessing::spatialFilter, DOC(dai, StereoDepthConfig, PostProcessing, spatialFilter))
Expand Down
16 changes: 1 addition & 15 deletions bindings/python/src/pipeline/node/NodeBindings.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -402,21 +402,7 @@ void NodeBindings::bind(pybind11::module& m, void* pCallstack) {
static_cast<AssetManager& (Node::*)()>(&Node::getAssetManager),
py::return_value_policy::reference_internal,
DOC(dai, Node, getAssetManager));
// .def_property_readonly( // TODO - This casting of the inputs/outputs might be illegal / cause bad behavior
// "io",
// [](Node& n) -> py::object {
// auto dict = py::dict();
// for(auto& output : n.getOutputRefs()) {
// // TODO - Revisit, pybind might try to release the output when refcount goes to zero
// dict[py::str(output->name)] = output;
// }
// for(auto& input : n.getInputRefs()) {
// // TODO - Revisit, pybind might try to release the input when refcount goes to zero
// dict[py::str(input->getName())] = input;
// }
// return dict;
// },
// py::return_value_policy::reference_internal);


// TODO(themarpe) - refactor, threaded node could be separate from Node
pyThreadedNode.def("trace", [](dai::ThreadedNode& node, const std::string& msg) { node.logger->trace(msg); })
Expand Down
19 changes: 19 additions & 0 deletions bindings/python/src/pipeline/node/ScriptBindings.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,25 @@ void bind_script(pybind11::module& m, void* pCallstack){
script
.def_readonly("inputs", &Script::inputs)
.def_readonly("outputs", &Script::outputs)
#ifdef DEPTHAI_SCRIPT_NODE_ADD_IO
.def_property_readonly(
"io",
[](Node& n) -> py::object {
auto dict = py::dict();
for(auto& output : n.getOutputRefs()) {
dict[py::str(output->getName())] = output;
}
for(auto& input : n.getInputRefs()) {
// Check if the key is already taken an throw an error
if(dict.contains(py::str(input->getName()))) {
throw std::runtime_error("Input with name '" + input->getName() + "' already exists in the node");
}
dict[py::str(input->getName())] = input;
}
return dict;
},
py::return_value_policy::reference_internal)
#endif
.def("setScriptPath", &Script::setScriptPath, DOC(dai, node, Script, setScriptPath))
.def("setScript", py::overload_cast<const std::string&, const std::string&>(&Script::setScript), py::arg("script"), py::arg("name") = "", DOC(dai, node, Script, setScript))
.def("setScript", py::overload_cast<const std::vector<std::uint8_t>&, const std::string&>(&Script::setScript), py::arg("data"), py::arg("name") = "", DOC(dai, node, Script, setScript, 2))
Expand Down
22 changes: 20 additions & 2 deletions bindings/python/src/pipeline/node/StereoDepthBindings.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,8 +64,25 @@ void bind_stereodepth(pybind11::module& m, void* pCallstack){
;

stereoDepthPresetMode
.value("HIGH_ACCURACY", StereoDepth::PresetMode::HIGH_ACCURACY, DOC(dai, node, StereoDepth, PresetMode, HIGH_ACCURACY))
.value("HIGH_DENSITY", StereoDepth::PresetMode::HIGH_DENSITY, DOC(dai, node, StereoDepth, PresetMode, HIGH_DENSITY))
.value("HIGH_ACCURACY", StereoDepth::PresetMode::HIGH_ACCURACY, "**Deprecated:** Will be removed in future releases and replaced with DEFAULT")
.value("HIGH_DENSITY", StereoDepth::PresetMode::HIGH_DENSITY, "**Deprecated:** Will be removed in future releases and replaced with DEFAULT")

.value("DEFAULT", StereoDepth::PresetMode::DEFAULT)
.value("FACE", StereoDepth::PresetMode::FACE)
.value("HIGH_DETAIL", StereoDepth::PresetMode::HIGH_DETAIL)
.value("ROBOTICS", StereoDepth::PresetMode::ROBOTICS)

// Deprecated overriden
.def_property_readonly_static("HIGH_ACCURACY", [](py::object){
PyErr_WarnEx(PyExc_DeprecationWarning, "HIGH_ACCURACY is deprecated, will be removed in future releases and replaced with DEFAULT.", 1);
return StereoDepth::PresetMode::HIGH_ACCURACY;
})

.def_property_readonly_static("HIGH_DENSITY", [](py::object){
PyErr_WarnEx(PyExc_DeprecationWarning, "HIGH_DENSITY is deprecated, will be removed in future releases and replaced with DEFAULT.", 1);
return StereoDepth::PresetMode::HIGH_DENSITY;
})

;

// Node
Expand Down Expand Up @@ -99,6 +116,7 @@ void bind_stereodepth(pybind11::module& m, void* pCallstack){
py::arg("presetMode") = StereoDepth::PresetMode::HIGH_DENSITY)
.def_readonly("initialConfig", &StereoDepth::initialConfig, DOC(dai, node, StereoDepth, initialConfig))
.def_readonly("inputConfig", &StereoDepth::inputConfig, DOC(dai, node, StereoDepth, inputConfig))
.def_readonly("inputAlignTo", &StereoDepth::inputAlignTo, DOC(dai, node, StereoDepth, inputAlignTo))
.def_readonly("left", &StereoDepth::left, DOC(dai, node, StereoDepth, left))
.def_readonly("right", &StereoDepth::right, DOC(dai, node, StereoDepth, right))
.def_readonly("inputLeftPixelDescriptor", &StereoDepth::inputLeftPixelDescriptor, DOC(dai, node, StereoDepth, inputLeftPixelDescriptor))
Expand Down
2 changes: 0 additions & 2 deletions bindings/python/utilities/cam_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -454,8 +454,6 @@ def socket_to_socket_opt(socket: dai.CameraBoardSocket) -> str:
print(
"Device is calibrated and has a stereo pair, creating StereoDepth node.")
stereo = pipeline.createStereoDepth()
stereo.setDefaultProfilePreset(
dai.node.StereoDepth.PresetMode.HIGH_DENSITY)
stereo.initialConfig.setMedianFilter(dai.MedianFilter.KERNEL_7x7)
stereo.setLeftRightCheck(True)
stereo.setSubpixel(True)
Expand Down
2 changes: 0 additions & 2 deletions bindings/python/utilities/stress_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -444,8 +444,6 @@ def build_pipeline(device: dai.Device, args) -> Tuple[dai.Pipeline, List[Tuple[s
output = "out" if hasattr(left, "out") else "video"
getattr(left, output).link(stereo.left)
getattr(right, output).link(stereo.right)
stereo.setDefaultProfilePreset(
dai.node.StereoDepth.PresetMode.HIGH_DENSITY)
stereo.setOutputSize(left.getResolutionWidth(),
left.getResolutionHeight())
stereo.setLeftRightCheck(True)
Expand Down
2 changes: 1 addition & 1 deletion cmake/Depthai/DepthaiDeviceRVC4Config.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -4,4 +4,4 @@ set(DEPTHAI_DEVICE_RVC4_MATURITY "snapshot")

# "version if applicable"
# set(DEPTHAI_DEVICE_RVC4_VERSION "0.0.1+93f7b75a885aa32f44c5e9f53b74470c49d2b1af")
set(DEPTHAI_DEVICE_RVC4_VERSION "0.0.1+d7eb7c6a19e25e5d799dd00daf87e9daeb42fb28")
set(DEPTHAI_DEVICE_RVC4_VERSION "0.0.1+81617bcfe7b7da9eda9654b5b3d3d3254b59a47d")
2 changes: 1 addition & 1 deletion cmake/Depthai/DepthaiDeviceSideConfig.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
set(DEPTHAI_DEVICE_SIDE_MATURITY "snapshot")

# "full commit hash of device side binary"
set(DEPTHAI_DEVICE_SIDE_COMMIT "5ea287b8b29e9cdefed2b5038be8ba18019408bf")
set(DEPTHAI_DEVICE_SIDE_COMMIT "c3e98b39b6a5445b2187b4109d03a146c6df37dd")

# "version if applicable"
set(DEPTHAI_DEVICE_SIDE_VERSION "")
1 change: 0 additions & 1 deletion examples/cpp/RVC2/VSLAM/basalt_vio_rtabmap_slam.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,6 @@ int main() {
imu->setMaxBatchReports(10);
stereo->setExtendedDisparity(false);
stereo->setSubpixel(true);
stereo->setDefaultProfilePreset(dai::node::StereoDepth::PresetMode::HIGH_DENSITY);
stereo->setLeftRightCheck(true);
stereo->setRectifyEdgeFillColor(0); // black, to better see the cutout
stereo->enableDistortionCorrection(true);
Expand Down
1 change: 0 additions & 1 deletion examples/cpp/RVC2/VSLAM/rtabmap_vio.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,6 @@ int main() {
right->setFps(fps);
stereo->setExtendedDisparity(false);

stereo->setDefaultProfilePreset(dai::node::StereoDepth::PresetMode::HIGH_DENSITY);
stereo->setLeftRightCheck(true);
stereo->setRectifyEdgeFillColor(0); // black, to better see the cutout
stereo->enableDistortionCorrection(true);
Expand Down
1 change: 0 additions & 1 deletion examples/cpp/RVC2/VSLAM/rtabmap_vio_slam.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,6 @@ int main() {
right->setFps(fps);
stereo->setExtendedDisparity(false);
stereo->setSubpixel(true);
stereo->setDefaultProfilePreset(dai::node::StereoDepth::PresetMode::HIGH_DENSITY);
stereo->setLeftRightCheck(true);
stereo->setRectifyEdgeFillColor(0); // black, to better see the cutout
stereo->enableDistortionCorrection(true);
Expand Down
9 changes: 9 additions & 0 deletions examples/python/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -214,3 +214,12 @@ dai_set_example_test_labels(visualizer_encoded_rvc2 ondevice rvc2 usb ci)

add_python_example(custom_services Visualizer/custom_services.py)
dai_set_example_test_labels(custom_services onhost ci)


## Script node
add_python_example(script_simple Script/script_simple.py)
dai_set_example_test_labels(script_simple ondevice rvc2_all rvc4 ci)
set_tests_properties(py_script_simple PROPERTIES FAIL_REGULAR_EXPRESSION "\\[error\\];\\[critical\\]")

add_python_example(script_all_cameras Script/script_switch_all_cameras.py)
dai_set_example_test_labels(script_all_cameras ondevice rvc2_all rvc4 ci)
21 changes: 12 additions & 9 deletions examples/python/ImageAlign/depth_align.py
Original file line number Diff line number Diff line change
Expand Up @@ -35,16 +35,16 @@ def getFps(self):

pipeline = dai.Pipeline(device)

platform = pipeline.getDefaultDevice().getPlatform()

# Define sources and outputs
camRgb = pipeline.create(dai.node.Camera).build(RGB_SOCKET)
left = pipeline.create(dai.node.Camera).build(LEFT_SOCKET)
right = pipeline.create(dai.node.Camera).build(RIGHT_SOCKET)
stereo = pipeline.create(dai.node.StereoDepth)
sync = pipeline.create(dai.node.Sync)
align = pipeline.create(dai.node.ImageAlign)

stereo.setDefaultProfilePreset(dai.node.StereoDepth.PresetMode.HIGH_DENSITY)
stereo.setDepthAlign(LEFT_SOCKET)
if platform == dai.Platform.RVC4:
align = pipeline.create(dai.node.ImageAlign)

stereo.setExtendedDisparity(True)

Expand All @@ -58,9 +58,14 @@ def getFps(self):
rgbOut.link(sync.inputs["rgb"])
leftOut.link(stereo.left)
rightOut.link(stereo.right)
stereo.depth.link(align.input)
align.outputAligned.link(sync.inputs["depth_aligned"])
rgbOut.link(align.inputAlignTo)
if platform == dai.Platform.RVC4:
stereo.depth.link(align.input)
rgbOut.link(align.inputAlignTo)
align.outputAligned.link(sync.inputs["depth_aligned"])
else:
stereo.depth.link(sync.inputs["depth_aligned"])
rgbOut.link(stereo.inputAlignTo)

queue = sync.out.createOutputQueue()

def colorizeDepth(frameDepth):
Expand Down Expand Up @@ -134,8 +139,6 @@ def updateBlendWeights(percentRgb):
frameDepth = messageGroup["depth_aligned"]
assert isinstance(frameDepth, dai.ImgFrame)

sizeRgb = frameRgb.getData().size
sizeDepth = frameDepth.getData().size
# Blend when both received
if frameDepth is not None:
cvFrame = frameRgb.getCvFrame()
Expand Down
1 change: 0 additions & 1 deletion examples/python/RVC2/ObjectTracker/object_tracker.py
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,6 @@
monoRight.setCamera("right")

# setting node configs
stereo.setDefaultProfilePreset(dai.node.StereoDepth.PresetMode.HIGH_DENSITY)
# Align depth map to the perspective of RGB camera, on which inference is done
stereo.setDepthAlign(dai.CameraBoardSocket.CAM_A)
stereo.setOutputSize(monoLeft.getResolutionWidth(), monoLeft.getResolutionHeight())
Expand Down
1 change: 0 additions & 1 deletion examples/python/RVC2/StereoDepth/stereo.py
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,6 @@
monoRight.setBoardSocket(dai.CameraBoardSocket.CAM_C)

# Create a node that will produce the depth map (using disparity output as it's easier to visualize depth this way)
depth.setDefaultProfilePreset(dai.node.StereoDepth.PresetMode.HIGH_DENSITY)
depth.setLeftRightCheck(lr_check)
depth.setExtendedDisparity(extended_disparity)
depth.setSubpixel(subpixel)
Expand Down
32 changes: 32 additions & 0 deletions examples/python/Script/script_simple.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
import depthai as dai
import time

# Create pipeline
pipeline = dai.Pipeline()
script = pipeline.create(dai.node.Script)
inputQueue = script.inputs["in"].createInputQueue()
outputQueue = script.outputs["out"].createOutputQueue()


script.setScript(
"""
while True:
message = node.inputs["in"].get()
# Or alternatively:
# message = node.io["in"].get()
node.warn("I received a message!")
node.outputs["out"].send(message)
# Or alternatively:
# node.io["out"].send(message)
"""
)

pipeline.start()
with pipeline:
while pipeline.isRunning():
message = dai.ImgFrame()
print("Sending a message")
inputQueue.send(message)
output = outputQueue.get()
print("Received a message")
time.sleep(1)
Loading

0 comments on commit 58f7e4a

Please sign in to comment.