FeatureTrackerConfig

This message is used to configure the FeatureTracker node. You can set the CornerDetector, FeatureMaintainer and MotionEstimator.

Reference

class depthai.FeatureTrackerConfig
get(self: depthai.FeatureTrackerConfig)depthai.RawFeatureTrackerConfig
getData(self: object) → numpy.ndarray[numpy.uint8]
getRaw(self: depthai.ADatatype)depthai.RawBuffer
getSequenceNum(self: depthai.Buffer)int
getTimestamp(self: depthai.Buffer)datetime.timedelta
getTimestampDevice(self: depthai.Buffer)datetime.timedelta
set(self: depthai.FeatureTrackerConfig, config: depthai.RawFeatureTrackerConfig)depthai.FeatureTrackerConfig
setCornerDetector(*args, **kwargs)

Overloaded function.

  1. setCornerDetector(self: depthai.FeatureTrackerConfig, cornerDetector: depthai.RawFeatureTrackerConfig.CornerDetector.Type) -> depthai.FeatureTrackerConfig

  2. setCornerDetector(self: depthai.FeatureTrackerConfig, config: depthai.RawFeatureTrackerConfig.CornerDetector) -> depthai.FeatureTrackerConfig

setData(*args, **kwargs)

Overloaded function.

  1. setData(self: depthai.Buffer, arg0: List[int]) -> None

  2. setData(self: depthai.Buffer, arg0: numpy.ndarray[numpy.uint8]) -> None

setFeatureMaintainer(*args, **kwargs)

Overloaded function.

  1. setFeatureMaintainer(self: depthai.FeatureTrackerConfig, enable: bool) -> depthai.FeatureTrackerConfig

  2. setFeatureMaintainer(self: depthai.FeatureTrackerConfig, config: depthai.RawFeatureTrackerConfig.FeatureMaintainer) -> depthai.FeatureTrackerConfig

setHwMotionEstimation(self: depthai.FeatureTrackerConfig)depthai.FeatureTrackerConfig
setMotionEstimator(*args, **kwargs)

Overloaded function.

  1. setMotionEstimator(self: depthai.FeatureTrackerConfig, enable: bool) -> depthai.FeatureTrackerConfig

  2. setMotionEstimator(self: depthai.FeatureTrackerConfig, config: depthai.RawFeatureTrackerConfig.MotionEstimator) -> depthai.FeatureTrackerConfig

setNumTargetFeatures(self: depthai.FeatureTrackerConfig, numTargetFeatures: int)depthai.FeatureTrackerConfig
setOpticalFlow(*args, **kwargs)

Overloaded function.

  1. setOpticalFlow(self: depthai.FeatureTrackerConfig) -> depthai.FeatureTrackerConfig

  2. setOpticalFlow(self: depthai.FeatureTrackerConfig, config: depthai.RawFeatureTrackerConfig.MotionEstimator.OpticalFlow) -> depthai.FeatureTrackerConfig

setSequenceNum(self: depthai.Buffer, arg0: int)depthai.Buffer
setTimestamp(self: depthai.Buffer, arg0: datetime.timedelta)depthai.Buffer
setTimestampDevice(self: depthai.Buffer, arg0: datetime.timedelta)depthai.Buffer
class dai::FeatureTrackerConfig : public dai::Buffer

FeatureTrackerConfig message. Carries config for feature tracking algorithm

Public Types

using CornerDetector = RawFeatureTrackerConfig::CornerDetector
using MotionEstimator = RawFeatureTrackerConfig::MotionEstimator
using FeatureMaintainer = RawFeatureTrackerConfig::FeatureMaintainer

Public Functions

FeatureTrackerConfig()

Construct FeatureTrackerConfig message.

FeatureTrackerConfig(std::shared_ptr<RawFeatureTrackerConfig> ptr)
~FeatureTrackerConfig() = default
FeatureTrackerConfig &setCornerDetector(dai::FeatureTrackerConfig::CornerDetector::Type cornerDetector)

Set corner detector algorithm type.

Parameters
  • cornerDetector: Corner detector type, HARRIS or SHI_THOMASI

FeatureTrackerConfig &setCornerDetector(dai::FeatureTrackerConfig::CornerDetector config)

Set corner detector full configuration.

Parameters
  • config: Corner detector configuration

FeatureTrackerConfig &setOpticalFlow()

Set optical flow as motion estimation algorithm type.

FeatureTrackerConfig &setOpticalFlow(dai::FeatureTrackerConfig::MotionEstimator::OpticalFlow config)

Set optical flow full configuration.

Parameters
  • config: Optical flow configuration

FeatureTrackerConfig &setHwMotionEstimation()

Set hardware accelerated motion estimation using block matching. Faster than optical flow (software implementation) but might not be as accurate.

FeatureTrackerConfig &setNumTargetFeatures(std::int32_t numTargetFeatures)

Set number of target features to detect.

Parameters
  • numTargetFeatures: Number of features

FeatureTrackerConfig &setMotionEstimator(bool enable)

Enable or disable motion estimator.

Parameters
  • enable:

FeatureTrackerConfig &setMotionEstimator(dai::FeatureTrackerConfig::MotionEstimator config)

Set motion estimator full configuration.

Parameters
  • config: Motion estimator configuration

FeatureTrackerConfig &setFeatureMaintainer(bool enable)

Enable or disable feature maintainer.

Parameters
  • enable:

FeatureTrackerConfig &setFeatureMaintainer(dai::FeatureTrackerConfig::FeatureMaintainer config)

Set feature maintainer full configuration.

Parameters
  • config: feature maintainer configuration

FeatureTrackerConfig &set(dai::RawFeatureTrackerConfig config)

Set explicit configuration.

Parameters
  • config: Explicit configuration

dai::RawFeatureTrackerConfig get() const

Retrieve configuration data for FeatureTracker.

Return

config for feature tracking algorithm

Private Functions

std::shared_ptr<RawBuffer> serialize() const override

Private Members

RawFeatureTrackerConfig &cfg

Got questions?

Head over to Discussion Forum for technical support or any other questions you might have.