calibration_reader.cpp
Go to the documentation of this file.
1 #include <cstdio>
2 #include <iostream>
3 #include <string>
4 
5 // Includes common necessary includes for development using depthai library
8 #include "depthai/depthai.hpp"
9 
10 void printMatrix(std::vector<std::vector<float>> matrix) {
11  using namespace std;
12  std::string out = "[";
13  for(auto row : matrix) {
14  out += "[";
15  for(auto val : row) out += to_string(val) + ", ";
16  out = out.substr(0, out.size() - 2) + "]\n";
17  }
18  out = out.substr(0, out.size() - 1) + "]\n\n";
19  cout << out;
20 }
21 
22 int main(int argc, char** argv) {
23  using namespace std;
24 
25  // Connect Device
26  dai::Device device;
27 
28  dai::CalibrationHandler calibData = device.readCalibration();
29  // calibData.eepromToJsonFile(filename);
30  std::vector<std::vector<float>> intrinsics;
31  int width, height;
32 
33  cout << "Intrinsics from defaultIntrinsics function:" << endl;
34  std::tie(intrinsics, width, height) = calibData.getDefaultIntrinsics(dai::CameraBoardSocket::CAM_C);
35  printMatrix(intrinsics);
36 
37  cout << "Width: " << width << endl;
38  cout << "Height: " << height << endl;
39 
40  cout << "Stereo baseline distance: " << calibData.getBaselineDistance() << " cm" << endl;
41 
42  cout << "Mono FOV from camera specs: " << calibData.getFov(dai::CameraBoardSocket::CAM_B)
43  << ", calculated FOV: " << calibData.getFov(dai::CameraBoardSocket::CAM_B, false) << endl;
44 
45  cout << "Intrinsics from getCameraIntrinsics function full resolution:" << endl;
46  intrinsics = calibData.getCameraIntrinsics(dai::CameraBoardSocket::CAM_C);
47  printMatrix(intrinsics);
48 
49  cout << "Intrinsics from getCameraIntrinsics function 1280 x 720:" << endl;
50  intrinsics = calibData.getCameraIntrinsics(dai::CameraBoardSocket::CAM_C, 1280, 720);
51  printMatrix(intrinsics);
52 
53  cout << "Intrinsics from getCameraIntrinsics function 720 x 450:" << endl;
54  intrinsics = calibData.getCameraIntrinsics(dai::CameraBoardSocket::CAM_C, 720);
55  printMatrix(intrinsics);
56 
57  cout << "Intrinsics from getCameraIntrinsics function 600 x 1280:" << endl;
58  intrinsics = calibData.getCameraIntrinsics(dai::CameraBoardSocket::CAM_C, 600, 1280);
59  printMatrix(intrinsics);
60 
61  std::vector<std::vector<float>> extrinsics;
62 
63  cout << "Extrinsics from left->right test:" << endl;
65  printMatrix(extrinsics);
66 
67  cout << "Extrinsics from right->left test:" << endl;
69  printMatrix(extrinsics);
70 
71  cout << "Extrinsics from right->rgb test:" << endl;
73  printMatrix(extrinsics);
74 
75  cout << "Extrinsics from rgb->right test:" << endl;
77  printMatrix(extrinsics);
78 
79  cout << "Extrinsics from left->rgb test:" << endl;
81  printMatrix(extrinsics);
82 
83  return 0;
84 }
dai::CalibrationHandler::getCameraExtrinsics
std::vector< std::vector< float > > getCameraExtrinsics(CameraBoardSocket srcCamera, CameraBoardSocket dstCamera, bool useSpecTranslation=false) const
Definition: CalibrationHandler.cpp:357
dai::CalibrationHandler::getDefaultIntrinsics
std::tuple< std::vector< std::vector< float > >, int, int > getDefaultIntrinsics(CameraBoardSocket cameraId) const
Definition: CalibrationHandler.cpp:291
dai::CameraBoardSocket::CAM_A
@ CAM_A
CameraBoardSocket.hpp
dai::CalibrationHandler::getCameraIntrinsics
std::vector< std::vector< float > > getCameraIntrinsics(CameraBoardSocket cameraId, int resizeWidth=-1, int resizeHeight=-1, Point2f topLeftPixelId=Point2f(), Point2f bottomRightPixelId=Point2f(), bool keepAspectRatio=true) const
Definition: CalibrationHandler.cpp:204
dai::CameraBoardSocket::CAM_B
@ CAM_B
depthai.hpp
dai::DeviceBase::readCalibration
CalibrationHandler readCalibration()
Definition: DeviceBase.cpp:1376
dai::CalibrationHandler::getBaselineDistance
float getBaselineDistance(CameraBoardSocket cam1=CameraBoardSocket::CAM_C, CameraBoardSocket cam2=CameraBoardSocket::CAM_B, bool useSpecTranslation=true) const
Definition: CalibrationHandler.cpp:400
EepromData.hpp
dai::CameraBoardSocket::CAM_C
@ CAM_C
main
int main(int argc, char **argv)
Definition: calibration_reader.cpp:22
nanorpc::core::exception::to_string
std::string to_string(std::exception const &e)
Definition: exception.h:46
dai::CalibrationHandler::getFov
float getFov(CameraBoardSocket cameraId, bool useSpec=true) const
Definition: CalibrationHandler.cpp:328
dai::CalibrationHandler
Definition: CalibrationHandler.hpp:24
dai::Device
Definition: Device.hpp:21
printMatrix
void printMatrix(std::vector< std::vector< float >> matrix)
Definition: calibration_reader.cpp:10
std
Definition: Node.hpp:366


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