From 5c19feb02b091304af9ef28437ca812dbc50753f Mon Sep 17 00:00:00 2001 From: Denis Bakin Date: Thu, 18 Jul 2024 17:49:07 +0300 Subject: [PATCH] fix: minor linting and codestyle changes --- packages/camera/CMakeLists.txt | 16 +++++++--------- packages/camera/include/triangulation.h | 5 ++--- packages/camera/src/params.cpp | 12 ++++++------ packages/camera/src/triangulation.cpp | 8 ++++---- 4 files changed, 19 insertions(+), 22 deletions(-) diff --git a/packages/camera/CMakeLists.txt b/packages/camera/CMakeLists.txt index d8973bf..70758b7 100644 --- a/packages/camera/CMakeLists.txt +++ b/packages/camera/CMakeLists.txt @@ -4,7 +4,6 @@ project(camera) add_compile_options(-Wall -Wextra -Werror=unused-variable -Wpedantic) set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -pthread") -# find_package(cv_bridge REQUIRED) find_package(OpenCV REQUIRED) find_package(yaml_cpp_vendor REQUIRED) find_package(ament_cmake REQUIRED) @@ -26,23 +25,22 @@ target_include_directories( target_include_directories( calibration PUBLIC "$" - "/usr/include" + "/usr/include" ) target_include_directories( triangulation PUBLIC "$" - "/usr/include") + "/usr/include" +) ament_target_dependencies(camera yaml_cpp_vendor) ament_target_dependencies(calibration yaml_cpp_vendor Boost OpenCV) - -ament_target_dependencies( - triangulation - OpenCV - yaml_cpp_vendor) +ament_target_dependencies(triangulation OpenCV yaml_cpp_vendor) target_link_libraries(camera mvsdk) -install(TARGETS camera calibration triangulation DESTINATION lib/${PROJECT_NAME}) +install(TARGETS camera calibration triangulation + DESTINATION lib/${PROJECT_NAME} +) if(NOT EXISTS "${CMAKE_CURRENT_SOURCE_DIR}/params") file(MAKE_DIRECTORY "${CMAKE_CURRENT_SOURCE_DIR}/params") diff --git a/packages/camera/include/triangulation.h b/packages/camera/include/triangulation.h index eb410d1..18ca8b9 100644 --- a/packages/camera/include/triangulation.h +++ b/packages/camera/include/triangulation.h @@ -15,7 +15,7 @@ struct StereoParameters { class TriangulationNode { public: - TriangulationNode(std::string ¶ms_file_path, std::vector camera_ids); + TriangulationNode(std::string& params_file_path, std::vector camera_ids); cv::Point3f triangulatePosition(std::vector image_points); @@ -25,6 +25,5 @@ class TriangulationNode { std::vector camera_stereo_params = {}; std::vector projection_matrices = {}; } param_{}; - }; -} // namespace handy \ No newline at end of file +} // namespace handy diff --git a/packages/camera/src/params.cpp b/packages/camera/src/params.cpp index ca7754f..6488887 100644 --- a/packages/camera/src/params.cpp +++ b/packages/camera/src/params.cpp @@ -11,12 +11,12 @@ namespace handy { CameraIntrinsicParameters::CameraIntrinsicParameters( - cv::Size size, cv::Mat camera_matr, const cv::Vec& distort_coefs, const int cam_id) - : image_size(size) - , camera_matrix(std::move(camera_matr)) - , camera_matrix_inv(camera_matrix.inv()) - , dist_coefs(distort_coefs) - , camera_id(cam_id) {} + cv::Size size, cv::Mat camera_matr, const cv::Vec& distort_coefs, const int cam_id) : + image_size(size), + camera_matrix(std::move(camera_matr)), + camera_matrix_inv(camera_matrix.inv()), + dist_coefs(distort_coefs), + camera_id(cam_id) {} void CameraIntrinsicParameters::storeYaml(const std::string& yaml_path) const { const std::string camera_id_str = std::to_string(camera_id); diff --git a/packages/camera/src/triangulation.cpp b/packages/camera/src/triangulation.cpp index 71a1d61..e702463 100644 --- a/packages/camera/src/triangulation.cpp +++ b/packages/camera/src/triangulation.cpp @@ -16,7 +16,7 @@ TriangulationNode::TriangulationNode(std::string& params_file_path, std::vector< printf("only 2 cameras are supported\n"); exit(EXIT_FAILURE); } - for (int i = 0; i < camera_ids.size(); ++i) { + for (size_t i = 0; i < camera_ids.size(); ++i) { param_.cameras_intrinsics.push_back( CameraIntrinsicParameters::loadFromYaml(params_file_path, camera_ids[i])); param_.camera_stereo_params.emplace_back(); @@ -85,7 +85,7 @@ int main(int argc, char* argv[]) { } std::sort(filenames.begin(), filenames.end()); - printf("%d\n", filenames.size()); + printf("%ld\n", filenames.size()); std::string path_file_param(argv[1]); handy::TriangulationNode triangulation_node(path_file_param, {1, 2}); @@ -94,7 +94,7 @@ int main(int argc, char* argv[]) { json triangulation_json; triangulation_json["triangulated_points"] = {}; - for (int i = 0; i < filenames.size(); ++i) { + for (size_t i = 0; i < filenames.size(); ++i) { std::string current_filename = filenames[i]; cv::Point2f first_image_point{ detections_1_json[current_filename]["centroid"][0], @@ -155,4 +155,4 @@ int main(int argc, char* argv[]) { detections_2_json_file.close(); return 0; -} \ No newline at end of file +}