1 #define _USE_MATH_DEFINES
11 #include <unordered_set>
16 #include "nlohmann/json.hpp"
17 #include "spdlog/spdlog.h"
23 using namespace matrix;
26 void invertSe3Matrix4x4InPlace(std::vector<std::vector<float>>& mat) {
28 float temp = mat[0][1];
29 mat[0][1] = mat[1][0];
33 mat[0][2] = mat[2][0];
37 mat[1][2] = mat[2][1];
42 for(
int i = 0; i < 3; ++i) {
44 for(
int j = 0; j < 3; ++j) {
45 newTrans[i] -= mat[i][j] * mat[j][3];
48 for(
int i = 0; i < 3; ++i) mat[i][3] = newTrans[i];
53 std::ifstream jsonStream(eepromDataPath);
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.");
58 if(!jsonStream.good() || jsonStream.bad()) {
59 throw std::runtime_error(
"Calibration data file not found or corrupted");
61 nlohmann::json jsonData = nlohmann::json::parse(jsonStream);
62 eepromData = jsonData;
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]);
86 unsigned versionSize =
sizeof(float) * (9 * 7 + 3 * 2 + 14 * 3);
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");
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");
97 nlohmann::json boardConfigData = nlohmann::json::parse(boardConfigStream);
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;
107 if(!swapLeftRightCam) {
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>();
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;
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;
125 throw std::runtime_error(
"board_config key not found");
128 file.seekg(0, file.end);
129 const unsigned fSize =
static_cast<unsigned>(file.tellg());
130 file.seekg(0, file.beg);
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.");
136 std::vector<float> calibrationBuff(versionSize /
sizeof(
float));
137 file.read(
reinterpret_cast<char*
>(calibrationBuff.data()), fSize);
140 eepromData.stereoRectificationData.rectifiedRotationLeft = matrixConv(calibrationBuff, 0);
141 eepromData.stereoRectificationData.rectifiedRotationRight = matrixConv(calibrationBuff, 9);
142 eepromData.stereoRectificationData.leftCameraSocket = left;
143 eepromData.stereoRectificationData.rightCameraSocket = right;
145 eepromData.cameraData[left].intrinsicMatrix = matrixConv(calibrationBuff, 18);
146 eepromData.cameraData[right].intrinsicMatrix = matrixConv(calibrationBuff, 27);
153 eepromData.cameraData[left].width = 1280;
154 eepromData.cameraData[left].height = 800;
156 eepromData.cameraData[right].width = 1280;
157 eepromData.cameraData[right].height = 800;
162 eepromData.cameraData[left].distortionCoeff = std::vector<float>(calibrationBuff.begin() + 69, calibrationBuff.begin() + 83);
163 eepromData.cameraData[right].distortionCoeff = std::vector<float>(calibrationBuff.begin() + 83, calibrationBuff.begin() + 69 + (2 * 14));
165 std::vector<float>(calibrationBuff.begin() + 69 + (2 * 14), calibrationBuff.begin() + 69 + (3 * 14));
167 eepromData.cameraData[left].extrinsics.rotationMatrix = matrixConv(calibrationBuff, 36);
168 eepromData.cameraData[left].extrinsics.toCameraSocket = right;
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];
174 eepromData.cameraData[right].extrinsics.rotationMatrix = matrixConv(calibrationBuff, 57);
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];
181 CameraInfo& camera = eepromData.cameraData[right];
197 eepromData = newEepromData;
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");
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");
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));
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));
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);
231 scaleW = std::min(scaleW, scaleH);
232 scaleMat = {{scaleW, 0, 0}, {0, scaleW, 0}, {0, 0, 1}};
233 intrinsicMatrix =
matMul(scaleMat, intrinsicMatrix);
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;
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);
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;
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);
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");
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");
271 if(topLeftPixelId.
x > bottomRightPixelId.
x || topLeftPixelId.
y > bottomRightPixelId.
y) {
272 throw std::runtime_error(
"Invalid Crop ratio.");
275 intrinsicMatrix[0][2] -= topLeftPixelId.
x;
276 intrinsicMatrix[1][2] -= topLeftPixelId.
y;
277 return intrinsicMatrix;
282 return getCameraIntrinsics(
283 cameraId,
static_cast<int>(destShape.
width),
static_cast<int>(destShape.
height), topLeftPixelId, bottomRightPixelId, keepAspectRatio);
288 return getCameraIntrinsics(cameraId, std::get<0>(destShape), std::get<1>(destShape), topLeftPixelId, bottomRightPixelId, keepAspectRatio);
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");
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");
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");
301 return {eepromData.cameraData.at(cameraId).intrinsicMatrix, eepromData.cameraData.at(cameraId).width, eepromData.cameraData.at(cameraId).height};
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");
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");
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");
317 std::vector<float> ret(4);
318 for(
int i = 0; i < 4; i++) {
319 ret[i] = eepromData.cameraData.at(cameraId).distortionCoeff[i];
325 return eepromData.cameraData.at(cameraId).distortionCoeff;
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");
333 return eepromData.cameraData.at(cameraId).specHfovDeg;
336 std::vector<std::vector<float>> intrinsics;
339 auto focalLength = intrinsics[0][0];
340 return 2 * 180 / ((float)M_PI) * std::atan(width * 0.5f / focalLength);
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");
347 return eepromData.cameraData.at(cameraId).lensPosition;
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");
354 return eepromData.cameraData.at(cameraId).cameraType;
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");
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");
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);
385 throw std::runtime_error(
"Extrinsic connection between the requested cameraId's doesn't exist. Please recalibrate or modify your calibration data");
391 std::vector<std::vector<float>> extrinsics = getCameraExtrinsics(srcCamera, dstCamera, useSpecTranslation);
393 std::vector<float> translationVector = {0, 0, 0};
394 for(
auto i = 0; i < 3; i++) {
395 translationVector[i] = extrinsics[i][3];
397 return translationVector;
401 std::vector<float> translationVector = getCameraTranslationVector(cam1, cam2, useSpecTranslation);
403 for(
auto val : translationVector) {
406 return std::sqrt(sum);
410 std::vector<std::vector<float>> transformationMatrix = getImuToCameraExtrinsics(cameraId, useSpecTranslation);
411 invertSe3Matrix4x4InPlace(transformationMatrix);
412 return transformationMatrix;
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");
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);
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);
432 std::vector<float> homogeneous_vector = {0, 0, 0, 1};
433 currTransformationMatrixImu.push_back(homogeneous_vector);
435 if(eepromData.imuExtrinsics.toCameraSocket == cameraId) {
436 return currTransformationMatrixImu;
438 std::vector<std::vector<float>> destTransformationMatrixCurr =
439 getCameraExtrinsics(eepromData.imuExtrinsics.toCameraSocket, cameraId, useSpecTranslation);
440 return matMul(destTransformationMatrixCurr, currTransformationMatrixImu);
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 ");
449 return rotationMatrix;
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 ");
458 return rotationMatrix;
462 return eepromData.stereoRectificationData.leftCameraSocket;
466 return eepromData.stereoRectificationData.rightCameraSocket;
470 nlohmann::json j = eepromData;
471 std::ofstream ob(destPath);
472 ob << std::setw(4) << j << std::endl;
482 bool useSpecTranslation)
const {
484 throw std::runtime_error(
"Invalid cameraId input..");
486 if(eepromData.cameraData.at(srcCamera).extrinsics.toCameraSocket == dstCamera) {
487 if(eepromData.cameraData.at(srcCamera).extrinsics.rotationMatrix.size() == 0
489 throw std::runtime_error(
490 "Defined Extrinsic conenction but rotation matrix is not available. Please cross check your calibration data configuration.");
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}");
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);
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);
506 std::vector<float> homogeneous_vector = {0, 0, 0, 1};
507 transformationMatrix.push_back(homogeneous_vector);
508 return transformationMatrix;
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}");
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);
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);
526 std::vector<float> homogeneous_vector = {0, 0, 0, 1};
527 currTransformationMatrixSrc.push_back(homogeneous_vector);
528 return matMul(destTransformationMatrixCurr, currTransformationMatrixSrc);
533 bool isConnectionFound =
false;
536 currentCameraId = eepromData.cameraData.at(currentCameraId).extrinsics.toCameraSocket;
537 if(currentCameraId == dstCamera) {
538 isConnectionFound =
true;
542 return isConnectionFound;
546 eepromData.boardName = boardName;
547 eepromData.boardRev = boardRev;
551 std::string boardName,
552 std::string boardRev,
553 std::string boardConf,
554 std::string hardwareConf,
555 std::string batchName,
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;
568 if(batchName !=
"") {
569 logger::warn(
"batchName parameter not supported anymore");
573 eepromData.version = 7;
577 std::string productName,
578 std::string boardName,
579 std::string boardRev,
580 std::string boardConf,
581 std::string hardwareConf,
582 std::string batchName,
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;
596 if(batchName !=
"") {
597 logger::warn(
"batchName parameter not supported anymore");
601 eepromData.version = 7;
605 eepromData.deviceName = deviceName;
608 eepromData.version = 7;
612 eepromData.productName = productName;
615 eepromData.version = 7;
619 if(intrinsics.size() != 3 || intrinsics[0].size() != 3) {
620 throw std::runtime_error(
"Intrinsic Matrix size should always be 3x3 ");
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!!");
627 if(eepromData.cameraData.find(cameraId) == eepromData.cameraData.end()) {
629 camera_info.
height = height;
630 camera_info.
width = width;
632 eepromData.cameraData.emplace(cameraId, camera_info);
634 eepromData.cameraData.at(cameraId).height = height;
635 eepromData.cameraData.at(cameraId).width = width;
636 eepromData.cameraData.at(cameraId).intrinsicMatrix = intrinsics;
642 setCameraIntrinsics(cameraId, intrinsics,
static_cast<int>(frameSize.
width),
static_cast<int>(frameSize.
height));
647 setCameraIntrinsics(cameraId, intrinsics, std::get<0>(frameSize), std::get<1>(frameSize));
652 const size_t num = 14;
654 if(distortionCoefficients.size() > num) {
655 throw std::runtime_error(
"Too many distortion coefficients! Max is 14.");
659 while(distortionCoefficients.size() != num) {
663 distortionCoefficients.push_back(0.0f);
667 if(eepromData.cameraData.find(cameraId) == eepromData.cameraData.end()) {
670 eepromData.cameraData.emplace(cameraId, camera_info);
672 eepromData.cameraData.at(cameraId).distortionCoeff = distortionCoefficients;
678 if(eepromData.cameraData.find(cameraId) == eepromData.cameraData.end()) {
681 eepromData.cameraData.emplace(cameraId, camera_info);
683 eepromData.cameraData.at(cameraId).specHfovDeg = hfov;
689 if(eepromData.cameraData.find(cameraId) == eepromData.cameraData.end()) {
692 eepromData.cameraData.emplace(cameraId, camera_info);
694 eepromData.cameraData.at(cameraId).lensPosition = lensPosition;
700 if(eepromData.cameraData.find(cameraId) == eepromData.cameraData.end()) {
703 eepromData.cameraData.emplace(cameraId, camera_info);
705 eepromData.cameraData.at(cameraId).cameraType = cameraModel;
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 ");
718 if(translation.size() != 3) {
719 throw std::runtime_error(
"Translation vector size should always be 3x1");
721 if(specTranslation.size() != 3) {
722 throw std::runtime_error(
"specTranslation vector size should always be 3x1");
731 if(eepromData.cameraData.find(srcCameraId) == eepromData.cameraData.end()) {
734 eepromData.cameraData.emplace(srcCameraId, camera_info);
736 eepromData.cameraData[srcCameraId].extrinsics = extrinsics;
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 ");
748 if(translation.size() != 3) {
749 throw std::runtime_error(
"Translation vector size should always be 3x1");
751 if(specTranslation.size() != 3) {
752 throw std::runtime_error(
"specTranslation vector size should always be 3x1");
760 eepromData.imuExtrinsics = extrinsics;
765 if(rectifiedRotation.size() != 3 || rectifiedRotation[0].size() != 3) {
766 throw std::runtime_error(
"Rotation Matrix size should always be 3x3 ");
768 eepromData.stereoRectificationData.rectifiedRotationLeft = rectifiedRotation;
769 eepromData.stereoRectificationData.leftCameraSocket = cameraId;
774 if(rectifiedRotation.size() != 3 || rectifiedRotation[0].size() != 3) {
775 throw std::runtime_error(
"Rotation Matrix size should always be 3x3 ");
777 eepromData.stereoRectificationData.rectifiedRotationRight = rectifiedRotation;
778 eepromData.stereoRectificationData.rightCameraSocket = cameraId;
783 if(eepromData.cameraData.size() > 1) {
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(). ");
798 bool isConnectionValidated =
true;
799 std::unordered_set<dai::CameraBoardSocket> marked;
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;
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;
816 marked.insert(headSocket);
817 headSocket = eepromData.cameraData.at(headSocket).extrinsics.toCameraSocket;
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");
824 return isConnectionValidated;