feature_tracker.cpp
Go to the documentation of this file.
1 #include <iostream>
2 
3 // Includes common necessary includes for development using depthai library
4 #include "depthai/depthai.hpp"
5 #include "deque"
6 #include "unordered_map"
7 #include "unordered_set"
8 
9 static const auto lineColor = cv::Scalar(200, 0, 200);
10 static const auto pointColor = cv::Scalar(0, 0, 255);
11 
13  private:
14  static const int circleRadius = 2;
15  static const int maxTrackedFeaturesPathLength = 30;
16  // for how many frames the feature is tracked
18 
20 
21  std::unordered_set<featureIdType> trackedIDs;
22  std::unordered_map<featureIdType, std::deque<dai::Point2f>> trackedFeaturesPath;
23 
24  std::string trackbarName;
25  std::string windowName;
26 
27  public:
28  void trackFeaturePath(std::vector<dai::TrackedFeature>& features) {
29  std::unordered_set<featureIdType> newTrackedIDs;
30  for(auto& currentFeature : features) {
31  auto currentID = currentFeature.id;
32  newTrackedIDs.insert(currentID);
33 
34  if(!trackedFeaturesPath.count(currentID)) {
35  trackedFeaturesPath.insert({currentID, std::deque<dai::Point2f>()});
36  }
37  std::deque<dai::Point2f>& path = trackedFeaturesPath.at(currentID);
38 
39  path.push_back(currentFeature.position);
40  while(path.size() > std::max<unsigned int>(1, trackedFeaturesPathLength)) {
41  path.pop_front();
42  }
43  }
44 
45  std::unordered_set<featureIdType> featuresToRemove;
46  for(auto& oldId : trackedIDs) {
47  if(!newTrackedIDs.count(oldId)) {
48  featuresToRemove.insert(oldId);
49  }
50  }
51 
52  for(auto& id : featuresToRemove) {
53  trackedFeaturesPath.erase(id);
54  }
55 
56  trackedIDs = newTrackedIDs;
57  }
58 
59  void drawFeatures(cv::Mat& img) {
60  cv::setTrackbarPos(trackbarName.c_str(), windowName.c_str(), trackedFeaturesPathLength);
61 
62  for(auto& featurePath : trackedFeaturesPath) {
63  std::deque<dai::Point2f>& path = featurePath.second;
64  unsigned int j = 0;
65  for(j = 0; j < path.size() - 1; j++) {
66  auto src = cv::Point(path[j].x, path[j].y);
67  auto dst = cv::Point(path[j + 1].x, path[j + 1].y);
68  cv::line(img, src, dst, lineColor, 1, cv::LINE_AA, 0);
69  }
70 
71  cv::circle(img, cv::Point(path[j].x, path[j].y), circleRadius, pointColor, -1, cv::LINE_AA, 0);
72  }
73  }
74 
76  cv::namedWindow(windowName.c_str());
77  cv::createTrackbar(trackbarName.c_str(), windowName.c_str(), &trackedFeaturesPathLength, maxTrackedFeaturesPathLength, nullptr);
78  }
79 };
80 
82 
83 int main() {
84  using namespace std;
85 
86  // Create pipeline
87  dai::Pipeline pipeline;
88 
89  // Define sources and outputs
90  auto monoLeft = pipeline.create<dai::node::MonoCamera>();
91  auto monoRight = pipeline.create<dai::node::MonoCamera>();
92  auto featureTrackerLeft = pipeline.create<dai::node::FeatureTracker>();
93  auto featureTrackerRight = pipeline.create<dai::node::FeatureTracker>();
94 
95  auto xoutPassthroughFrameLeft = pipeline.create<dai::node::XLinkOut>();
96  auto xoutTrackedFeaturesLeft = pipeline.create<dai::node::XLinkOut>();
97  auto xoutPassthroughFrameRight = pipeline.create<dai::node::XLinkOut>();
98  auto xoutTrackedFeaturesRight = pipeline.create<dai::node::XLinkOut>();
99  auto xinTrackedFeaturesConfig = pipeline.create<dai::node::XLinkIn>();
100 
101  xoutPassthroughFrameLeft->setStreamName("passthroughFrameLeft");
102  xoutTrackedFeaturesLeft->setStreamName("trackedFeaturesLeft");
103  xoutPassthroughFrameRight->setStreamName("passthroughFrameRight");
104  xoutTrackedFeaturesRight->setStreamName("trackedFeaturesRight");
105  xinTrackedFeaturesConfig->setStreamName("trackedFeaturesConfig");
106 
107  // Properties
109  monoLeft->setCamera("left");
111  monoRight->setCamera("right");
112 
113  // Linking
114  monoLeft->out.link(featureTrackerLeft->inputImage);
115  featureTrackerLeft->passthroughInputImage.link(xoutPassthroughFrameLeft->input);
116  featureTrackerLeft->outputFeatures.link(xoutTrackedFeaturesLeft->input);
117  xinTrackedFeaturesConfig->out.link(featureTrackerLeft->inputConfig);
118 
119  monoRight->out.link(featureTrackerRight->inputImage);
120  featureTrackerRight->passthroughInputImage.link(xoutPassthroughFrameRight->input);
121  featureTrackerRight->outputFeatures.link(xoutTrackedFeaturesRight->input);
122  xinTrackedFeaturesConfig->out.link(featureTrackerRight->inputConfig);
123 
124  // By default the least mount of resources are allocated
125  // increasing it improves performance when optical flow is enabled
126  auto numShaves = 2;
127  auto numMemorySlices = 2;
128  featureTrackerLeft->setHardwareResources(numShaves, numMemorySlices);
129  featureTrackerRight->setHardwareResources(numShaves, numMemorySlices);
130 
131  auto featureTrackerConfig = featureTrackerRight->initialConfig.get();
132 
133  printf("Press 's' to switch between Lucas-Kanade optical flow and hardware accelerated motion estimation! \n");
134 
135  // Connect to device and start pipeline
136  dai::Device device(pipeline);
137 
138  // Output queues used to receive the results
139  auto passthroughImageLeftQueue = device.getOutputQueue("passthroughFrameLeft", 8, false);
140  auto outputFeaturesLeftQueue = device.getOutputQueue("trackedFeaturesLeft", 8, false);
141  auto passthroughImageRightQueue = device.getOutputQueue("passthroughFrameRight", 8, false);
142  auto outputFeaturesRightQueue = device.getOutputQueue("trackedFeaturesRight", 8, false);
143 
144  auto inputFeatureTrackerConfigQueue = device.getInputQueue("trackedFeaturesConfig");
145 
146  const auto leftWindowName = "left";
147  auto leftFeatureDrawer = FeatureTrackerDrawer("Feature tracking duration (frames)", leftWindowName);
148 
149  const auto rightWindowName = "right";
150  auto rightFeatureDrawer = FeatureTrackerDrawer("Feature tracking duration (frames)", rightWindowName);
151 
152  while(true) {
153  auto inPassthroughFrameLeft = passthroughImageLeftQueue->get<dai::ImgFrame>();
154  cv::Mat passthroughFrameLeft = inPassthroughFrameLeft->getFrame();
155  cv::Mat leftFrame;
156  cv::cvtColor(passthroughFrameLeft, leftFrame, cv::COLOR_GRAY2BGR);
157 
158  auto inPassthroughFrameRight = passthroughImageRightQueue->get<dai::ImgFrame>();
159  cv::Mat passthroughFrameRight = inPassthroughFrameRight->getFrame();
160  cv::Mat rightFrame;
161  cv::cvtColor(passthroughFrameRight, rightFrame, cv::COLOR_GRAY2BGR);
162 
163  auto trackedFeaturesLeft = outputFeaturesLeftQueue->get<dai::TrackedFeatures>()->trackedFeatures;
164  leftFeatureDrawer.trackFeaturePath(trackedFeaturesLeft);
165  leftFeatureDrawer.drawFeatures(leftFrame);
166 
167  auto trackedFeaturesRight = outputFeaturesRightQueue->get<dai::TrackedFeatures>()->trackedFeatures;
168  rightFeatureDrawer.trackFeaturePath(trackedFeaturesRight);
169  rightFeatureDrawer.drawFeatures(rightFrame);
170 
171  // Show the frame
172  cv::imshow(leftWindowName, leftFrame);
173  cv::imshow(rightWindowName, rightFrame);
174 
175  int key = cv::waitKey(1);
176  if(key == 'q') {
177  break;
178  } else if(key == 's') {
179  if(featureTrackerConfig.motionEstimator.type == dai::FeatureTrackerConfig::MotionEstimator::Type::LUCAS_KANADE_OPTICAL_FLOW) {
180  featureTrackerConfig.motionEstimator.type = dai::FeatureTrackerConfig::MotionEstimator::Type::HW_MOTION_ESTIMATION;
181  printf("Switching to hardware accelerated motion estimation \n");
182  } else {
183  featureTrackerConfig.motionEstimator.type = dai::FeatureTrackerConfig::MotionEstimator::Type::LUCAS_KANADE_OPTICAL_FLOW;
184  printf("Switching to Lucas-Kanade optical flow \n");
185  }
186  auto cfg = dai::FeatureTrackerConfig();
187  cfg.set(featureTrackerConfig);
188  inputFeatureTrackerConfigQueue->send(cfg);
189  }
190  }
191  return 0;
192 }
dai::node::MonoCamera::out
Output out
Definition: MonoCamera.hpp:47
dai::node::XLinkOut
XLinkOut node. Sends messages over XLink.
Definition: XLinkOut.hpp:14
dai::node::MonoCamera::setCamera
void setCamera(std::string name)
Definition: MonoCamera.cpp:36
dai::Pipeline
Represents the pipeline, set of nodes and connections between them.
Definition: Pipeline.hpp:100
dai::ImgFrame::getFrame
void getFrame(T...)
Definition: ImgFrame.hpp:218
pointColor
static const auto pointColor
Definition: feature_tracker.cpp:10
FeatureTrackerDrawer::drawFeatures
void drawFeatures(cv::Mat &img)
Definition: feature_tracker.cpp:59
FeatureTrackerDrawer::trackbarName
std::string trackbarName
Definition: feature_tracker.cpp:24
dai::node::MonoCamera
MonoCamera node. For use with grayscale sensors.
Definition: MonoCamera.hpp:17
lineColor
static const auto lineColor
Definition: feature_tracker.cpp:9
FeatureTrackerDrawer::trackedFeaturesPathLength
static int trackedFeaturesPathLength
Definition: feature_tracker.cpp:17
dai::FeatureTrackerConfig::get
dai::RawFeatureTrackerConfig get() const
Definition: FeatureTrackerConfig.cpp:13
main
int main()
Definition: feature_tracker.cpp:83
FeatureTrackerDrawer::maxTrackedFeaturesPathLength
static const int maxTrackedFeaturesPathLength
Definition: feature_tracker.cpp:15
dai::node::FeatureTracker::inputConfig
Input inputConfig
Definition: FeatureTracker.hpp:43
dai::TrackedFeature::id
uint32_t id
Definition: RawTrackedFeatures.hpp:26
dai::RawFeatureTrackerConfig::MotionEstimator::Type::LUCAS_KANADE_OPTICAL_FLOW
@ LUCAS_KANADE_OPTICAL_FLOW
dai::TrackedFeatures
Definition: TrackedFeatures.hpp:14
dai::RawFeatureTrackerConfig::MotionEstimator::Type::HW_MOTION_ESTIMATION
@ HW_MOTION_ESTIMATION
FeatureTrackerDrawer::FeatureTrackerDrawer
FeatureTrackerDrawer(std::string trackbarName, std::string windowName)
Definition: feature_tracker.cpp:75
FeatureTrackerDrawer::featureIdType
decltype(dai::TrackedFeature::id) featureIdType
Definition: feature_tracker.cpp:19
dai::Device::getOutputQueue
std::shared_ptr< DataOutputQueue > getOutputQueue(const std::string &name)
Definition: Device.cpp:86
FeatureTrackerDrawer::windowName
std::string windowName
Definition: feature_tracker.cpp:25
dai::MonoCameraProperties::SensorResolution::THE_720_P
@ THE_720_P
dai::node::XLinkOut::input
Input input
Definition: XLinkOut.hpp:27
depthai.hpp
FeatureTrackerDrawer
Definition: feature_tracker.cpp:12
FeatureTrackerDrawer::trackedIDs
std::unordered_set< featureIdType > trackedIDs
Definition: feature_tracker.cpp:21
dai::Pipeline::create
std::shared_ptr< N > create()
Definition: Pipeline.hpp:145
dai::node::FeatureTracker::outputFeatures
Output outputFeatures
Definition: FeatureTracker.hpp:53
dai::node::FeatureTracker::passthroughInputImage
Output passthroughInputImage
Definition: FeatureTracker.hpp:59
dai::FeatureTrackerConfig
Definition: FeatureTrackerConfig.hpp:14
dai::node::MonoCamera::setResolution
void setResolution(Properties::SensorResolution resolution)
Set sensor resolution.
Definition: MonoCamera.cpp:82
FeatureTrackerDrawer::trackFeaturePath
void trackFeaturePath(std::vector< dai::TrackedFeature > &features)
Definition: feature_tracker.cpp:28
dai::node::FeatureTracker::setHardwareResources
void setHardwareResources(int numShaves, int numMemorySlices)
Definition: FeatureTracker.cpp:32
dai::ImgFrame
Definition: ImgFrame.hpp:25
dai::Device
Definition: Device.hpp:21
std
Definition: Node.hpp:366
FeatureTrackerDrawer::trackedFeaturesPath
std::unordered_map< featureIdType, std::deque< dai::Point2f > > trackedFeaturesPath
Definition: feature_tracker.cpp:22
dai::node::FeatureTracker::inputImage
Input inputImage
Definition: FeatureTracker.hpp:48
dai::node::XLinkIn
XLinkIn node. Receives messages over XLink.
Definition: XLinkIn.hpp:14
dai::Device::getInputQueue
std::shared_ptr< DataInputQueue > getInputQueue(const std::string &name)
Definition: Device.cpp:120
dai::Node::Output::link
void link(const Input &in)
Definition: Node.cpp:84
dai::node::XLinkOut::setStreamName
void setStreamName(const std::string &name)
Definition: XLinkOut.cpp:13
FeatureTrackerDrawer::circleRadius
static const int circleRadius
Definition: feature_tracker.cpp:14
dai::node::FeatureTracker::initialConfig
FeatureTrackerConfig initialConfig
Definition: FeatureTracker.hpp:37
dai::node::FeatureTracker
FeatureTracker node. Performs feature tracking and reidentification using motion estimation between 2...
Definition: FeatureTracker.hpp:20


depthai
Author(s): Martin Peterlin
autogenerated on Sat Mar 22 2025 02:58:19