From 4e1a92b4bbe1e1f7e21de27fb4cc147a87508421 Mon Sep 17 00:00:00 2001 From: Bakin Denis Date: Sun, 30 Jun 2024 14:38:18 +0000 Subject: [PATCH] fix: minor linter errors fixed --- packages/camera/src/triangulation.cpp | 23 +++++++++++------------ 1 file changed, 11 insertions(+), 12 deletions(-) diff --git a/packages/camera/src/triangulation.cpp b/packages/camera/src/triangulation.cpp index 6470c9b..b974002 100644 --- a/packages/camera/src/triangulation.cpp +++ b/packages/camera/src/triangulation.cpp @@ -1,13 +1,14 @@ #include "triangulation.h" -#include -#include -#include #include #include +#include #include +#include +#include -using json = nlohmann::json; +// linter override to preserve json as a type and as a namespace +using json = nlohmann::json; // NOLINT namespace handy { TriangulationNode::TriangulationNode(std::string& params_file_path, std::vector camera_ids) { @@ -26,13 +27,13 @@ TriangulationNode::TriangulationNode(std::string& params_file_path, std::vector< param_.camera_stereo_params.back().translation_vector, camera_ids[i]); cv::Rodrigues(rotation_vector, param_.camera_stereo_params.back().rotation_matrix); - cv::Mat Rt; + cv::Mat rot_trans; // [R|t] matrix cv::hconcat( param_.camera_stereo_params[i].rotation_matrix, param_.camera_stereo_params[i].translation_vector, - Rt); // [R|t] matrix + rot_trans); // [R|t] matrix param_.projection_matrices.push_back( - param_.cameras_intrinsics[i].camera_matrix * Rt); // Projection matrix + param_.cameras_intrinsics[i].camera_matrix * rot_trans); // Projection matrix } } @@ -46,11 +47,9 @@ cv::Point2f normalize(const cv::Point2f& point, const cv::Mat& camera_matrix) { } cv::Point3f TriangulationNode::triangulatePosition(std::vector image_points) { - std::vector point_1 = {image_points[0]}; - std::vector point_2 = {image_points[1]}; - - std::vector undistorted_point_1 = point_1; - std::vector undistorted_point_2 = point_2; + // in case image points were detected on a distorted image, call cv::undistortPoints + std::vector undistorted_point_1 = {image_points[0]}; + std::vector undistorted_point_2 = {image_points[1]}; cv::Mat res_point_homogen; cv::triangulatePoints(