object_tracker_video.cpp
Go to the documentation of this file.
1 #include <chrono>
2 #include <iostream>
3 
4 #include "utility.hpp"
5 
6 // Includes common necessary includes for development using depthai library
7 #include "depthai/depthai.hpp"
8 
9 static const std::vector<std::string> labelMap = {"", "person"};
10 
11 static std::atomic<bool> fullFrameTracking{false};
12 
13 int main(int argc, char** argv) {
14  using namespace std;
15  using namespace std::chrono;
16  std::string nnPath(BLOB_PATH);
17  std::string videoPath(VIDEO_PATH);
18 
19  // If path to blob specified, use that
20  if(argc > 2) {
21  nnPath = std::string(argv[1]);
22  videoPath = std::string(argv[2]);
23  }
24 
25  // Print which blob we are using
26  printf("Using blob at path: %s\n", nnPath.c_str());
27  printf("Using video at path: %s\n", videoPath.c_str());
28 
29  // Create pipeline
30  dai::Pipeline pipeline;
31 
32  // Define sources and outputs
33  auto manip = pipeline.create<dai::node::ImageManip>();
34  auto objectTracker = pipeline.create<dai::node::ObjectTracker>();
35  auto detectionNetwork = pipeline.create<dai::node::MobileNetDetectionNetwork>();
36 
37  auto manipOut = pipeline.create<dai::node::XLinkOut>();
38  auto xinFrame = pipeline.create<dai::node::XLinkIn>();
39  auto trackerOut = pipeline.create<dai::node::XLinkOut>();
40  auto xlinkOut = pipeline.create<dai::node::XLinkOut>();
41  auto nnOut = pipeline.create<dai::node::XLinkOut>();
42 
43  manipOut->setStreamName("manip");
44  xinFrame->setStreamName("inFrame");
45  xlinkOut->setStreamName("trackerFrame");
46  trackerOut->setStreamName("tracklets");
47  nnOut->setStreamName("nn");
48 
49  // Properties
50  xinFrame->setMaxDataSize(1920 * 1080 * 3);
51 
52  manip->initialConfig.setResizeThumbnail(544, 320);
53  // manip->initialConfig.setResize(384, 384);
54  // manip->initialConfig.setKeepAspectRatio(false); //squash the image to not lose FOV
55  // The NN model expects BGR input. By default ImageManip output type would be same as input (gray in this case)
56  manip->initialConfig.setFrameType(dai::ImgFrame::Type::BGR888p);
57  manip->inputImage.setBlocking(true);
58 
59  // setting node configs
60  detectionNetwork->setBlobPath(nnPath);
61  detectionNetwork->setConfidenceThreshold(0.5);
62  detectionNetwork->input.setBlocking(true);
63 
64  objectTracker->inputTrackerFrame.setBlocking(true);
65  objectTracker->inputDetectionFrame.setBlocking(true);
66  objectTracker->inputDetections.setBlocking(true);
67  objectTracker->setDetectionLabelsToTrack({1}); // track only person
68  // possible tracking types: ZERO_TERM_COLOR_HISTOGRAM, ZERO_TERM_IMAGELESS, SHORT_TERM_IMAGELESS, SHORT_TERM_KCF
69  objectTracker->setTrackerType(dai::TrackerType::ZERO_TERM_COLOR_HISTOGRAM);
70  // take the smallest ID when new object is tracked, possible options: SMALLEST_ID, UNIQUE_ID
71  objectTracker->setTrackerIdAssignmentPolicy(dai::TrackerIdAssignmentPolicy::SMALLEST_ID);
72 
73  // Linking
74  manip->out.link(manipOut->input);
75  manip->out.link(detectionNetwork->input);
76  xinFrame->out.link(manip->inputImage);
77  xinFrame->out.link(objectTracker->inputTrackerFrame);
78  detectionNetwork->out.link(nnOut->input);
79  detectionNetwork->out.link(objectTracker->inputDetections);
80  detectionNetwork->passthrough.link(objectTracker->inputDetectionFrame);
81  objectTracker->out.link(trackerOut->input);
82  objectTracker->passthroughTrackerFrame.link(xlinkOut->input);
83 
84  // Connect to device and start pipeline
85  dai::Device device(pipeline);
86 
87  auto qIn = device.getInputQueue("inFrame", 4);
88  auto trackerFrameQ = device.getOutputQueue("trackerFrame", 4);
89  auto tracklets = device.getOutputQueue("tracklets", 4);
90  auto qManip = device.getOutputQueue("manip", 4);
91  auto qDet = device.getOutputQueue("nn", 4);
92 
93  auto startTime = steady_clock::now();
94  int counter = 0;
95  float fps = 0;
96  cv::Mat frame;
97  cv::Mat manipFrame;
98  std::vector<dai::ImgDetection> detections;
99 
100  // Add bounding boxes and text to the frame and show it to the user
101  auto displayFrame = [](std::string name, cv::Mat frame, std::vector<dai::ImgDetection>& detections) {
102  auto color = cv::Scalar(255, 0, 0);
103  // nn data, being the bounding box locations, are in <0..1> range - they need to be normalized with frame width/height
104  for(auto& detection : detections) {
105  int x1 = detection.xmin * frame.cols;
106  int y1 = detection.ymin * frame.rows;
107  int x2 = detection.xmax * frame.cols;
108  int y2 = detection.ymax * frame.rows;
109 
110  uint32_t labelIndex = detection.label;
111  std::string labelStr = to_string(labelIndex);
112  if(labelIndex < labelMap.size()) {
113  labelStr = labelMap[labelIndex];
114  }
115  cv::putText(frame, labelStr, cv::Point(x1 + 10, y1 + 20), cv::FONT_HERSHEY_TRIPLEX, 0.5, color);
116  std::stringstream confStr;
117  confStr << std::fixed << std::setprecision(2) << detection.confidence * 100;
118  cv::putText(frame, confStr.str(), cv::Point(x1 + 10, y1 + 40), cv::FONT_HERSHEY_TRIPLEX, 0.5, color);
119  cv::rectangle(frame, cv::Rect(cv::Point(x1, y1), cv::Point(x2, y2)), color, cv::FONT_HERSHEY_SIMPLEX);
120  }
121  // Show the frame
122  cv::imshow(name, frame);
123  };
124 
125  cv::VideoCapture cap(videoPath);
126  auto baseTs = steady_clock::now();
127  float simulatedFps = 30;
128 
129  while(cap.isOpened()) {
130  // Read frame from video
131  cap >> frame;
132  if(frame.empty()) break;
133 
134  auto img = std::make_shared<dai::ImgFrame>();
135  frame = resizeKeepAspectRatio(frame, cv::Size(1920, 1080), cv::Scalar(0));
136  toPlanar(frame, img->getData());
137  img->setTimestamp(baseTs);
138  baseTs += steady_clock::duration(static_cast<int64_t>((1000 * 1000 * 1000 / simulatedFps)));
139  img->setWidth(1920);
140  img->setHeight(1080);
141  img->setType(dai::ImgFrame::Type::BGR888p);
142  qIn->send(img);
143 
144  auto trackFrame = trackerFrameQ->tryGet<dai::ImgFrame>();
145  if(!trackFrame) {
146  continue;
147  }
148 
149  auto track = tracklets->get<dai::Tracklets>();
150  auto inManip = qManip->get<dai::ImgFrame>();
151  auto inDet = qDet->get<dai::ImgDetections>();
152 
153  counter++;
154  auto currentTime = steady_clock::now();
155  auto elapsed = duration_cast<duration<float>>(currentTime - startTime);
156  if(elapsed > seconds(1)) {
157  fps = counter / elapsed.count();
158  counter = 0;
159  startTime = currentTime;
160  }
161 
162  detections = inDet->detections;
163  manipFrame = inManip->getCvFrame();
164  displayFrame("nn", manipFrame, detections);
165 
166  auto color = cv::Scalar(255, 0, 0);
167  cv::Mat trackerFrame = trackFrame->getCvFrame();
168  auto trackletsData = track->tracklets;
169  for(auto& t : trackletsData) {
170  auto roi = t.roi.denormalize(trackerFrame.cols, trackerFrame.rows);
171  int x1 = roi.topLeft().x;
172  int y1 = roi.topLeft().y;
173  int x2 = roi.bottomRight().x;
174  int y2 = roi.bottomRight().y;
175 
176  uint32_t labelIndex = t.label;
177  std::string labelStr = to_string(labelIndex);
178  if(labelIndex < labelMap.size()) {
179  labelStr = labelMap[labelIndex];
180  }
181  cv::putText(trackerFrame, labelStr, cv::Point(x1 + 10, y1 + 20), cv::FONT_HERSHEY_TRIPLEX, 0.5, color);
182 
183  std::stringstream idStr;
184  idStr << "ID: " << t.id;
185  cv::putText(trackerFrame, idStr.str(), cv::Point(x1 + 10, y1 + 40), cv::FONT_HERSHEY_TRIPLEX, 0.5, color);
186  std::stringstream statusStr;
187  statusStr << "Status: " << t.status;
188  cv::putText(trackerFrame, statusStr.str(), cv::Point(x1 + 10, y1 + 60), cv::FONT_HERSHEY_TRIPLEX, 0.5, color);
189 
190  cv::rectangle(trackerFrame, cv::Rect(cv::Point(x1, y1), cv::Point(x2, y2)), color, cv::FONT_HERSHEY_SIMPLEX);
191  }
192 
193  std::stringstream fpsStr;
194  fpsStr << "NN fps:" << std::fixed << std::setprecision(2) << fps;
195  cv::putText(trackerFrame, fpsStr.str(), cv::Point(2, trackFrame->getHeight() - 4), cv::FONT_HERSHEY_TRIPLEX, 0.4, color);
196 
197  cv::imshow("tracker", trackerFrame);
198 
199  int key = cv::waitKey(1);
200  if(key == 'q' || key == 'Q') {
201  return 0;
202  }
203  }
204  return 0;
205 }
dai::node::XLinkOut
XLinkOut node. Sends messages over XLink.
Definition: XLinkOut.hpp:14
labelMap
static const std::vector< std::string > labelMap
Definition: object_tracker_video.cpp:9
dai::Pipeline
Represents the pipeline, set of nodes and connections between them.
Definition: Pipeline.hpp:100
fps
static constexpr int fps
Definition: rgb_depth_aligned.cpp:12
dai::TrackerIdAssignmentPolicy::SMALLEST_ID
@ SMALLEST_ID
Take the smallest available ID.
dai::Tracklets
Definition: Tracklets.hpp:15
dai::TrackerType::ZERO_TERM_COLOR_HISTOGRAM
@ ZERO_TERM_COLOR_HISTOGRAM
Tracking using image data too.
dai::RawImgFrame::Type::BGR888p
@ BGR888p
dai::Device::getOutputQueue
std::shared_ptr< DataOutputQueue > getOutputQueue(const std::string &name)
Definition: Device.cpp:86
toPlanar
void toPlanar(cv::Mat &bgr, std::vector< std::uint8_t > &data)
Definition: utility.cpp:100
dai::node::ObjectTracker::out
Output out
Definition: ObjectTracker.hpp:47
dai::node::XLinkOut::input
Input input
Definition: XLinkOut.hpp:27
depthai.hpp
dai::Pipeline::create
std::shared_ptr< N > create()
Definition: Pipeline.hpp:145
dai::node::XLinkIn::setStreamName
void setStreamName(const std::string &name)
Definition: XLinkIn.cpp:12
dai::node::ObjectTracker
ObjectTracker node. Performs object tracking using Kalman filter and hungarian algorithm.
Definition: ObjectTracker.hpp:19
dai::node::ImageManip::out
Output out
Definition: ImageManip.hpp:51
main
int main(int argc, char **argv)
Definition: object_tracker_video.cpp:13
dai::ImgFrame
Definition: ImgFrame.hpp:25
nanorpc::core::exception::to_string
std::string to_string(std::exception const &e)
Definition: exception.h:46
dai::node::ImageManip
ImageManip node. Capability to crop, resize, warp, ... incoming image frames.
Definition: ImageManip.hpp:15
dai::Device
Definition: Device.hpp:21
resizeKeepAspectRatio
cv::Mat resizeKeepAspectRatio(const cv::Mat &input, const cv::Size &dstSize, const cv::Scalar &bgcolor)
Definition: utility.cpp:113
std
Definition: Node.hpp:366
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::MobileNetDetectionNetwork
MobileNetDetectionNetwork node. Parses MobileNet results.
Definition: DetectionNetwork.hpp:56
dai::node::XLinkOut::setStreamName
void setStreamName(const std::string &name)
Definition: XLinkOut.cpp:13
dai::ImgDetections
Definition: ImgDetections.hpp:14
fullFrameTracking
static std::atomic< bool > fullFrameTracking
Definition: object_tracker_video.cpp:11
utility.hpp


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