Skip to content

V3 dcl mode implementation #1366

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
wants to merge 31 commits into
base: develop
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
31 commits
Select commit Hold shift + click to select a range
5ed0c1e
Mock implementation
May 9, 2025
df3da91
Handle of errors
MaticTonin Jun 16, 2025
3adbfc5
Merge remote-tracking branch 'origin/develop' into v3_dynamic_calib_m…
Jun 17, 2025
70ce59b
Add missing bindings and update the python example
Jun 17, 2025
9c08c78
Example to change calibration when wanted
MaticTonin Jun 17, 2025
acd9232
Adding set new calibration in bindings
MaticTonin Jun 17, 2025
6b05792
More proper integration of the library
Jun 18, 2025
49e3c95
Merge remote-tracking branch 'origin/v3_dynamic_calib_mt_cmake' into …
Jun 18, 2025
a7bbef2
Fix build
Jun 18, 2025
630586b
Fix docstrings
Jun 18, 2025
6e62c48
Implementation of InputConfig
MaticTonin Jun 19, 2025
58518c7
Metrics -> threshold
MaticTonin Jun 19, 2025
884db54
Dynamic calibration: switch to message queues
SzabolcsGergely Jun 20, 2025
2c0b674
Add a way to specify DCL locally
Jun 20, 2025
f0f574f
Add comments; serialization CalibrationHandler
SzabolcsGergely Jun 20, 2025
2d37649
Structure changes with new results and forcedCalibCheck
MaticTonin Jun 22, 2025
e21562f
Depth error instead of accuracy
MaticTonin Jun 24, 2025
289e3b7
Performance mode
MaticTonin Jun 25, 2025
fb3b06a
Fixing so that continious mode does not get stuck in a loop
MaticTonin Jun 25, 2025
bdaf986
Update the DCL
Jun 25, 2025
d7b342a
Initial syncing
Jun 25, 2025
cdd92c2
Fix queue size
Jun 26, 2025
5b1055e
Recalibration not reporting coverage
MaticTonin Jun 26, 2025
5ede4b7
CI: retrigger to test merge commit HEAD
Jun 27, 2025
c2b67c8
New API changes
MaticTonin Jun 28, 2025
2e7a602
Adding click -> results method, no more needed to recall same method,…
MaticTonin Jun 29, 2025
9b202da
Adding readme and as well that you get display of depth
MaticTonin Jun 29, 2025
f26b6f0
Fixing issue with translation vector
MaticTonin Jun 30, 2025
ed018e1
T vector to the meters
MaticTonin Jun 30, 2025
47c5624
mathmul error dst->origin -> src-> origin instead of src->origin ->dst
MaticTonin Jun 30, 2025
6884da7
Rotation drift as a measurement
MaticTonin Jun 30, 2025
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
56 changes: 55 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,15 @@ set(DEPTHAI_PRE_RELEASE_VERSION "2")
# Set DEPTHAI_VERSION universally, not conditionally
set(DEPTHAI_VERSION ${PROJECT_VERSION}-${DEPTHAI_PRE_RELEASE_TYPE}.${DEPTHAI_PRE_RELEASE_VERSION})

# Default for dynamic calibration support (turn on x64 Liunux, but off for others)
if(CMAKE_SYSTEM_PROCESSOR MATCHES "x86_64" AND UNIX)
message(STATUS "Dynamic Calibration support enabled by default for x64 Linux")
option(DEPTHAI_DYNAMIC_CALIBRATION_SUPPORT "Enable Dynamic Calibration support" ON)
else()
message(STATUS "Dynamic Calibration support disabled by default")
option(DEPTHAI_DYNAMIC_CALIBRATION_SUPPORT "Enable Dynamic Calibration support" OFF)
endif()

get_directory_property(has_parent PARENT_DIRECTORY)
if(has_parent)
set(DEPTHAI_VERSION ${DEPTHAI_VERSION} PARENT_SCOPE) # Set in parent scope if there's a parent
Expand Down Expand Up @@ -190,7 +199,7 @@ set(THIRDPARTY_OPENCV_LIBRARIES "" CACHE STRING "Optional libraries to link Open
set(TARGET_OPENCV_NAME ${PROJECT_NAME}-opencv)
set(TARGET_OPENCV_ALIAS opencv)
if(DEPTHAI_OPENCV_SUPPORT)
set(REQUIRED_OPENCV_LIBRARIES "opencv_core" "opencv_imgproc" "opencv_videoio" "opencv_highgui")
set(REQUIRED_OPENCV_LIBRARIES "opencv_core" "opencv_imgproc" "opencv_videoio" "opencv_highgui" "opencv_calib3d")
set(OPENCV_SUPPORT_AVAILABLE ${OpenCV_FOUND})
foreach(lib ${REQUIRED_OPENCV_LIBRARIES})
if(NOT (lib IN_LIST OpenCV_LIBS))
Expand Down Expand Up @@ -363,6 +372,12 @@ if(DEPTHAI_ENABLE_PROTOBUF)
)
endif()

if(DEPTHAI_DYNAMIC_CALIBRATION_SUPPORT)
list(APPEND TARGET_CORE_SOURCES
src/pipeline/node/DynamicCalibration.cpp
)
endif()

set(TARGET_OPENCV_SOURCES
src/opencv/ImgFrame.cpp
src/pipeline/node/host/Display.cpp
Expand Down Expand Up @@ -500,6 +515,45 @@ if(NOT BUILD_SHARED_LIBS)
target_compile_definitions(${TARGET_CORE_NAME} PUBLIC MCAP_STATIC)
endif()

if(DEPTHAI_DYNAMIC_CALIBRATION_SUPPORT)
include(FetchContent)
set(DEPTHAI_DYNAMIC_CALIBRATION_PATH "" CACHE FILEPATH "Override path to local dynamic_calibration .zip file")

if(DEPTHAI_DYNAMIC_CALIBRATION_PATH AND EXISTS "${DEPTHAI_DYNAMIC_CALIBRATION_PATH}")
message(STATUS "Using local dynamic_calibration zip: ${DEPTHAI_DYNAMIC_CALIBRATION_PATH}")
FetchContent_Declare(
dynamic_calibration
URL "file://${DEPTHAI_DYNAMIC_CALIBRATION_PATH}"
)
else()
message(STATUS "Using remote dynamic_calibration zip")
FetchContent_Declare(
dynamic_calibration
URL https://artifacts.luxonis.com/artifactory/list/luxonis-depthai-helper-binaries/dynamic_calibration/510f107f671bbba2e353c5d5a4ac9a03f1715dea/dynamic_calibration_manylinux.zip
URL_HASH MD5=8d179385a633b979fe81a3ca91c6cca6
)
endif()
FetchContent_MakeAvailable(dynamic_calibration)
message(STATUS "Dynamic calibration extracted to ${dynamic_calibration_SOURCE_DIR}")
set(DYNAMIC_CALIBRATION_DIR ${dynamic_calibration_SOURCE_DIR})
target_include_directories(
${TARGET_CORE_NAME} PUBLIC
$<BUILD_INTERFACE:${DYNAMIC_CALIBRATION_DIR}/include>
)

find_library(DYNAMIC_CALIBRATION dynamic_calibration
PATHS ${DYNAMIC_CALIBRATION_DIR}/lib
NO_DEFAULT_PATH
)
target_compile_definitions(${TARGET_CORE_NAME} PUBLIC DEPTHAI_HAVE_DYNAMIC_CALIBRATION_SUPPORT)
if(DYNAMIC_CALIBRATION)
message(STATUS "Dynamic Calibration library found: ${DYNAMIC_CALIBRATION}")
target_link_libraries(${TARGET_CORE_NAME} PUBLIC ${DYNAMIC_CALIBRATION})
else()
message(FATAL_ERROR "Dynamic Calibration library not found, disable support by setting DEPTHAI_DYNAMIC_CALIBRATION_SUPPORT to OFF")
endif()
endif()

# Set constant
set(DEPTHAI_RESOURCES_OUTPUT_DIR "${CMAKE_CURRENT_BINARY_DIR}/resources")

Expand Down
8 changes: 8 additions & 0 deletions bindings/python/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -167,6 +167,14 @@ if(DEPTHAI_RTABMAP_SUPPORT)
)
endif()

if(DEPTHAI_DYNAMIC_CALIBRATION_SUPPORT)
list(APPEND SOURCE_LIST
src/pipeline/node/DynamicCalibrationBindings.cpp
src/pipeline/datatype/DynamicCalibrationResultsBindings.cpp
src/pipeline/datatype/DynamicCalibrationConfigBindings.cpp
)
endif()

# Add files for python module
if(DEPTHAI_PYTHON_EMBEDDED_MODULE)
add_library(${TARGET_NAME} ${SOURCE_LIST})
Expand Down
4 changes: 4 additions & 0 deletions bindings/python/src/DatatypeBindings.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,8 @@ void bind_transformdata(pybind11::module& m, void* pCallstack);
void bind_rgbddata(pybind11::module& m, void* pCallstack);
void bind_imagealignconfig(pybind11::module& m, void* pCallstack);
void bind_imageannotations(pybind11::module& m, void* pCallstack);
void bind_dynamic_calibration_results(pybind11::module& m, void* pCallstack);
void bind_dynamic_calibration_config(pybind11::module& m, void* pCallstack);

void DatatypeBindings::addToCallstack(std::deque<StackFunction>& callstack) {
// Bind common datatypebindings
Expand Down Expand Up @@ -71,6 +73,8 @@ void DatatypeBindings::addToCallstack(std::deque<StackFunction>& callstack) {
callstack.push_front(bind_imagealignconfig);
callstack.push_front(bind_imageannotations);
callstack.push_front(bind_rgbddata);
callstack.push_front(bind_dynamic_calibration_results);
callstack.push_front(bind_dynamic_calibration_config);
}

void DatatypeBindings::bind(pybind11::module& m, void* pCallstack) {
Expand Down
7 changes: 7 additions & 0 deletions bindings/python/src/DeviceBindings.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -779,6 +779,13 @@ void DeviceBindings::bind(pybind11::module& m, void* pCallstack) {
return d.factoryResetCalibration();
},
DOC(dai, DeviceBase, factoryResetCalibration))
.def(
"setCalibration",
[](DeviceBase& d, CalibrationHandler ch) {
py::gil_scoped_release release;
return d.setCalibration(ch);
},
DOC(dai, DeviceBase, setCalibration))
.def(
"flashFactoryCalibration",
[](DeviceBase& d, CalibrationHandler ch) {
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,73 @@
#include <memory>
#include <unordered_map>

#include "DatatypeBindings.hpp"
#include "pipeline/CommonBindings.hpp"

// depthai
#include "depthai/pipeline/datatype/DynamicCalibrationConfig.hpp"

void bind_dynamic_calibration_config(pybind11::module& m, void* pCallstack) {
using namespace dai;

py::class_<DynamicCalibrationConfig, Py<DynamicCalibrationConfig>, Buffer, std::shared_ptr<DynamicCalibrationConfig>> _DynamicCalibrationResults(
m, "DynamicCalibrationConfig", DOC(dai, DynamicCalibrationConfig));

py::class_<DynamicCalibrationConfig::AlgorithmControl> _AlgorithmControl(
_DynamicCalibrationResults, "AlgorithmControl", DOC(dai, DynamicCalibrationConfig, AlgorithmControl));

py::enum_<DynamicCalibrationConfig::CalibrationCommand> _CalibrationCommand(_DynamicCalibrationResults, "CalibrationCommand", DOC(dai, DynamicCalibrationConfig, CalibrationCommand));

py::enum_<DynamicCalibrationConfig::AlgorithmControl::PerformanceMode>(_AlgorithmControl, "PerformanceMode")
.value("SKIP_CHECKS", DynamicCalibrationConfig::AlgorithmControl::PerformanceMode::SKIP_CHECKS)
.value("STATIC_SCENERY", DynamicCalibrationConfig::AlgorithmControl::PerformanceMode::STATIC_SCENERY)
.value("OPTIMIZE_SPEED", DynamicCalibrationConfig::AlgorithmControl::PerformanceMode::OPTIMIZE_SPEED)
.value("OPTIMIZE_PERFORMANCE", DynamicCalibrationConfig::AlgorithmControl::PerformanceMode::OPTIMIZE_PERFORMANCE)
.value("DEFAULT", DynamicCalibrationConfig::AlgorithmControl::PerformanceMode::DEFAULT)
.export_values();
///////////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////////
// Call the rest of the type defines, then perform the actual bindings
Callstack* callstack = (Callstack*)pCallstack;
auto cb = callstack->top();
callstack->pop();
cb(m, pCallstack);
// Actual bindings
///////////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////////

// Metadata / raw
_AlgorithmControl.def(py::init<>())
.def_readwrite("recalibrationMode",
&DynamicCalibrationConfig::AlgorithmControl::recalibrationMode,
DOC(dai, DynamicCalibrationConfig, AlgorithmControl, recalibrationMode))
.def_readwrite("performanceMode",
&DynamicCalibrationConfig::AlgorithmControl::performanceMode,
DOC(dai, DynamicCalibrationConfig, AlgorithmControl, performanceMode ))
.def_readwrite("timeFrequency",
&DynamicCalibrationConfig::AlgorithmControl::timeFrequency,
DOC(dai, DynamicCalibrationConfig, AlgorithmControl, timeFrequency))
;


_CalibrationCommand
.value("START_CALIBRATION_QUALITY_CHECK", DynamicCalibrationConfig::CalibrationCommand::START_CALIBRATION_QUALITY_CHECK)
.value("START_FORCE_CALIBRATION_QUALITY_CHECK", DynamicCalibrationConfig::CalibrationCommand::START_FORCE_CALIBRATION_QUALITY_CHECK)
.value("START_RECALIBRATION", DynamicCalibrationConfig::CalibrationCommand::START_RECALIBRATION)
.value("START_FORCE_RECALIBRATION", DynamicCalibrationConfig::CalibrationCommand::START_FORCE_RECALIBRATION)
;

// Message
_DynamicCalibrationResults.def(py::init<>())
.def("__repr__", &DynamicCalibrationConfig::str)

.def_readwrite("algorithmControl",
&DynamicCalibrationConfig::algorithmControl,
DOC(dai, DynamicCalibrationConfig, algorithmControl))
.def_readwrite("calibrationCommand",
&DynamicCalibrationConfig::calibrationCommand,
DOC(dai, DynamicCalibrationConfig, calibrationCommand))
;
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,90 @@
#include <memory>
#include <unordered_map>

#include "DatatypeBindings.hpp"
#include "pipeline/CommonBindings.hpp"

// depthai
#include "depthai/pipeline/datatype/DynamicCalibrationResults.hpp"

void bind_dynamic_calibration_results(pybind11::module& m, void* pCallstack) {
using namespace dai;


py::class_<DynamicCalibrationResults, Py<DynamicCalibrationResults>, Buffer, std::shared_ptr<DynamicCalibrationResults>> _DynamicCalibrationResults(
m, "DynamicCalibrationResults", DOC(dai, DynamicCalibrationResults));

py::class_<DynamicCalibrationResults::CalibrationResult> _CalibrationResult(
_DynamicCalibrationResults, "CalibrationResult", DOC(dai, DynamicCalibrationResults, CalibrationResult));

py::class_<DynamicCalibrationResults::CalibrationData> _CalibrationData(
_DynamicCalibrationResults, "CalibrationData", DOC(dai, DynamicCalibrationResults, CalibrationData));

py::class_<DynamicCalibrationResults::CoverageData> _CoverageData(
_DynamicCalibrationResults, "CoverageData", DOC(dai, DynamicCalibrationResults, CoverageData));

py::class_<DynamicCalibrationResults::CalibrationQuality> _CalibrationQuality(
_DynamicCalibrationResults, "CalibrationQuality", DOC(dai, DynamicCalibrationResults, CalibrationQuality));

py::class_<DynamicCalibrationResults::CalibrationQualityResult> _CalibrationQualityResult(
_DynamicCalibrationResults, "CalibrationQualityResult", DOC(dai, DynamicCalibrationResults, CalibrationQualityResult));


///////////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////////
// Call the rest of the type defines, then perform the actual bindings
Callstack* callstack = (Callstack*)pCallstack;
auto cb = callstack->top();
callstack->pop();
cb(m, pCallstack);
// Actual bindings
///////////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////////

// Metadata / raw
_CalibrationResult
.def(py::init<>())
.def_readwrite("calibHandler", &DynamicCalibrationResults::CalibrationResult::calibHandler,
DOC(dai, DynamicCalibrationResults, CalibrationResult, calibHandler));

// Bind CalibrationData
_CalibrationData
.def(py::init<>())
.def_readwrite("rotationChange", &DynamicCalibrationResults::CalibrationData::rotationChange)
.def_readwrite("epipolarErrorChange", &DynamicCalibrationResults::CalibrationData::epipolarErrorChange)
.def_readwrite("depthErrorDifference", &DynamicCalibrationResults::CalibrationData::depthErrorDifference);

// Bind CoverageData
_CoverageData
.def(py::init<>())
.def_readwrite("coveragePerCellA", &DynamicCalibrationResults::CoverageData::coveragePerCellA)
.def_readwrite("coveragePerCellB", &DynamicCalibrationResults::CoverageData::coveragePerCellB)
.def_readwrite("meanCoverage", &DynamicCalibrationResults::CoverageData::meanCoverage);

// Bind CalibrationQuality
_CalibrationQuality
.def(py::init<>())
.def_readwrite("dataAquired", &DynamicCalibrationResults::CalibrationQuality::dataAquired)
.def_readwrite("coverageQuality", &DynamicCalibrationResults::CalibrationQuality::coverageQuality)
.def_readwrite("calibrationQuality", &DynamicCalibrationResults::CalibrationQuality::calibrationQuality);

// Bind CalibrationQualityResult
_CalibrationQualityResult
.def(py::init<>())
.def_readwrite("report", &DynamicCalibrationResults::CalibrationQualityResult::report);


// Message
_DynamicCalibrationResults
.def(py::init<>())
.def("reset", &DynamicCalibrationResults::reset)
.def_readwrite("newCalibration", &DynamicCalibrationResults::newCalibration,
DOC(dai, DynamicCalibrationResults, newCalibration))
.def_readwrite("calibOverallQuality", &DynamicCalibrationResults::calibOverallQuality,
DOC(dai, DynamicCalibrationResults, calibOverallQuality))
.def_readwrite("info", &DynamicCalibrationResults::info,
DOC(dai, DynamicCalibrationResults, info));
;
}
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,8 @@ void bind_objecttrackerconfig(pybind11::module& m, void* pCallstack) {
using namespace dai;

// py::class_<RawPointCloudConfig, RawBuffer, std::shared_ptr<RawPointCloudConfig>> rawConfig(m, "RawPointCloudConfig", DOC(dai, RawPointCloudConfig));
py::class_<ObjectTrackerConfig, Py<ObjectTrackerConfig>, Buffer, std::shared_ptr<ObjectTrackerConfig>> config(m, "ObjectTrackerConfig", DOC(dai, ObjectTrackerConfig));
py::class_<ObjectTrackerConfig, Py<ObjectTrackerConfig>, Buffer, std::shared_ptr<ObjectTrackerConfig>> config(
m, "ObjectTrackerConfig", DOC(dai, ObjectTrackerConfig));

///////////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////////
Expand Down Expand Up @@ -46,7 +47,6 @@ void bind_objecttrackerconfig(pybind11::module& m, void* pCallstack) {
// .def("set", &ObjectTrackerConfig::set, py::arg("config"), DOC(dai, ObjectTrackerConfig, set))
// .def("get", &ObjectTrackerConfig::get, DOC(dai, ObjectTrackerConfig, get))
.def("forceRemoveID", &ObjectTrackerConfig::forceRemoveID, DOC(dai, ObjectTrackerConfig, forceRemoveID))
.def("forceRemoveIDs", &ObjectTrackerConfig::forceRemoveIDs, DOC(dai, ObjectTrackerConfig, forceRemoveIDs))
;
.def("forceRemoveIDs", &ObjectTrackerConfig::forceRemoveIDs, DOC(dai, ObjectTrackerConfig, forceRemoveIDs));
// add aliases
}
40 changes: 40 additions & 0 deletions bindings/python/src/pipeline/node/DynamicCalibrationBindings.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
#include "Common.hpp"
#include "NodeBindings.hpp"
#include "depthai/pipeline/Node.hpp"
#include "depthai/pipeline/Pipeline.hpp"
#include "depthai/pipeline/node/DynamicCalibration.hpp"

void bind_dynamic_calibration(pybind11::module& m, void* pCallstack) {
using namespace dai;
using namespace dai::node;

// Node and Properties declare upfront
py::class_<DynamicCalibrationProperties> DynamicCalibrationProperties(m, "DynamicCalibrationProperties", DOC(dai, DynamicCalibrationProperties));
auto dynamicCalibration = ADD_NODE(DynamicCalibration);

///////////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////////
// Call the rest of the type defines, then perform the actual bindings
Callstack* callstack = (Callstack*)pCallstack;
auto cb = callstack->top();
callstack->pop();
cb(m, pCallstack);
// Actual bindings
///////////////////////////////////////////////////////////////////////
// Node
dynamicCalibration
.def_property_readonly(
"left", [](DynamicCalibration& node) { return &node.left; }, py::return_value_policy::reference_internal)
.def_property_readonly(
"right", [](DynamicCalibration& node) { return &node.right; }, py::return_value_policy::reference_internal)
.def_readonly("inputConfig", &DynamicCalibration::inputConfig, DOC(dai, node, DynamicCalibration, inputConfig))
.def_readonly("outputCalibrationResults", &DynamicCalibration::outputCalibrationResults, DOC(dai, node, DynamicCalibration, outputCalibrationResults))
.def("setRunOnHost", &DynamicCalibration::setRunOnHost, py::arg("runOnHost"), DOC(dai, node, DynamicCalibration, setRunOnHost))
.def("runOnHost", &DynamicCalibration::runOnHost, DOC(dai, node, DynamicCalibration, runOnHost))
.def("setPerformanceMode", &DynamicCalibration::setPerformanceMode, py::arg("mode"), DOC(dai, node, DynamicCalibration, setPerformanceMode))
.def("setContiniousMode", &DynamicCalibration::setContiniousMode, DOC(dai, node, DynamicCalibration, setContiniousMode))
.def("setTimeFrequency", &DynamicCalibration::setTimeFrequency, py::arg("int"), DOC(dai, node, DynamicCalibration, setTimeFrequency))
;
daiNodeModule.attr("DynamicCalibration").attr("Properties") = DynamicCalibrationProperties;
}
6 changes: 6 additions & 0 deletions bindings/python/src/pipeline/node/NodeBindings.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -167,6 +167,9 @@ void bind_basaltnode(pybind11::module& m, void* pCallstack);
void bind_rtabmapvionode(pybind11::module& m, void* pCallstack);
void bind_rtabmapslamnode(pybind11::module& m, void* pCallstack);
#endif
#ifdef DEPTHAI_HAVE_DYNAMIC_CALIBRATION_SUPPORT
void bind_dynamic_calibration(pybind11::module& m, void* pCallstack);
#endif
void NodeBindings::addToCallstack(std::deque<StackFunction>& callstack) {
// Bind Node et al
callstack.push_front(NodeBindings::bind);
Expand Down Expand Up @@ -212,6 +215,9 @@ void NodeBindings::addToCallstack(std::deque<StackFunction>& callstack) {
callstack.push_front(bind_rtabmapvionode);
callstack.push_front(bind_rtabmapslamnode);
#endif
#ifdef DEPTHAI_HAVE_DYNAMIC_CALIBRATION_SUPPORT
callstack.push_front(bind_dynamic_calibration);
#endif
}

void NodeBindings::bind(pybind11::module& m, void* pCallstack) {
Expand Down
2 changes: 1 addition & 1 deletion bindings/python/src/pybind11_common.hpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#pragma once

#if(_MSC_VER >= 1910) || !defined(_MSC_VER)
#if (_MSC_VER >= 1910) || !defined(_MSC_VER)
#ifndef HAVE_SNPRINTF
#define HAVE_SNPRINTF
#endif
Expand Down
5 changes: 5 additions & 0 deletions examples/cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -130,6 +130,11 @@ add_subdirectory(AprilTags)
add_subdirectory(Benchmark)
add_subdirectory(Camera)
add_subdirectory(DetectionNetwork)

if(DEPTHAI_DYNAMIC_CALIBRATION_SUPPORT)
add_subdirectory(DynamicCalibration)
endif()

add_subdirectory(Events)
add_subdirectory(FeatureTracker)
add_subdirectory(HostNodes)
Expand Down
Loading
Loading