forked from SpectacularAI/sdk-examples
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathvio_jsonl.cpp
42 lines (34 loc) · 1.26 KB
/
vio_jsonl.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
#include <iostream>
#include <depthai/depthai.hpp>
#include <spectacularAI/depthai/plugin.hpp>
#ifdef EXAMPLE_USE_OPENCV
#include <opencv2/opencv.hpp>
#endif
int main(int argc, char** argv) {
// Create Depth AI (OAK-D) pipeline
dai::Pipeline pipeline;
// Optional configuration
spectacularAI::daiPlugin::Configuration config;
// Example: enable these to support fisheye lenses (SDK 0.16+)
// config.meshRectification = true;
// config.depthScaleCorrection = true;
// If a folder is given as an argument, record session there
if (argc >= 2) config.recordingFolder = argv[1];
spectacularAI::daiPlugin::Pipeline vioPipeline(pipeline, config);
#ifdef EXAMPLE_USE_OPENCV
// note: must set useFeatureTracker = false or mono cam will not be read
vioPipeline.hooks.monoPrimary = [&](std::shared_ptr<dai::ImgFrame> img) {
// Note: typically not main thread
cv::imshow("primary mono cam", img->getCvFrame());
cv::waitKey(1);
};
#endif
// Connect to device and start pipeline
dai::Device device(pipeline);
auto vioSession = vioPipeline.startSession(device);
while (true) {
auto vioOut = vioSession->waitForOutput();
std::cout << vioOut->asJson() << std::endl;
}
return 0;
}