|
| 1 | +#include "DatatypeBindings.hpp" |
| 2 | +#include "pipeline/CommonBindings.hpp" |
| 3 | +#include <unordered_map> |
| 4 | +#include <memory> |
| 5 | + |
| 6 | +// depthai |
| 7 | +#include "depthai/pipeline/datatype/FeatureTrackerConfigRvc4.hpp" |
| 8 | + |
| 9 | +//pybind |
| 10 | +#include <pybind11/chrono.h> |
| 11 | +#include <pybind11/numpy.h> |
| 12 | + |
| 13 | +// #include "spdlog/spdlog.h" |
| 14 | + |
| 15 | +void bind_featuretrackerconfigRvc4(pybind11::module& m, void* pCallstack){ |
| 16 | + |
| 17 | + using namespace dai; |
| 18 | + |
| 19 | + // py::class_<RawFeatureTrackerConfig, RawBuffer, std::shared_ptr<RawFeatureTrackerConfig>> rawFeatureTrackerConfig(m, "RawFeatureTrackerConfig", DOC(dai, RawFeatureTrackerConfig)); |
| 20 | + py::class_<FeatureTrackerConfigRvc4, Py<FeatureTrackerConfigRvc4>, Buffer, std::shared_ptr<FeatureTrackerConfigRvc4>> featureTrackerConfigRvc4(m, "FeatureTrackerConfigRvc4", DOC(dai, FeatureTrackerConfigRvc4)); |
| 21 | + py::class_<FeatureTrackerConfigRvc4::CornerDetector> cornerDetector(featureTrackerConfigRvc4, "CornerDetector", DOC(dai, FeatureTrackerConfigRvc4, CornerDetector)); |
| 22 | + py::enum_<FeatureTrackerConfigRvc4::CornerDetector::Type> cornerDetectorType(cornerDetector, "Type", DOC(dai, FeatureTrackerConfigRvc4, CornerDetector, Type)); |
| 23 | + py::class_<FeatureTrackerConfigRvc4::CornerDetector::Thresholds> cornerDetectorThresholds(cornerDetector, "Thresholds", DOC(dai, FeatureTrackerConfigRvc4, CornerDetector, Thresholds)); |
| 24 | + py::class_<FeatureTrackerConfigRvc4::MotionEstimator> motionEstimator(featureTrackerConfigRvc4, "MotionEstimator", DOC(dai, FeatureTrackerConfigRvc4, MotionEstimator)); |
| 25 | + py::enum_<FeatureTrackerConfigRvc4::MotionEstimator::Type> motionEstimatorType(motionEstimator, "Type", DOC(dai, FeatureTrackerConfigRvc4, MotionEstimator, Type)); |
| 26 | + py::class_<FeatureTrackerConfigRvc4::MotionEstimator::OpticalFlow> motionEstimatorOpticalFlow(motionEstimator, "OpticalFlow", DOC(dai, FeatureTrackerConfigRvc4, MotionEstimator, OpticalFlow)); |
| 27 | + py::class_<FeatureTrackerConfigRvc4::FeatureMaintainer> featureMaintainer(featureTrackerConfigRvc4, "FeatureMaintainer", DOC(dai, FeatureTrackerConfigRvc4, FeatureMaintainer)); |
| 28 | + |
| 29 | + /////////////////////////////////////////////////////////////////////// |
| 30 | + /////////////////////////////////////////////////////////////////////// |
| 31 | + /////////////////////////////////////////////////////////////////////// |
| 32 | + // Call the rest of the type defines, then perform the actual bindings |
| 33 | + Callstack* callstack = (Callstack*) pCallstack; |
| 34 | + auto cb = callstack->top(); |
| 35 | + callstack->pop(); |
| 36 | + cb(m, pCallstack); |
| 37 | + // Actual bindings |
| 38 | + /////////////////////////////////////////////////////////////////////// |
| 39 | + /////////////////////////////////////////////////////////////////////// |
| 40 | + /////////////////////////////////////////////////////////////////////// |
| 41 | + |
| 42 | + // // Metadata / raw |
| 43 | + // rawFeatureTrackerConfig |
| 44 | + // .def(py::init<>()) |
| 45 | + // .def_readwrite("cornerDetector", &FeatureTrackerConfigRvc4::cornerDetector, DOC(dai, FeatureTrackerConfigRvc4, cornerDetector)) |
| 46 | + // .def_readwrite("motionEstimator", &FeatureTrackerConfigRvc4::motionEstimator, DOC(dai, FeatureTrackerConfigRvc4, motionEstimator)) |
| 47 | + // .def_readwrite("featureMaintainer", &FeatureTrackerConfigRvc4::featureMaintainer, DOC(dai, FeatureTrackerConfigRvc4, featureMaintainer)) |
| 48 | + // ; |
| 49 | + |
| 50 | + cornerDetectorType |
| 51 | + .value("HARRIS", FeatureTrackerConfigRvc4::CornerDetector::Type::HARRIS) |
| 52 | + ; |
| 53 | + |
| 54 | + cornerDetectorThresholds |
| 55 | + .def(py::init<>()) |
| 56 | + .def_readwrite("harrisScore", &FeatureTrackerConfigRvc4::CornerDetector::Thresholds::harrisScore, DOC(dai, FeatureTrackerConfigRvc4, CornerDetector, Thresholds, harrisScore)) |
| 57 | + .def_readwrite("robustness", &FeatureTrackerConfigRvc4::CornerDetector::Thresholds::robustness, DOC(dai, FeatureTrackerConfigRvc4, CornerDetector, Thresholds, robustness)) |
| 58 | + ; |
| 59 | + |
| 60 | + cornerDetector |
| 61 | + .def(py::init<>()) |
| 62 | + .def_readwrite("type", &FeatureTrackerConfigRvc4::CornerDetector::type, DOC(dai, FeatureTrackerConfigRvc4, CornerDetector, type)) |
| 63 | + .def_readwrite("numMaxFeatures", &FeatureTrackerConfigRvc4::CornerDetector::numMaxFeatures, DOC(dai, FeatureTrackerConfigRvc4, CornerDetector, numMaxFeatures)) |
| 64 | + .def_readwrite("gradientFilterShift", &FeatureTrackerConfigRvc4::CornerDetector::gradientFilterShift, DOC(dai, FeatureTrackerConfigRvc4, CornerDetector, gradientFilterShift)) |
| 65 | + .def_readwrite("descriptorLpf", &FeatureTrackerConfigRvc4::CornerDetector::descriptorLpf, DOC(dai, FeatureTrackerConfigRvc4, CornerDetector, descriptorLpf)) |
| 66 | + .def_readwrite("thresholds", &FeatureTrackerConfigRvc4::CornerDetector::thresholds, DOC(dai, FeatureTrackerConfigRvc4, CornerDetector, thresholds)) |
| 67 | + ; |
| 68 | + |
| 69 | + motionEstimatorType |
| 70 | + .value("HW_MOTION_ESTIMATION", FeatureTrackerConfigRvc4::MotionEstimator::Type::HW_MOTION_ESTIMATION) |
| 71 | + ; |
| 72 | + |
| 73 | + motionEstimatorOpticalFlow |
| 74 | + .def(py::init<>()) |
| 75 | + .def_readwrite("pyramidLevels", &FeatureTrackerConfigRvc4::MotionEstimator::OpticalFlow::pyramidLevels, DOC(dai, FeatureTrackerConfigRvc4, MotionEstimator, OpticalFlow, pyramidLevels)) |
| 76 | + .def_readwrite("searchWindowWidth", &FeatureTrackerConfigRvc4::MotionEstimator::OpticalFlow::searchWindowWidth, DOC(dai, FeatureTrackerConfigRvc4, MotionEstimator, OpticalFlow, searchWindowWidth)) |
| 77 | + .def_readwrite("searchWindowHeight", &FeatureTrackerConfigRvc4::MotionEstimator::OpticalFlow::searchWindowHeight, DOC(dai, FeatureTrackerConfigRvc4, MotionEstimator, OpticalFlow, searchWindowHeight)) |
| 78 | + .def_readwrite("epsilon", &FeatureTrackerConfigRvc4::MotionEstimator::OpticalFlow::epsilon, DOC(dai, FeatureTrackerConfigRvc4, MotionEstimator, OpticalFlow, epsilon)) |
| 79 | + .def_readwrite("maxIterations", &FeatureTrackerConfigRvc4::MotionEstimator::OpticalFlow::maxIterations, DOC(dai, FeatureTrackerConfigRvc4, MotionEstimator, OpticalFlow, maxIterations)) |
| 80 | + ; |
| 81 | + |
| 82 | + motionEstimator |
| 83 | + .def(py::init<>()) |
| 84 | + .def_readwrite("enable", &FeatureTrackerConfigRvc4::MotionEstimator::enable, DOC(dai, FeatureTrackerConfigRvc4, MotionEstimator, enable)) |
| 85 | + .def_readwrite("type", &FeatureTrackerConfigRvc4::MotionEstimator::type, DOC(dai, FeatureTrackerConfigRvc4, MotionEstimator, type)) |
| 86 | + .def_readwrite("opticalFlow", &FeatureTrackerConfigRvc4::MotionEstimator::opticalFlow, DOC(dai, FeatureTrackerConfigRvc4, MotionEstimator, opticalFlow)) |
| 87 | + ; |
| 88 | + |
| 89 | + featureMaintainer |
| 90 | + .def(py::init<>()) |
| 91 | + .def_readwrite("enable", &FeatureTrackerConfigRvc4::FeatureMaintainer::enable, DOC(dai, FeatureTrackerConfigRvc4, FeatureMaintainer, enable)) |
| 92 | + .def_readwrite("minimumDistanceBetweenFeatures", &FeatureTrackerConfigRvc4::FeatureMaintainer::minimumDistanceBetweenFeatures, DOC(dai, FeatureTrackerConfigRvc4, FeatureMaintainer, minimumDistanceBetweenFeatures)) |
| 93 | + .def_readwrite("lostFeatureErrorThreshold", &FeatureTrackerConfigRvc4::FeatureMaintainer::lostFeatureErrorThreshold, DOC(dai, FeatureTrackerConfigRvc4, FeatureMaintainer, lostFeatureErrorThreshold)) |
| 94 | + .def_readwrite("trackedFeatureThreshold", &FeatureTrackerConfigRvc4::FeatureMaintainer::trackedFeatureThreshold, DOC(dai, FeatureTrackerConfigRvc4, FeatureMaintainer, trackedFeatureThreshold)) |
| 95 | + .def_readwrite("confidenceThreshold", &FeatureTrackerConfigRvc4::FeatureMaintainer::confidenceThreshold, DOC(dai, FeatureTrackerConfigRvc4, FeatureMaintainer, confidenceThreshold)) |
| 96 | + ; |
| 97 | + |
| 98 | + // Message |
| 99 | + featureTrackerConfigRvc4 |
| 100 | + .def(py::init<>()) |
| 101 | + // .def(py::init<std::shared_ptr<FeatureTrackerConfigRvc4>>()) |
| 102 | + |
| 103 | + .def("setCornerDetector", static_cast<FeatureTrackerConfigRvc4&(FeatureTrackerConfigRvc4::*)(dai::FeatureTrackerConfigRvc4::CornerDetector::Type)>(&FeatureTrackerConfigRvc4::setCornerDetector), py::arg("cornerDetector"), DOC(dai, FeatureTrackerConfigRvc4, setCornerDetector)) |
| 104 | + .def("setCornerDetector", static_cast<FeatureTrackerConfigRvc4&(FeatureTrackerConfigRvc4::*)(dai::FeatureTrackerConfigRvc4::CornerDetector)>(&FeatureTrackerConfigRvc4::setCornerDetector), py::arg("config"), DOC(dai, FeatureTrackerConfigRvc4, setCornerDetector, 2)) |
| 105 | + .def("setMotionEstimator", static_cast<FeatureTrackerConfigRvc4&(FeatureTrackerConfigRvc4::*)(bool)>(&FeatureTrackerConfigRvc4::setMotionEstimator), py::arg("enable"), DOC(dai, FeatureTrackerConfigRvc4, setMotionEstimator)) |
| 106 | + .def("setMotionEstimator", static_cast<FeatureTrackerConfigRvc4&(FeatureTrackerConfigRvc4::*)(dai::FeatureTrackerConfigRvc4::MotionEstimator)>(&FeatureTrackerConfigRvc4::setMotionEstimator), py::arg("config"), DOC(dai, FeatureTrackerConfigRvc4, setMotionEstimator, 2)) |
| 107 | + .def("setHwMotionEstimation", &FeatureTrackerConfigRvc4::setHwMotionEstimation, DOC(dai, FeatureTrackerConfigRvc4, setHwMotionEstimation)) |
| 108 | + .def("setFeatureMaintainer", static_cast<FeatureTrackerConfigRvc4&(FeatureTrackerConfigRvc4::*)(bool)>(&FeatureTrackerConfigRvc4::setFeatureMaintainer), py::arg("enable"), DOC(dai, FeatureTrackerConfigRvc4, setFeatureMaintainer)) |
| 109 | + .def("setFeatureMaintainer", static_cast<FeatureTrackerConfigRvc4&(FeatureTrackerConfigRvc4::*)(dai::FeatureTrackerConfigRvc4::FeatureMaintainer)>(&FeatureTrackerConfigRvc4::setFeatureMaintainer), py::arg("config"), DOC(dai, FeatureTrackerConfigRvc4, setFeatureMaintainer, 2)) |
| 110 | + .def("setNumMaxFeatures", &FeatureTrackerConfigRvc4::setNumMaxFeatures, py::arg("numMaxFeatures"), DOC(dai, FeatureTrackerConfigRvc4, setNumMaxFeatures)) |
| 111 | + .def("setHarrisCornerDetectorThreshold", &FeatureTrackerConfigRvc4::setHarrisCornerDetectorThreshold, py::arg("cornerDetectorThreshold"), DOC(dai, FeatureTrackerConfigRvc4, setHarrisCornerDetectorThreshold)) |
| 112 | + .def("setHarrisCornerDetectorRobustness", &FeatureTrackerConfigRvc4::setHarrisCornerDetectorRobustness, py::arg("cornerDetectorRobustness"), DOC(dai, FeatureTrackerConfigRvc4, setHarrisCornerDetectorRobustness)) |
| 113 | + .def("setConfidence", &FeatureTrackerConfigRvc4::setConfidence, py::arg("confidenceThreshold"), DOC(dai, FeatureTrackerConfigRvc4, setConfidence)) |
| 114 | + .def("setFilterCoeffs", &FeatureTrackerConfigRvc4::setFilterCoeffs, py::arg("filterCoeffs"), DOC(dai, FeatureTrackerConfigRvc4, setFilterCoeffs)) |
| 115 | + |
| 116 | + |
| 117 | + // .def("set", &FeatureTrackerConfigRvc4::set, py::arg("config"), DOC(dai, FeatureTrackerConfigRvc4, set)) |
| 118 | + // .def("get", &FeatureTrackerConfigRvc4::get, DOC(dai, FeatureTrackerConfigRvc4, get)) |
| 119 | + ; |
| 120 | + |
| 121 | + // add aliases |
| 122 | + m.attr("FeatureTrackerConfigRvc4").attr("CornerDetector") = m.attr("FeatureTrackerConfigRvc4").attr("CornerDetector"); |
| 123 | + m.attr("FeatureTrackerConfigRvc4").attr("MotionEstimator") = m.attr("FeatureTrackerConfigRvc4").attr("MotionEstimator"); |
| 124 | + m.attr("FeatureTrackerConfigRvc4").attr("FeatureMaintainer") = m.attr("FeatureTrackerConfigRvc4").attr("FeatureMaintainer"); |
| 125 | + |
| 126 | +} |
0 commit comments