#include <FeatureTrackerConfig.hpp>
Public Types | |
using | CornerDetector = RawFeatureTrackerConfig::CornerDetector |
using | FeatureMaintainer = RawFeatureTrackerConfig::FeatureMaintainer |
using | MotionEstimator = RawFeatureTrackerConfig::MotionEstimator |
Public Member Functions | |
FeatureTrackerConfig () | |
FeatureTrackerConfig (std::shared_ptr< RawFeatureTrackerConfig > ptr) | |
dai::RawFeatureTrackerConfig | get () const |
FeatureTrackerConfig & | set (dai::RawFeatureTrackerConfig config) |
FeatureTrackerConfig & | setCornerDetector (dai::FeatureTrackerConfig::CornerDetector config) |
FeatureTrackerConfig & | setCornerDetector (dai::FeatureTrackerConfig::CornerDetector::Type cornerDetector) |
FeatureTrackerConfig & | setFeatureMaintainer (bool enable) |
FeatureTrackerConfig & | setFeatureMaintainer (dai::FeatureTrackerConfig::FeatureMaintainer config) |
FeatureTrackerConfig & | setHwMotionEstimation () |
FeatureTrackerConfig & | setMotionEstimator (bool enable) |
FeatureTrackerConfig & | setMotionEstimator (dai::FeatureTrackerConfig::MotionEstimator config) |
FeatureTrackerConfig & | setNumTargetFeatures (std::int32_t numTargetFeatures) |
FeatureTrackerConfig & | setOpticalFlow () |
FeatureTrackerConfig & | setOpticalFlow (dai::FeatureTrackerConfig::MotionEstimator::OpticalFlow config) |
virtual | ~FeatureTrackerConfig ()=default |
![]() | |
Buffer () | |
Creates Buffer message. More... | |
Buffer (std::shared_ptr< dai::RawBuffer > ptr) | |
std::vector< std::uint8_t > & | getData () const |
Get non-owning reference to internal buffer. More... | |
int64_t | getSequenceNum () const |
std::chrono::time_point< std::chrono::steady_clock, std::chrono::steady_clock::duration > | getTimestamp () const |
std::chrono::time_point< std::chrono::steady_clock, std::chrono::steady_clock::duration > | getTimestampDevice () const |
void | setData (const std::vector< std::uint8_t > &data) |
void | setData (std::vector< std::uint8_t > &&data) |
Buffer & | setSequenceNum (int64_t sequenceNum) |
Buffer & | setTimestamp (std::chrono::time_point< std::chrono::steady_clock, std::chrono::steady_clock::duration > timestamp) |
Buffer & | setTimestampDevice (std::chrono::time_point< std::chrono::steady_clock, std::chrono::steady_clock::duration > timestamp) |
virtual | ~Buffer ()=default |
![]() | |
ADatatype (std::shared_ptr< RawBuffer > r) | |
std::shared_ptr< RawBuffer > | getRaw () const |
virtual | ~ADatatype ()=default |
Private Member Functions | |
std::shared_ptr< RawBuffer > | serialize () const override |
Private Attributes | |
RawFeatureTrackerConfig & | cfg |
Additional Inherited Members | |
![]() | |
std::shared_ptr< RawBuffer > | raw |
FeatureTrackerConfig message. Carries config for feature tracking algorithm
Definition at line 14 of file FeatureTrackerConfig.hpp.
Definition at line 20 of file FeatureTrackerConfig.hpp.
Definition at line 22 of file FeatureTrackerConfig.hpp.
Definition at line 21 of file FeatureTrackerConfig.hpp.
dai::FeatureTrackerConfig::FeatureTrackerConfig | ( | ) |
Construct FeatureTrackerConfig message.
Definition at line 9 of file FeatureTrackerConfig.cpp.
|
explicit |
Definition at line 10 of file FeatureTrackerConfig.cpp.
|
virtualdefault |
dai::RawFeatureTrackerConfig dai::FeatureTrackerConfig::get | ( | ) | const |
Retrieve configuration data for FeatureTracker.
Definition at line 13 of file FeatureTrackerConfig.cpp.
|
overrideprivatevirtual |
Reimplemented from dai::Buffer.
Definition at line 5 of file FeatureTrackerConfig.cpp.
FeatureTrackerConfig & dai::FeatureTrackerConfig::set | ( | dai::RawFeatureTrackerConfig | config | ) |
Set explicit configuration.
config | Explicit configuration |
Definition at line 66 of file FeatureTrackerConfig.cpp.
FeatureTrackerConfig & dai::FeatureTrackerConfig::setCornerDetector | ( | dai::FeatureTrackerConfig::CornerDetector | config | ) |
Set corner detector full configuration.
config | Corner detector configuration |
Definition at line 22 of file FeatureTrackerConfig.cpp.
FeatureTrackerConfig & dai::FeatureTrackerConfig::setCornerDetector | ( | dai::FeatureTrackerConfig::CornerDetector::Type | cornerDetector | ) |
Set corner detector algorithm type.
cornerDetector | Corner detector type, HARRIS or SHI_THOMASI |
Definition at line 17 of file FeatureTrackerConfig.cpp.
FeatureTrackerConfig & dai::FeatureTrackerConfig::setFeatureMaintainer | ( | bool | enable | ) |
Enable or disable feature maintainer.
enable |
Definition at line 56 of file FeatureTrackerConfig.cpp.
FeatureTrackerConfig & dai::FeatureTrackerConfig::setFeatureMaintainer | ( | dai::FeatureTrackerConfig::FeatureMaintainer | config | ) |
Set feature maintainer full configuration.
config | feature maintainer configuration |
Definition at line 61 of file FeatureTrackerConfig.cpp.
FeatureTrackerConfig & dai::FeatureTrackerConfig::setHwMotionEstimation | ( | ) |
Set hardware accelerated motion estimation using block matching. Faster than optical flow (software implementation) but might not be as accurate.
Definition at line 50 of file FeatureTrackerConfig.cpp.
FeatureTrackerConfig & dai::FeatureTrackerConfig::setMotionEstimator | ( | bool | enable | ) |
Enable or disable motion estimator.
enable |
Definition at line 27 of file FeatureTrackerConfig.cpp.
FeatureTrackerConfig & dai::FeatureTrackerConfig::setMotionEstimator | ( | dai::FeatureTrackerConfig::MotionEstimator | config | ) |
Set motion estimator full configuration.
config | Motion estimator configuration |
Definition at line 32 of file FeatureTrackerConfig.cpp.
FeatureTrackerConfig & dai::FeatureTrackerConfig::setNumTargetFeatures | ( | std::int32_t | numTargetFeatures | ) |
Set number of target features to detect.
numTargetFeatures | Number of features |
Definition at line 71 of file FeatureTrackerConfig.cpp.
FeatureTrackerConfig & dai::FeatureTrackerConfig::setOpticalFlow | ( | ) |
Set optical flow as motion estimation algorithm type.
Definition at line 37 of file FeatureTrackerConfig.cpp.
FeatureTrackerConfig & dai::FeatureTrackerConfig::setOpticalFlow | ( | dai::FeatureTrackerConfig::MotionEstimator::OpticalFlow | config | ) |
Set optical flow full configuration.
config | Optical flow configuration |
Definition at line 43 of file FeatureTrackerConfig.cpp.
|
private |
Definition at line 16 of file FeatureTrackerConfig.hpp.