FeatureTrackerConfig
This message is used to configure the FeatureTracker node. You can set the CornerDetector, FeatureMaintainer and MotionEstimator.Reference
class
dai::FeatureTrackerConfig
variable
CornerDetector cornerDetector
Corner detector configuration. Used for feature detection.
variable
MotionEstimator motionEstimator
Motion estimator configuration. Used for feature reidentification between current and previous features.
variable
FeatureMaintainer featureMaintainer
FeatureMaintainer configuration. Used for feature maintaining.
function
FeatureTrackerConfig()
function
~FeatureTrackerConfig()
function
FeatureTrackerConfig & setCornerDetector(CornerDetector::Type cornerDetector)
Set corner detector algorithm type.
Parameters
- cornerDetector: Corner detector type, HARRIS or SHI_THOMASI
function
FeatureTrackerConfig & setCornerDetector(CornerDetector config)
Set corner detector full configuration.
Parameters
- config: Corner detector configuration
function
FeatureTrackerConfig & setOpticalFlow()
Set optical flow as motion estimation algorithm type.
function
FeatureTrackerConfig & setOpticalFlow(MotionEstimator::OpticalFlow config)
Set optical flow full configuration.
Parameters
- config: Optical flow configuration
function
FeatureTrackerConfig & setHwMotionEstimation()
Set hardware accelerated motion estimation using block matching. Faster than optical flow (software implementation) but might not be as accurate.
function
FeatureTrackerConfig & setNumTargetFeatures(std::int32_t numTargetFeatures)
Set number of target features to detect.
Parameters
- numTargetFeatures: Number of features
function
FeatureTrackerConfig & setMotionEstimator(bool enable)
Enable or disable motion estimator.
Parameters
- enable:
function
FeatureTrackerConfig & setMotionEstimator(MotionEstimator config)
Set motion estimator full configuration.
Parameters
- config: Motion estimator configuration
function
FeatureTrackerConfig & setFeatureMaintainer(bool enable)
Enable or disable feature maintainer.
Parameters
- enable:
function
FeatureTrackerConfig & setFeatureMaintainer(FeatureMaintainer config)
Set feature maintainer full configuration.
Parameters
- config: feature maintainer configuration
inline function
void serialize(std::vector< std::uint8_t > & metadata, DatatypeEnum & datatype)
function
DEPTHAI_SERIALIZE(FeatureTrackerConfig, cornerDetector, motionEstimator, featureMaintainer)
struct
dai::FeatureTrackerConfig::CornerDetector
variable
Type type
Corner detector algorithm type.
variable
std::int32_t cellGridDimension
Ensures distributed feature detection across the image. Image is divided into horizontal and vertical cells, each cell has a target feature count = numTargetFeatures / cellGridDimension. Each cell has its own feature threshold. A value of 4 means that the image is divided into 4x4 cells of equal width/height. Maximum 4, minimum 1.
variable
std::int32_t numTargetFeatures
Target number of features to detect. Maximum number of features is determined at runtime based on algorithm type.
variable
std::int32_t numMaxFeatures
Hard limit for the maximum number of features that can be detected. 0 means auto, will be set to the maximum value based on memory constraints.
variable
bool enableSobel
Enable 3x3 Sobel operator to smoothen the image whose gradient is to be computed. If disabled, a simple 1D row/column differentiator is used for gradient.
variable
bool enableSorting
Enable sorting detected features based on their score or not.
variable
Thresholds thresholds
Threshold settings. These are advanced settings, suitable for debugging/special cases.
function
DEPTHAI_SERIALIZE(CornerDetector, type, cellGridDimension, numTargetFeatures, numMaxFeatures, thresholds, enableSobel, enableSorting)
struct
dai::FeatureTrackerConfig::CornerDetector::Thresholds
variable
float initialValue
Minimum strength of a feature which will be detected. 0 means automatic threshold update. Recommended so the tracker can adapt to different scenes/textures. Each cell has its own threshold. Empirical value.
variable
float min
Minimum limit for threshold. Applicable when automatic threshold update is enabled. 0 means auto, 6000000 for HARRIS, 1200 for SHI_THOMASI. Empirical value.
variable
float max
Maximum limit for threshold. Applicable when automatic threshold update is enabled. 0 means auto. Empirical value.
variable
float decreaseFactor
When detected number of features exceeds the maximum in a cell threshold is lowered by multiplying its value with this factor.
variable
float increaseFactor
When detected number of features doesn't exceed the maximum in a cell, threshold is increased by multiplying its value with this factor.
function
DEPTHAI_SERIALIZE(Thresholds, initialValue, min, max, decreaseFactor, increaseFactor)
enum
std::int32_t Type
enumerator
HARRIS
Harris corner detector.
enumerator
SHI_THOMASI
Shi-Thomasi corner detector.
struct
dai::FeatureTrackerConfig::FeatureMaintainer
variable
bool enable
Enable feature maintaining or not.
variable
float minimumDistanceBetweenFeatures
Used to filter out detected feature points that are too close. Requires sorting enabled in detector. Unit of measurement is squared euclidean distance in pixels.
variable
float lostFeatureErrorThreshold
Optical flow measures the tracking error for every feature. If the point can’t be tracked or it’s out of the image it will set this error to a maximum value. This threshold defines the level where the tracking accuracy is considered too bad to keep the point.
variable
float trackedFeatureThreshold
Once a feature was detected and we started tracking it, we need to update its Harris score on each image. This is needed because a feature point can disappear, or it can become too weak to be tracked. This threshold defines the point where such a feature must be dropped. As the goal of the algorithm is to provide longer tracks, we try to add strong points and track them until they are absolutely untrackable. This is why, this value is usually smaller than the detection threshold.
function
DEPTHAI_SERIALIZE(FeatureMaintainer, enable, minimumDistanceBetweenFeatures, lostFeatureErrorThreshold, trackedFeatureThreshold)
struct
dai::FeatureTrackerConfig::MotionEstimator
variable
bool enable
Enable motion estimation or not.
variable
Type type
Motion estimator algorithm type.
variable
OpticalFlow opticalFlow
Optical flow configuration. Takes effect only if MotionEstimator algorithm type set to LUCAS_KANADE_OPTICAL_FLOW.
function
DEPTHAI_SERIALIZE(MotionEstimator, enable, type, opticalFlow)
struct
dai::FeatureTrackerConfig::MotionEstimator::OpticalFlow
variable
std::int32_t pyramidLevels
Number of pyramid levels, only for optical flow. AUTO means it's decided based on input resolution: 3 if image width <= 640, else 4. Valid values are either 3/4 for VGA, 4 for 720p and above.
variable
std::int32_t searchWindowWidth
Image patch width used to track features. Must be an odd number, maximum 9. N means the algorithm will be able to track motion at most (N-1)/2 pixels in a direction per pyramid level. Increasing this number increases runtime
variable
std::int32_t searchWindowHeight
Image patch height used to track features. Must be an odd number, maximum 9. N means the algorithm will be able to track motion at most (N-1)/2 pixels in a direction per pyramid level. Increasing this number increases runtime
variable
float epsilon
Feature tracking termination criteria. Optical flow will refine the feature position on each pyramid level until the displacement between two refinements is smaller than this value. Decreasing this number increases runtime.
variable
std::int32_t maxIterations
Feature tracking termination criteria. Optical flow will refine the feature position maximum this many times on each pyramid level. If the Epsilon criteria described in the previous chapter is not met after this number of iterations, the algorithm will continue with the current calculated value. Increasing this number increases runtime.
function
DEPTHAI_SERIALIZE(OpticalFlow, pyramidLevels, searchWindowWidth, searchWindowHeight, epsilon, maxIterations)
enum
std::int32_t Type
enumerator
LUCAS_KANADE_OPTICAL_FLOW
Using the pyramidal Lucas-Kanade optical flow method.
enumerator
HW_MOTION_ESTIMATION
Using a dense motion estimation hardware block (Block matcher).
Need assistance?
Head over to Discussion Forum for technical support or any other questions you might have.