CalibrationHandler.cpp
Go to the documentation of this file.
1 #define _USE_MATH_DEFINES
2 
4 
5 #include <cmath>
6 #include <fstream>
7 #include <iomanip>
8 #include <iostream>
9 #include <string>
10 #include <tuple>
11 #include <unordered_set>
12 
16 #include "nlohmann/json.hpp"
17 #include "spdlog/spdlog.h"
18 #include "utility/Logging.hpp"
19 #include "utility/matrixOps.hpp"
20 
21 namespace dai {
22 
23 using namespace matrix;
24 
25 namespace {
26 void invertSe3Matrix4x4InPlace(std::vector<std::vector<float>>& mat) {
27  // Transpose in-place
28  float temp = mat[0][1];
29  mat[0][1] = mat[1][0];
30  mat[1][0] = temp;
31 
32  temp = mat[0][2];
33  mat[0][2] = mat[2][0];
34  mat[2][0] = temp;
35 
36  temp = mat[1][2];
37  mat[1][2] = mat[2][1];
38  mat[2][1] = temp;
39 
40  // The inverse of an SE(3) transformation (R, t) is (R^T, -R^T t)
41  float newTrans[3];
42  for(int i = 0; i < 3; ++i) {
43  newTrans[i] = 0;
44  for(int j = 0; j < 3; ++j) {
45  newTrans[i] -= mat[i][j] * mat[j][3];
46  }
47  }
48  for(int i = 0; i < 3; ++i) mat[i][3] = newTrans[i];
49 }
50 } // namespace
51 
53  std::ifstream jsonStream(eepromDataPath);
54  // TODO(sachin): Check if the file exists first.
55  if(!jsonStream.is_open()) {
56  throw std::runtime_error("Calibration data file doesn't exist at the provided path. Please provide a absolute path.");
57  }
58  if(!jsonStream.good() || jsonStream.bad()) {
59  throw std::runtime_error("Calibration data file not found or corrupted");
60  }
61  nlohmann::json jsonData = nlohmann::json::parse(jsonStream);
62  eepromData = jsonData;
63 }
64 
65 CalibrationHandler CalibrationHandler::fromJson(nlohmann::json eepromDataJson) {
66  CalibrationHandler calib;
67  calib.eepromData = eepromDataJson;
68  return calib;
69 }
70 
71 CalibrationHandler::CalibrationHandler(dai::Path calibrationDataPath, dai::Path boardConfigPath) {
72  auto matrixConv = [](std::vector<float>& src, int startIdx) {
73  std::vector<std::vector<float>> dest;
74  int currIdx = startIdx;
75  for(int j = 0; j < 3; j++) {
76  std::vector<float> temp;
77  for(int k = 0; k < 3; k++) {
78  temp.push_back(src[currIdx]);
79  currIdx++;
80  }
81  dest.push_back(temp);
82  }
83  return dest;
84  };
85 
86  unsigned versionSize = sizeof(float) * (9 * 7 + 3 * 2 + 14 * 3); /*R1,R2,M1,M2,R,T,M3,R_rgb,T_rgb,d1,d2,d3*/
87  std::ifstream file(calibrationDataPath, std::ios::binary);
88  if(!file.is_open() || !file.good() || file.bad()) {
89  throw std::runtime_error("Calibration data file not found or corrupted");
90  }
91 
92  std::ifstream boardConfigStream(boardConfigPath);
93  if(!boardConfigStream.is_open() || !boardConfigStream.good() || boardConfigStream.bad()) {
94  throw std::runtime_error("BoardConfig file not found or corrupted");
95  }
96 
97  nlohmann::json boardConfigData = nlohmann::json::parse(boardConfigStream);
100 
101  if(boardConfigData.contains("board_config")) {
102  eepromData.boardName = boardConfigData.at("board_config").at("name").get<std::string>();
103  eepromData.boardRev = boardConfigData.at("board_config").at("revision").get<std::string>();
104  bool swapLeftRightCam = boardConfigData.at("board_config").at("swap_left_and_right_cameras").get<bool>();
105  eepromData.version = 6;
106 
107  if(!swapLeftRightCam) {
108  right = CameraBoardSocket::CAM_B;
110  }
111 
112  eepromData.cameraData[right].specHfovDeg = boardConfigData.at("board_config").at("left_fov_deg").get<float>();
113  eepromData.cameraData[left].specHfovDeg = boardConfigData.at("board_config").at("left_fov_deg").get<float>();
114  eepromData.cameraData[CameraBoardSocket::CAM_A].specHfovDeg = boardConfigData.at("board_config").at("rgb_fov_deg").get<float>();
115 
116  eepromData.cameraData[left].extrinsics.specTranslation.x = -boardConfigData.at("board_config").at("left_to_right_distance_cm").get<float>();
117  eepromData.cameraData[left].extrinsics.specTranslation.y = 0;
118  eepromData.cameraData[left].extrinsics.specTranslation.z = 0;
119 
120  eepromData.cameraData[right].extrinsics.specTranslation.x = boardConfigData.at("board_config").at("left_to_right_distance_cm").get<float>()
121  - boardConfigData.at("board_config").at("left_to_rgb_distance_cm").get<float>();
122  eepromData.cameraData[right].extrinsics.specTranslation.y = 0;
123  eepromData.cameraData[right].extrinsics.specTranslation.z = 0;
124  } else {
125  throw std::runtime_error("board_config key not found");
126  }
127 
128  file.seekg(0, file.end);
129  const unsigned fSize = static_cast<unsigned>(file.tellg());
130  file.seekg(0, file.beg);
131 
132  if(fSize != versionSize) {
133  throw std::runtime_error("The calib file version is less than version 5. which has been deprecated. Please Recalibrate with the new version.");
134  }
135 
136  std::vector<float> calibrationBuff(versionSize / sizeof(float));
137  file.read(reinterpret_cast<char*>(calibrationBuff.data()), fSize);
138  // std::vector<float> calibrationBuff(std::istreambuf_iterator<char>(file), {});
139 
140  eepromData.stereoRectificationData.rectifiedRotationLeft = matrixConv(calibrationBuff, 0);
141  eepromData.stereoRectificationData.rectifiedRotationRight = matrixConv(calibrationBuff, 9);
142  eepromData.stereoRectificationData.leftCameraSocket = left;
143  eepromData.stereoRectificationData.rightCameraSocket = right;
144 
145  eepromData.cameraData[left].intrinsicMatrix = matrixConv(calibrationBuff, 18);
146  eepromData.cameraData[right].intrinsicMatrix = matrixConv(calibrationBuff, 27);
147  eepromData.cameraData[CameraBoardSocket::CAM_A].intrinsicMatrix = matrixConv(calibrationBuff, 48); // 9*5 + 3
148 
149  eepromData.cameraData[left].cameraType = CameraModel::Perspective;
150  eepromData.cameraData[right].cameraType = CameraModel::Perspective;
151  eepromData.cameraData[CameraBoardSocket::CAM_A].cameraType = CameraModel::Perspective; // 9*5 + 3
152 
153  eepromData.cameraData[left].width = 1280;
154  eepromData.cameraData[left].height = 800;
155 
156  eepromData.cameraData[right].width = 1280;
157  eepromData.cameraData[right].height = 800;
158 
159  eepromData.cameraData[CameraBoardSocket::CAM_A].width = 1920;
160  eepromData.cameraData[CameraBoardSocket::CAM_A].height = 1080;
161 
162  eepromData.cameraData[left].distortionCoeff = std::vector<float>(calibrationBuff.begin() + 69, calibrationBuff.begin() + 83); // 69 + 14
163  eepromData.cameraData[right].distortionCoeff = std::vector<float>(calibrationBuff.begin() + 83, calibrationBuff.begin() + 69 + (2 * 14));
164  eepromData.cameraData[CameraBoardSocket::CAM_A].distortionCoeff =
165  std::vector<float>(calibrationBuff.begin() + 69 + (2 * 14), calibrationBuff.begin() + 69 + (3 * 14));
166 
167  eepromData.cameraData[left].extrinsics.rotationMatrix = matrixConv(calibrationBuff, 36);
168  eepromData.cameraData[left].extrinsics.toCameraSocket = right;
169 
170  eepromData.cameraData[left].extrinsics.translation.x = calibrationBuff[45];
171  eepromData.cameraData[left].extrinsics.translation.y = calibrationBuff[46];
172  eepromData.cameraData[left].extrinsics.translation.z = calibrationBuff[47];
173 
174  eepromData.cameraData[right].extrinsics.rotationMatrix = matrixConv(calibrationBuff, 57);
175  eepromData.cameraData[right].extrinsics.toCameraSocket = CameraBoardSocket::CAM_A;
176 
177  eepromData.cameraData[right].extrinsics.translation.x = -calibrationBuff[66];
178  eepromData.cameraData[right].extrinsics.translation.y = -calibrationBuff[67];
179  eepromData.cameraData[right].extrinsics.translation.z = -calibrationBuff[68];
180 
181  CameraInfo& camera = eepromData.cameraData[right];
182 
183  float temp = camera.extrinsics.rotationMatrix[0][1];
184  camera.extrinsics.rotationMatrix[0][1] = camera.extrinsics.rotationMatrix[1][0];
185  camera.extrinsics.rotationMatrix[1][0] = temp;
186 
187  temp = camera.extrinsics.rotationMatrix[0][2];
188  camera.extrinsics.rotationMatrix[0][2] = camera.extrinsics.rotationMatrix[2][0];
189  camera.extrinsics.rotationMatrix[2][0] = temp;
190 
191  temp = camera.extrinsics.rotationMatrix[1][2];
192  camera.extrinsics.rotationMatrix[1][2] = camera.extrinsics.rotationMatrix[2][1];
193  camera.extrinsics.rotationMatrix[2][1] = temp;
194 }
195 
197  eepromData = newEepromData;
198 }
199 
201  return eepromData;
202 }
203 
204 std::vector<std::vector<float>> CalibrationHandler::getCameraIntrinsics(
205  CameraBoardSocket cameraId, int resizeWidth, int resizeHeight, Point2f topLeftPixelId, Point2f bottomRightPixelId, bool keepAspectRatio) const {
206  if(eepromData.version < 4) {
207  throw std::runtime_error("Your device contains old calibration which doesn't include Intrinsic data. Please recalibrate your device");
208  }
209  if(eepromData.cameraData.at(cameraId).intrinsicMatrix.size() == 0 || eepromData.cameraData.at(cameraId).intrinsicMatrix[0][0] == 0) {
210  throw std::runtime_error("There is no Intrinsic matrix available for the the requested cameraID");
211  }
212  std::vector<std::vector<float>> intrinsicMatrix = eepromData.cameraData.at(cameraId).intrinsicMatrix;
213  if(resizeWidth != -1 || resizeHeight != -1) {
214  if(resizeWidth == -1) {
215  resizeWidth = static_cast<decltype(resizeWidth)>(eepromData.cameraData.at(cameraId).width * resizeHeight
216  / static_cast<float>(eepromData.cameraData.at(cameraId).height));
217  }
218  if(resizeHeight == -1) {
219  resizeHeight = static_cast<decltype(resizeHeight)>(eepromData.cameraData.at(cameraId).height * resizeWidth
220  / static_cast<float>(eepromData.cameraData.at(cameraId).width));
221  }
222 
223  std::vector<std::vector<float>> scaleMat;
224  if(keepAspectRatio) {
225  float originalRatio = eepromData.cameraData.at(cameraId).width / static_cast<float>(eepromData.cameraData.at(cameraId).height);
226  float resizeRatio = resizeWidth / static_cast<float>(resizeHeight);
227  if(resizeRatio <= 1.34f && originalRatio <= 1.778f && originalRatio > 1.5f) {
228  float scaleW = resizeWidth / static_cast<float>(eepromData.cameraData.at(cameraId).width);
229  float scaleH = resizeHeight / static_cast<float>(eepromData.cameraData.at(cameraId).height);
230 
231  scaleW = std::min(scaleW, scaleH);
232  scaleMat = {{scaleW, 0, 0}, {0, scaleW, 0}, {0, 0, 1}};
233  intrinsicMatrix = matMul(scaleMat, intrinsicMatrix);
234 
235  if(scaleW * eepromData.cameraData.at(cameraId).height < resizeHeight) {
236  intrinsicMatrix[1][2] += static_cast<float>(resizeHeight - eepromData.cameraData.at(cameraId).height * scaleW) / 2.0f;
237  } else if(scaleW * eepromData.cameraData.at(cameraId).width > resizeWidth) {
238  intrinsicMatrix[0][2] += static_cast<float>(resizeWidth - eepromData.cameraData.at(cameraId).width * scaleW) / 2.0f;
239  }
240  } else {
241  float scale = resizeHeight / static_cast<float>(eepromData.cameraData.at(cameraId).height);
242  if(scale * eepromData.cameraData.at(cameraId).width < resizeWidth) {
243  scale = resizeWidth / static_cast<float>(eepromData.cameraData.at(cameraId).width);
244  }
245 
246  scaleMat = {{scale, 0, 0}, {0, scale, 0}, {0, 0, 1}};
247  intrinsicMatrix = matMul(scaleMat, intrinsicMatrix);
248  if(scale * eepromData.cameraData.at(cameraId).height > resizeHeight) {
249  intrinsicMatrix[1][2] -= (eepromData.cameraData.at(cameraId).height * scale - resizeHeight) / 2;
250  } else if(scale * eepromData.cameraData.at(cameraId).width > resizeWidth) {
251  intrinsicMatrix[0][2] -= (eepromData.cameraData.at(cameraId).width * scale - resizeWidth) / 2;
252  }
253  }
254  } else {
255  float scaleX = resizeWidth / static_cast<float>(eepromData.cameraData.at(cameraId).width);
256  float scaleY = resizeHeight / static_cast<float>(eepromData.cameraData.at(cameraId).height);
257  scaleMat = {{scaleX, 0, 0}, {0, scaleY, 0}, {0, 0, 1}};
258  intrinsicMatrix = matMul(scaleMat, intrinsicMatrix);
259  }
260  }
261  if(resizeWidth != -1 || resizeHeight != -1) {
262  if(bottomRightPixelId.y > resizeHeight || bottomRightPixelId.x > resizeWidth) {
263  throw std::runtime_error("Invalid Crop size. Crop width or height is more than the original resized height and width");
264  }
265  } else {
266  if(bottomRightPixelId.y > eepromData.cameraData.at(cameraId).height || bottomRightPixelId.x > eepromData.cameraData.at(cameraId).width) {
267  throw std::runtime_error("Invalid Crop size. Crop width or height is more than the original height and width");
268  }
269  }
270 
271  if(topLeftPixelId.x > bottomRightPixelId.x || topLeftPixelId.y > bottomRightPixelId.y) {
272  throw std::runtime_error("Invalid Crop ratio.");
273  }
274 
275  intrinsicMatrix[0][2] -= topLeftPixelId.x;
276  intrinsicMatrix[1][2] -= topLeftPixelId.y;
277  return intrinsicMatrix;
278 }
279 
280 std::vector<std::vector<float>> CalibrationHandler::getCameraIntrinsics(
281  CameraBoardSocket cameraId, Size2f destShape, Point2f topLeftPixelId, Point2f bottomRightPixelId, bool keepAspectRatio) const {
282  return getCameraIntrinsics(
283  cameraId, static_cast<int>(destShape.width), static_cast<int>(destShape.height), topLeftPixelId, bottomRightPixelId, keepAspectRatio);
284 }
285 
286 std::vector<std::vector<float>> CalibrationHandler::getCameraIntrinsics(
287  CameraBoardSocket cameraId, std::tuple<int, int> destShape, Point2f topLeftPixelId, Point2f bottomRightPixelId, bool keepAspectRatio) const {
288  return getCameraIntrinsics(cameraId, std::get<0>(destShape), std::get<1>(destShape), topLeftPixelId, bottomRightPixelId, keepAspectRatio);
289 }
290 
291 std::tuple<std::vector<std::vector<float>>, int, int> CalibrationHandler::getDefaultIntrinsics(CameraBoardSocket cameraId) const {
292  if(eepromData.version < 4)
293  throw std::runtime_error("Your device contains old calibration which doesn't include Intrinsic data. Please recalibrate your device");
294 
295  if(eepromData.cameraData.find(cameraId) == eepromData.cameraData.end())
296  throw std::runtime_error("There is no Camera data available corresponding to the the requested cameraId");
297 
298  if(eepromData.cameraData.at(cameraId).intrinsicMatrix.size() == 0 || eepromData.cameraData.at(cameraId).intrinsicMatrix[0][0] == 0)
299  throw std::runtime_error("There is no Intrinsic matrix available for the the requested cameraID");
300 
301  return {eepromData.cameraData.at(cameraId).intrinsicMatrix, eepromData.cameraData.at(cameraId).width, eepromData.cameraData.at(cameraId).height};
302 }
303 
305  if(eepromData.version < 4)
306  throw std::runtime_error("Your device contains old calibration which doesn't include Intrinsic data. Please recalibrate your device");
307 
308  if(eepromData.cameraData.find(cameraId) == eepromData.cameraData.end())
309  throw std::runtime_error("There is no Camera data available corresponding to the the requested cameraID");
310 
311  if(eepromData.cameraData.at(cameraId).intrinsicMatrix.size() == 0 || eepromData.cameraData.at(cameraId).intrinsicMatrix[0][0] == 0)
312  throw std::runtime_error("There is no Intrinsic matrix available for the the requested cameraID");
313 
314  if(eepromData.cameraData.at(cameraId).cameraType == CameraModel::Fisheye) {
315  // in this case the camera model is Fisheye; we only want to return four floats.
316  // camera calibration is stored as 14 floats in eeprom, only return the first four.
317  std::vector<float> ret(4);
318  for(int i = 0; i < 4; i++) {
319  ret[i] = eepromData.cameraData.at(cameraId).distortionCoeff[i];
320  }
321  return ret;
322  }
323 
324  // in this case the camera model is Perspective, we want to return all 14
325  return eepromData.cameraData.at(cameraId).distortionCoeff;
326 }
327 
328 float CalibrationHandler::getFov(CameraBoardSocket cameraId, bool useSpec) const {
329  if(eepromData.cameraData.find(cameraId) == eepromData.cameraData.end())
330  throw std::runtime_error("There is no Camera data available corresponding to the the requested cameraID");
331 
332  if(useSpec) {
333  return eepromData.cameraData.at(cameraId).specHfovDeg;
334  }
335  // Calculate fov from intrinsics
336  std::vector<std::vector<float>> intrinsics;
337  int width, height;
338  std::tie(intrinsics, width, height) = CalibrationHandler::getDefaultIntrinsics(cameraId);
339  auto focalLength = intrinsics[0][0];
340  return 2 * 180 / ((float)M_PI) * std::atan(width * 0.5f / focalLength);
341 }
342 
344  if(eepromData.cameraData.find(cameraId) == eepromData.cameraData.end())
345  throw std::runtime_error("There is no Camera data available corresponding to the the requested cameraID");
346 
347  return eepromData.cameraData.at(cameraId).lensPosition;
348 }
349 
351  if(eepromData.cameraData.find(cameraId) == eepromData.cameraData.end())
352  throw std::runtime_error("There is no Camera data available corresponding to the the requested cameraID");
353 
354  return eepromData.cameraData.at(cameraId).cameraType;
355 }
356 
357 std::vector<std::vector<float>> CalibrationHandler::getCameraExtrinsics(CameraBoardSocket srcCamera,
358  CameraBoardSocket dstCamera,
359  bool useSpecTranslation) const {
370  if(eepromData.cameraData.find(srcCamera) == eepromData.cameraData.end()) {
371  throw std::runtime_error("There is no Camera data available corresponding to the the requested source cameraId");
372  }
373  if(eepromData.cameraData.find(dstCamera) == eepromData.cameraData.end()) {
374  throw std::runtime_error("There is no Camera data available corresponding to the the requested destination cameraId");
375  }
376 
377  std::vector<std::vector<float>> extrinsics;
378  if(checkExtrinsicsLink(srcCamera, dstCamera)) {
379  return computeExtrinsicMatrix(srcCamera, dstCamera, useSpecTranslation);
380  } else if(checkExtrinsicsLink(dstCamera, srcCamera)) {
381  extrinsics = computeExtrinsicMatrix(dstCamera, srcCamera, useSpecTranslation);
382  invertSe3Matrix4x4InPlace(extrinsics);
383  return extrinsics;
384  } else {
385  throw std::runtime_error("Extrinsic connection between the requested cameraId's doesn't exist. Please recalibrate or modify your calibration data");
386  }
387  return extrinsics;
388 }
389 
390 std::vector<float> CalibrationHandler::getCameraTranslationVector(CameraBoardSocket srcCamera, CameraBoardSocket dstCamera, bool useSpecTranslation) const {
391  std::vector<std::vector<float>> extrinsics = getCameraExtrinsics(srcCamera, dstCamera, useSpecTranslation);
392 
393  std::vector<float> translationVector = {0, 0, 0};
394  for(auto i = 0; i < 3; i++) {
395  translationVector[i] = extrinsics[i][3];
396  }
397  return translationVector;
398 }
399 
400 float CalibrationHandler::getBaselineDistance(CameraBoardSocket cam1, CameraBoardSocket cam2, bool useSpecTranslation) const {
401  std::vector<float> translationVector = getCameraTranslationVector(cam1, cam2, useSpecTranslation);
402  float sum = 0;
403  for(auto val : translationVector) {
404  sum += val * val;
405  }
406  return std::sqrt(sum);
407 }
408 
409 std::vector<std::vector<float>> CalibrationHandler::getCameraToImuExtrinsics(CameraBoardSocket cameraId, bool useSpecTranslation) const {
410  std::vector<std::vector<float>> transformationMatrix = getImuToCameraExtrinsics(cameraId, useSpecTranslation);
411  invertSe3Matrix4x4InPlace(transformationMatrix);
412  return transformationMatrix;
413 }
414 
415 std::vector<std::vector<float>> CalibrationHandler::getImuToCameraExtrinsics(CameraBoardSocket cameraId, bool useSpecTranslation) const {
416  if(eepromData.imuExtrinsics.rotationMatrix.size() == 0 || eepromData.imuExtrinsics.toCameraSocket == CameraBoardSocket::AUTO) {
417  throw std::runtime_error("IMU calibration data is not available on device yet.");
418  } else if(eepromData.cameraData.find(cameraId) == eepromData.cameraData.end()) {
419  throw std::runtime_error("There is no Camera data available corresponding to the requested source cameraId");
420  }
421 
422  std::vector<std::vector<float>> currTransformationMatrixImu = eepromData.imuExtrinsics.rotationMatrix;
423  if(useSpecTranslation) {
424  currTransformationMatrixImu[0].push_back(eepromData.imuExtrinsics.specTranslation.x);
425  currTransformationMatrixImu[1].push_back(eepromData.imuExtrinsics.specTranslation.y);
426  currTransformationMatrixImu[2].push_back(eepromData.imuExtrinsics.specTranslation.z);
427  } else {
428  currTransformationMatrixImu[0].push_back(eepromData.imuExtrinsics.translation.x);
429  currTransformationMatrixImu[1].push_back(eepromData.imuExtrinsics.translation.y);
430  currTransformationMatrixImu[2].push_back(eepromData.imuExtrinsics.translation.z);
431  }
432  std::vector<float> homogeneous_vector = {0, 0, 0, 1};
433  currTransformationMatrixImu.push_back(homogeneous_vector);
434 
435  if(eepromData.imuExtrinsics.toCameraSocket == cameraId) {
436  return currTransformationMatrixImu;
437  } else {
438  std::vector<std::vector<float>> destTransformationMatrixCurr =
439  getCameraExtrinsics(eepromData.imuExtrinsics.toCameraSocket, cameraId, useSpecTranslation);
440  return matMul(destTransformationMatrixCurr, currTransformationMatrixImu);
441  }
442 }
443 
444 std::vector<std::vector<float>> CalibrationHandler::getStereoRightRectificationRotation() const {
445  std::vector<std::vector<float>> rotationMatrix = eepromData.stereoRectificationData.rectifiedRotationRight;
446  if(rotationMatrix.size() != 3 || rotationMatrix[0].size() != 3) {
447  throw std::runtime_error("Rectified Rotation Matrix Doesn't exist ");
448  }
449  return rotationMatrix;
450 }
451 
452 std::vector<std::vector<float>> CalibrationHandler::getStereoLeftRectificationRotation() const {
453  ;
454  std::vector<std::vector<float>> rotationMatrix = eepromData.stereoRectificationData.rectifiedRotationLeft;
455  if(rotationMatrix.size() != 3 || rotationMatrix[0].size() != 3) {
456  throw std::runtime_error("Rectified Rotation Matrix Doesn't exist ");
457  }
458  return rotationMatrix;
459 }
460 
462  return eepromData.stereoRectificationData.leftCameraSocket;
463 }
464 
466  return eepromData.stereoRectificationData.rightCameraSocket;
467 }
468 
470  nlohmann::json j = eepromData;
471  std::ofstream ob(destPath);
472  ob << std::setw(4) << j << std::endl;
473  return true;
474 }
475 
476 nlohmann::json CalibrationHandler::eepromToJson() const {
477  return eepromData;
478 }
479 
480 std::vector<std::vector<float>> CalibrationHandler::computeExtrinsicMatrix(CameraBoardSocket srcCamera,
481  CameraBoardSocket dstCamera,
482  bool useSpecTranslation) const {
483  if(srcCamera == CameraBoardSocket::AUTO || dstCamera == CameraBoardSocket::AUTO) {
484  throw std::runtime_error("Invalid cameraId input..");
485  }
486  if(eepromData.cameraData.at(srcCamera).extrinsics.toCameraSocket == dstCamera) {
487  if(eepromData.cameraData.at(srcCamera).extrinsics.rotationMatrix.size() == 0
488  || eepromData.cameraData.at(srcCamera).extrinsics.toCameraSocket == CameraBoardSocket::AUTO) {
489  throw std::runtime_error(
490  "Defined Extrinsic conenction but rotation matrix is not available. Please cross check your calibration data configuration.");
491  }
492  std::vector<std::vector<float>> transformationMatrix = eepromData.cameraData.at(srcCamera).extrinsics.rotationMatrix;
493  if(useSpecTranslation) {
494  const dai::Point3f& mTrans = eepromData.cameraData.at(srcCamera).extrinsics.specTranslation;
495  if(mTrans.x == 0 && mTrans.y == 0 && mTrans.z == 0) {
496  throw std::runtime_error("Cannot use useSpecTranslation argument since specTranslation has {0, 0, 0}");
497  }
498  transformationMatrix[0].push_back(eepromData.cameraData.at(srcCamera).extrinsics.specTranslation.x);
499  transformationMatrix[1].push_back(eepromData.cameraData.at(srcCamera).extrinsics.specTranslation.y);
500  transformationMatrix[2].push_back(eepromData.cameraData.at(srcCamera).extrinsics.specTranslation.z);
501  } else {
502  transformationMatrix[0].push_back(eepromData.cameraData.at(srcCamera).extrinsics.translation.x);
503  transformationMatrix[1].push_back(eepromData.cameraData.at(srcCamera).extrinsics.translation.y);
504  transformationMatrix[2].push_back(eepromData.cameraData.at(srcCamera).extrinsics.translation.z);
505  }
506  std::vector<float> homogeneous_vector = {0, 0, 0, 1};
507  transformationMatrix.push_back(homogeneous_vector);
508  return transformationMatrix;
509  } else {
510  std::vector<std::vector<float>> destTransformationMatrixCurr =
511  computeExtrinsicMatrix(eepromData.cameraData.at(srcCamera).extrinsics.toCameraSocket, dstCamera, useSpecTranslation);
512  std::vector<std::vector<float>> currTransformationMatrixSrc = eepromData.cameraData.at(srcCamera).extrinsics.rotationMatrix;
513  if(useSpecTranslation) {
514  const dai::Point3f& mTrans = eepromData.cameraData.at(srcCamera).extrinsics.specTranslation;
515  if(mTrans.x == 0 && mTrans.y == 0 && mTrans.z == 0) {
516  throw std::runtime_error("Cannot use useSpecTranslation argument since specTranslation has {0, 0, 0}");
517  }
518  currTransformationMatrixSrc[0].push_back(eepromData.cameraData.at(srcCamera).extrinsics.specTranslation.x);
519  currTransformationMatrixSrc[1].push_back(eepromData.cameraData.at(srcCamera).extrinsics.specTranslation.y);
520  currTransformationMatrixSrc[2].push_back(eepromData.cameraData.at(srcCamera).extrinsics.specTranslation.z);
521  } else {
522  currTransformationMatrixSrc[0].push_back(eepromData.cameraData.at(srcCamera).extrinsics.translation.x);
523  currTransformationMatrixSrc[1].push_back(eepromData.cameraData.at(srcCamera).extrinsics.translation.y);
524  currTransformationMatrixSrc[2].push_back(eepromData.cameraData.at(srcCamera).extrinsics.translation.z);
525  }
526  std::vector<float> homogeneous_vector = {0, 0, 0, 1};
527  currTransformationMatrixSrc.push_back(homogeneous_vector);
528  return matMul(destTransformationMatrixCurr, currTransformationMatrixSrc);
529  }
530 }
531 
533  bool isConnectionFound = false;
534  CameraBoardSocket currentCameraId = srcCamera;
535  while(currentCameraId != CameraBoardSocket::AUTO) {
536  currentCameraId = eepromData.cameraData.at(currentCameraId).extrinsics.toCameraSocket;
537  if(currentCameraId == dstCamera) {
538  isConnectionFound = true;
539  break;
540  }
541  }
542  return isConnectionFound;
543 }
544 
545 void CalibrationHandler::setBoardInfo(std::string boardName, std::string boardRev) {
546  eepromData.boardName = boardName;
547  eepromData.boardRev = boardRev;
548 }
549 
550 void CalibrationHandler::setBoardInfo(std::string productName,
551  std::string boardName,
552  std::string boardRev,
553  std::string boardConf,
554  std::string hardwareConf,
555  std::string batchName,
556  uint64_t batchTime,
557  uint32_t boardOptions,
558  std::string boardCustom) {
559  eepromData.productName = productName;
560  eepromData.boardName = boardName;
561  eepromData.boardRev = boardRev;
562  eepromData.boardConf = boardConf;
563  eepromData.hardwareConf = hardwareConf;
564  eepromData.batchTime = batchTime;
565  eepromData.boardCustom = boardCustom;
566  eepromData.boardOptions = boardOptions;
567 
568  if(batchName != "") {
569  logger::warn("batchName parameter not supported anymore");
570  }
571 
572  // Bump version to V7
573  eepromData.version = 7;
574 }
575 
576 void CalibrationHandler::setBoardInfo(std::string deviceName,
577  std::string productName,
578  std::string boardName,
579  std::string boardRev,
580  std::string boardConf,
581  std::string hardwareConf,
582  std::string batchName,
583  uint64_t batchTime,
584  uint32_t boardOptions,
585  std::string boardCustom) {
586  eepromData.productName = productName;
587  eepromData.boardName = boardName;
588  eepromData.boardRev = boardRev;
589  eepromData.boardConf = boardConf;
590  eepromData.hardwareConf = hardwareConf;
591  eepromData.batchTime = batchTime;
592  eepromData.boardCustom = boardCustom;
593  eepromData.boardOptions = boardOptions;
594  eepromData.deviceName = deviceName;
595 
596  if(batchName != "") {
597  logger::warn("batchName parameter not supported anymore");
598  }
599 
600  // Bump version to V7
601  eepromData.version = 7;
602 }
603 
604 void CalibrationHandler::setDeviceName(std::string deviceName) {
605  eepromData.deviceName = deviceName;
606 
607  // Bump version to V7
608  eepromData.version = 7;
609 }
610 
611 void CalibrationHandler::setProductName(std::string productName) {
612  eepromData.productName = productName;
613 
614  // Bump version to V7
615  eepromData.version = 7;
616 }
617 
618 void CalibrationHandler::setCameraIntrinsics(CameraBoardSocket cameraId, std::vector<std::vector<float>> intrinsics, int width, int height) {
619  if(intrinsics.size() != 3 || intrinsics[0].size() != 3) {
620  throw std::runtime_error("Intrinsic Matrix size should always be 3x3 ");
621  }
622 
623  if(intrinsics[0][1] != 0 || intrinsics[1][0] != 0 || intrinsics[2][0] != 0 || intrinsics[2][1] != 0) {
624  throw std::runtime_error("Invalid Intrinsic Matrix entered!!");
625  }
626 
627  if(eepromData.cameraData.find(cameraId) == eepromData.cameraData.end()) {
628  dai::CameraInfo camera_info;
629  camera_info.height = height;
630  camera_info.width = width;
631  camera_info.intrinsicMatrix = intrinsics;
632  eepromData.cameraData.emplace(cameraId, camera_info);
633  } else {
634  eepromData.cameraData.at(cameraId).height = height;
635  eepromData.cameraData.at(cameraId).width = width;
636  eepromData.cameraData.at(cameraId).intrinsicMatrix = intrinsics;
637  }
638  return;
639 }
640 
641 void CalibrationHandler::setCameraIntrinsics(CameraBoardSocket cameraId, std::vector<std::vector<float>> intrinsics, Size2f frameSize) {
642  setCameraIntrinsics(cameraId, intrinsics, static_cast<int>(frameSize.width), static_cast<int>(frameSize.height));
643  return;
644 }
645 
646 void CalibrationHandler::setCameraIntrinsics(CameraBoardSocket cameraId, std::vector<std::vector<float>> intrinsics, std::tuple<int, int> frameSize) {
647  setCameraIntrinsics(cameraId, intrinsics, std::get<0>(frameSize), std::get<1>(frameSize));
648  return;
649 }
650 
651 void CalibrationHandler::setDistortionCoefficients(CameraBoardSocket cameraId, std::vector<float> distortionCoefficients) {
652  const size_t num = 14;
653 
654  if(distortionCoefficients.size() > num) {
655  throw std::runtime_error("Too many distortion coefficients! Max is 14.");
656  }
657 
658  if(num != 14) {
659  while(distortionCoefficients.size() != num) {
660  // Pad to 14 parameters.
661  // On the device it's static PoD, we always want it to be 14 parameters - for Perspective camera model, we return all 14; for Fisheye camera model,
662  // we only return the first four.
663  distortionCoefficients.push_back(0.0f);
664  }
665  }
666 
667  if(eepromData.cameraData.find(cameraId) == eepromData.cameraData.end()) {
668  dai::CameraInfo camera_info;
669  camera_info.distortionCoeff = distortionCoefficients;
670  eepromData.cameraData.emplace(cameraId, camera_info);
671  } else {
672  eepromData.cameraData.at(cameraId).distortionCoeff = distortionCoefficients;
673  }
674  return;
675 }
676 
677 void CalibrationHandler::setFov(CameraBoardSocket cameraId, float hfov) {
678  if(eepromData.cameraData.find(cameraId) == eepromData.cameraData.end()) {
679  dai::CameraInfo camera_info;
680  camera_info.specHfovDeg = hfov;
681  eepromData.cameraData.emplace(cameraId, camera_info);
682  } else {
683  eepromData.cameraData.at(cameraId).specHfovDeg = hfov;
684  }
685  return;
686 }
687 
688 void CalibrationHandler::setLensPosition(CameraBoardSocket cameraId, uint8_t lensPosition) {
689  if(eepromData.cameraData.find(cameraId) == eepromData.cameraData.end()) {
690  dai::CameraInfo camera_info;
691  camera_info.lensPosition = lensPosition;
692  eepromData.cameraData.emplace(cameraId, camera_info);
693  } else {
694  eepromData.cameraData.at(cameraId).lensPosition = lensPosition;
695  }
696  return;
697 }
698 
700  if(eepromData.cameraData.find(cameraId) == eepromData.cameraData.end()) {
701  dai::CameraInfo camera_info;
702  camera_info.cameraType = cameraModel;
703  eepromData.cameraData.emplace(cameraId, camera_info);
704  } else {
705  eepromData.cameraData.at(cameraId).cameraType = cameraModel;
706  }
707  return;
708 }
709 
711  CameraBoardSocket destCameraId,
712  std::vector<std::vector<float>> rotationMatrix,
713  std::vector<float> translation,
714  std::vector<float> specTranslation) {
715  if(rotationMatrix.size() != 3 || rotationMatrix[0].size() != 3) {
716  throw std::runtime_error("Rotation Matrix size should always be 3x3 ");
717  }
718  if(translation.size() != 3) {
719  throw std::runtime_error("Translation vector size should always be 3x1");
720  }
721  if(specTranslation.size() != 3) {
722  throw std::runtime_error("specTranslation vector size should always be 3x1");
723  }
724 
725  dai::Extrinsics extrinsics;
726  extrinsics.rotationMatrix = rotationMatrix;
727  extrinsics.translation = dai::Point3f(translation[0], translation[1], translation[2]);
728  extrinsics.specTranslation = dai::Point3f(specTranslation[0], specTranslation[1], specTranslation[2]);
729  extrinsics.toCameraSocket = destCameraId;
730 
731  if(eepromData.cameraData.find(srcCameraId) == eepromData.cameraData.end()) {
732  dai::CameraInfo camera_info;
733  camera_info.extrinsics = extrinsics;
734  eepromData.cameraData.emplace(srcCameraId, camera_info);
735  } else {
736  eepromData.cameraData[srcCameraId].extrinsics = extrinsics;
737  }
738  return;
739 }
740 
742  std::vector<std::vector<float>> rotationMatrix,
743  std::vector<float> translation,
744  std::vector<float> specTranslation) {
745  if(rotationMatrix.size() != 3 || rotationMatrix[0].size() != 3) {
746  throw std::runtime_error("Rotation Matrix size should always be 3x3 ");
747  }
748  if(translation.size() != 3) {
749  throw std::runtime_error("Translation vector size should always be 3x1");
750  }
751  if(specTranslation.size() != 3) {
752  throw std::runtime_error("specTranslation vector size should always be 3x1");
753  }
754 
755  dai::Extrinsics extrinsics;
756  extrinsics.rotationMatrix = rotationMatrix;
757  extrinsics.translation = dai::Point3f(translation[0], translation[1], translation[2]);
758  extrinsics.specTranslation = dai::Point3f(specTranslation[0], specTranslation[1], specTranslation[2]);
759  extrinsics.toCameraSocket = destCameraId;
760  eepromData.imuExtrinsics = extrinsics;
761  return;
762 }
763 
764 void CalibrationHandler::setStereoLeft(CameraBoardSocket cameraId, std::vector<std::vector<float>> rectifiedRotation) {
765  if(rectifiedRotation.size() != 3 || rectifiedRotation[0].size() != 3) {
766  throw std::runtime_error("Rotation Matrix size should always be 3x3 ");
767  }
768  eepromData.stereoRectificationData.rectifiedRotationLeft = rectifiedRotation;
769  eepromData.stereoRectificationData.leftCameraSocket = cameraId;
770  return;
771 }
772 
773 void CalibrationHandler::setStereoRight(CameraBoardSocket cameraId, std::vector<std::vector<float>> rectifiedRotation) {
774  if(rectifiedRotation.size() != 3 || rectifiedRotation[0].size() != 3) {
775  throw std::runtime_error("Rotation Matrix size should always be 3x3 ");
776  }
777  eepromData.stereoRectificationData.rectifiedRotationRight = rectifiedRotation;
778  eepromData.stereoRectificationData.rightCameraSocket = cameraId;
779  return;
780 }
781 
783  if(eepromData.cameraData.size() > 1) {
784  if(eepromData.cameraData.find(dai::CameraBoardSocket::CAM_B) != eepromData.cameraData.end()) {
785  return checkSrcLinks(dai::CameraBoardSocket::CAM_B) || checkSrcLinks(dai::CameraBoardSocket::CAM_C);
786  } else {
788  "make sure the head of the Extrinsics is your left camera. Please cross check the data by creating a json file using "
789  "eepromToJsonFile(). ");
790  return false;
791  }
792  } else {
793  return true; // Considering this would be bw1093 device
794  }
795 }
796 
798  bool isConnectionValidated = true;
799  std::unordered_set<dai::CameraBoardSocket> marked;
800 
801  while(headSocket != CameraBoardSocket::AUTO) {
802  if(eepromData.cameraData.find(headSocket) == eepromData.cameraData.end()) {
804  "Found link to a CameraID whose camera calibration is not loaded. Please cross check the connection by creating a json file using "
805  "eepromToJsonFile(). ");
806  isConnectionValidated = false;
807  break;
808  }
809  if(marked.find(headSocket) != marked.end()) {
811  "Loop found in extrinsics connection. Please cross check that the extrinsics are connected in an array in single direction by creating "
812  "a json file using eepromToJsonFile(). ");
813  isConnectionValidated = false;
814  break;
815  }
816  marked.insert(headSocket);
817  headSocket = eepromData.cameraData.at(headSocket).extrinsics.toCameraSocket;
818  }
819 
820  if(isConnectionValidated && eepromData.cameraData.size() != marked.size()) {
821  isConnectionValidated = false;
822  logger::debug("Extrinsics between all the cameras is not found with single head and a tail");
823  }
824  return isConnectionValidated;
825 }
826 
827 } // namespace dai
matrixOps.hpp
dai::CalibrationHandler::setCameraExtrinsics
void setCameraExtrinsics(CameraBoardSocket srcCameraId, CameraBoardSocket destCameraId, std::vector< std::vector< float >> rotationMatrix, std::vector< float > translation, std::vector< float > specTranslation={0, 0, 0})
Definition: CalibrationHandler.cpp:710
dai::CameraBoardSocket::AUTO
@ AUTO
dai::Size2f::height
float height
Definition: Size2f.hpp:18
dai::Point3f::y
float y
Definition: Point3f.hpp:19
dai::CalibrationHandler::checkExtrinsicsLink
bool checkExtrinsicsLink(CameraBoardSocket srcCamera, CameraBoardSocket dstCamera) const
Definition: CalibrationHandler.cpp:532
dai::CalibrationHandler::getCameraExtrinsics
std::vector< std::vector< float > > getCameraExtrinsics(CameraBoardSocket srcCamera, CameraBoardSocket dstCamera, bool useSpecTranslation=false) const
Definition: CalibrationHandler.cpp:357
dai::CalibrationHandler::setCameraIntrinsics
void setCameraIntrinsics(CameraBoardSocket cameraId, std::vector< std::vector< float >> intrinsics, Size2f frameSize)
Definition: CalibrationHandler.cpp:641
dai::CalibrationHandler::eepromToJsonFile
bool eepromToJsonFile(dai::Path destPath) const
Definition: CalibrationHandler.cpp:469
dai::CalibrationHandler::getDefaultIntrinsics
std::tuple< std::vector< std::vector< float > >, int, int > getDefaultIntrinsics(CameraBoardSocket cameraId) const
Definition: CalibrationHandler.cpp:291
dai::CameraInfo::extrinsics
Extrinsics extrinsics
Definition: CameraInfo.hpp:15
CameraInfo.hpp
dai::CameraBoardSocket::CAM_A
@ CAM_A
dai::CameraBoardSocket
CameraBoardSocket
Definition: shared/depthai-shared/include/depthai-shared/common/CameraBoardSocket.hpp:9
dai::CalibrationHandler::getStereoLeftRectificationRotation
std::vector< std::vector< float > > getStereoLeftRectificationRotation() const
Definition: CalibrationHandler.cpp:452
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::CalibrationHandler::checkSrcLinks
bool checkSrcLinks(CameraBoardSocket headSocket) const
Definition: CalibrationHandler.cpp:797
dai::CameraInfo::distortionCoeff
std::vector< float > distortionCoeff
Definition: CameraInfo.hpp:14
dai::CalibrationHandler::getCameraTranslationVector
std::vector< float > getCameraTranslationVector(CameraBoardSocket srcCamera, CameraBoardSocket dstCamera, bool useSpecTranslation=true) const
Definition: CalibrationHandler.cpp:390
dai::CalibrationHandler::setStereoRight
void setStereoRight(CameraBoardSocket cameraId, std::vector< std::vector< float >> rectifiedRotation)
Definition: CalibrationHandler.cpp:773
dai::Point3f::x
float x
Definition: Point3f.hpp:19
dai::Point2f
Definition: Point2f.hpp:16
dai::Point3f::z
float z
Definition: Point3f.hpp:19
dai::logger::debug
void debug(const FormatString &fmt, Args &&...args)
Definition: Logging.hpp:72
dai::CameraInfo
CameraInfo structure.
Definition: CameraInfo.hpp:10
dai::logger::warn
void warn(const FormatString &fmt, Args &&...args)
Definition: Logging.hpp:84
dai::CameraInfo::lensPosition
uint8_t lensPosition
Definition: CameraInfo.hpp:12
dai::Size2f::width
float width
Definition: Size2f.hpp:18
dai::CalibrationHandler::setDeviceName
void setDeviceName(std::string deviceName)
Definition: CalibrationHandler.cpp:604
dai::CameraModel::Perspective
@ Perspective
dai::CalibrationHandler::validateCameraArray
bool validateCameraArray() const
Definition: CalibrationHandler.cpp:782
dai::CalibrationHandler::setBoardInfo
void setBoardInfo(std::string boardName, std::string boardRev)
Definition: CalibrationHandler.cpp:545
dai::CalibrationHandler::setDistortionCoefficients
void setDistortionCoefficients(CameraBoardSocket cameraId, std::vector< float > distortionCoefficients)
Definition: CalibrationHandler.cpp:651
dai::CalibrationHandler::eepromToJson
nlohmann::json eepromToJson() const
Definition: CalibrationHandler.cpp:476
dai::CameraBoardSocket::CAM_B
@ CAM_B
dai::CalibrationHandler::getImuToCameraExtrinsics
std::vector< std::vector< float > > getImuToCameraExtrinsics(CameraBoardSocket cameraId, bool useSpecTranslation=false) const
Definition: CalibrationHandler.cpp:415
dai::Extrinsics::toCameraSocket
CameraBoardSocket toCameraSocket
Definition: Extrinsics.hpp:22
dai::CameraInfo::width
uint16_t width
Definition: CameraInfo.hpp:11
dai::CalibrationHandler::getDistortionCoefficients
std::vector< float > getDistortionCoefficients(CameraBoardSocket cameraId) const
Definition: CalibrationHandler.cpp:304
dai::CalibrationHandler::setFov
void setFov(CameraBoardSocket cameraId, float hfov)
Definition: CalibrationHandler.cpp:677
dai::CalibrationHandler::getBaselineDistance
float getBaselineDistance(CameraBoardSocket cam1=CameraBoardSocket::CAM_C, CameraBoardSocket cam2=CameraBoardSocket::CAM_B, bool useSpecTranslation=true) const
Definition: CalibrationHandler.cpp:400
dai::CameraInfo::specHfovDeg
float specHfovDeg
Definition: CameraInfo.hpp:16
dai::CalibrationHandler::fromJson
static CalibrationHandler fromJson(nlohmann::json eepromDataJson)
Definition: CalibrationHandler.cpp:65
dai::CameraModel
CameraModel
Definition: CameraModel.hpp:9
dai::CameraBoardSocket::CAM_C
@ CAM_C
dai::CalibrationHandler::computeExtrinsicMatrix
std::vector< std::vector< float > > computeExtrinsicMatrix(CameraBoardSocket srcCamera, CameraBoardSocket dstCamera, bool useSpecTranslation=false) const
Definition: CalibrationHandler.cpp:480
dai::CalibrationHandler::setProductName
void setProductName(std::string productName)
Definition: CalibrationHandler.cpp:611
dai::CalibrationHandler::getStereoLeftCameraId
dai::CameraBoardSocket getStereoLeftCameraId() const
Definition: CalibrationHandler.cpp:461
dai::Size2f
Definition: Size2f.hpp:15
dai::Extrinsics
Extrinsics structure.
Definition: Extrinsics.hpp:12
dai::CalibrationHandler::getDistortionModel
CameraModel getDistortionModel(CameraBoardSocket cameraId) const
Definition: CalibrationHandler.cpp:350
dai::CalibrationHandler::getFov
float getFov(CameraBoardSocket cameraId, bool useSpec=true) const
Definition: CalibrationHandler.cpp:328
dai::CalibrationHandler::setStereoLeft
void setStereoLeft(CameraBoardSocket cameraId, std::vector< std::vector< float >> rectifiedRotation)
Definition: CalibrationHandler.cpp:764
dai::CalibrationHandler
Definition: CalibrationHandler.hpp:24
dai::CalibrationHandler::getStereoRightCameraId
dai::CameraBoardSocket getStereoRightCameraId() const
Definition: CalibrationHandler.cpp:465
dai::Extrinsics::rotationMatrix
std::vector< std::vector< float > > rotationMatrix
Definition: Extrinsics.hpp:13
dai::CalibrationHandler::setCameraType
void setCameraType(CameraBoardSocket cameraId, CameraModel cameraModel)
Definition: CalibrationHandler.cpp:699
dai::Extrinsics::translation
Point3f translation
Definition: Extrinsics.hpp:17
dai::CameraInfo::height
uint16_t height
Definition: CameraInfo.hpp:11
dai::CalibrationHandler::getLensPosition
uint8_t getLensPosition(CameraBoardSocket cameraId) const
Definition: CalibrationHandler.cpp:343
dai::CameraInfo::cameraType
CameraModel cameraType
Definition: CameraInfo.hpp:17
dai::CalibrationHandler::setImuExtrinsics
void setImuExtrinsics(CameraBoardSocket destCameraId, std::vector< std::vector< float >> rotationMatrix, std::vector< float > translation, std::vector< float > specTranslation={0, 0, 0})
Definition: CalibrationHandler.cpp:741
CalibrationHandler.hpp
dai::Point2f::x
float x
Definition: Point2f.hpp:19
dai::CalibrationHandler::getStereoRightRectificationRotation
std::vector< std::vector< float > > getStereoRightRectificationRotation() const
Definition: CalibrationHandler.cpp:444
dai::Point3f
Definition: Point3f.hpp:16
dai::CalibrationHandler::getEepromData
dai::EepromData getEepromData() const
Definition: CalibrationHandler.cpp:200
dai::CalibrationHandler::setLensPosition
void setLensPosition(CameraBoardSocket cameraId, uint8_t lensPosition)
Definition: CalibrationHandler.cpp:688
dai::CalibrationHandler::getCameraToImuExtrinsics
std::vector< std::vector< float > > getCameraToImuExtrinsics(CameraBoardSocket cameraId, bool useSpecTranslation=false) const
Definition: CalibrationHandler.cpp:409
dai::Point2f::y
float y
Definition: Point2f.hpp:19
dai::CalibrationHandler::CalibrationHandler
CalibrationHandler()=default
dai::Path
Represents paths on a filesystem; accepts utf-8, Windows utf-16 wchar_t, or std::filesystem::path.
Definition: Path.hpp:27
dai::CalibrationHandler::eepromData
dai::EepromData eepromData
Definition: CalibrationHandler.hpp:547
Logging.hpp
dai::CameraInfo::intrinsicMatrix
std::vector< std::vector< float > > intrinsicMatrix
Definition: CameraInfo.hpp:13
dai::CameraModel::Fisheye
@ Fisheye
dai
Definition: CameraExposureOffset.hpp:6
dai::EepromData
Definition: EepromData.hpp:19
dai::matrix::matMul
std::vector< std::vector< float > > matMul(std::vector< std::vector< float >> &firstMatrix, std::vector< std::vector< float >> &secondMatrix)
Matrix multiplication between two matrixs of shape (m x n) and (n x p) of type float....
Definition: matrixOps.hpp:15
dai::Extrinsics::specTranslation
Point3f specTranslation
Definition: Extrinsics.hpp:21
Point3f.hpp
Extrinsics.hpp


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