diff --git a/.github/workflows/main.yml b/.github/workflows/main.yml index cddb6ccc..7c75340e 100755 --- a/.github/workflows/main.yml +++ b/.github/workflows/main.yml @@ -17,8 +17,8 @@ on: workflow_dispatch: env: - MC_CALIB_PROD_DOCKER_IMG: bailool/mc-calib-prod:opencv420 - MC_CALIB_DEV_DOCKER_IMG: bailool/mc-calib-dev:opencv420 + MC_CALIB_PROD_DOCKER_IMG: bailool/mc-calib-prod:opencv4100 + MC_CALIB_DEV_DOCKER_IMG: bailool/mc-calib-dev:opencv4100 # A workflow run is made up of one or more jobs that can run sequentially or in parallel jobs: @@ -70,6 +70,34 @@ jobs: run-clang-tidy + test-charuco-boards-generation: + runs-on: ubuntu-latest + needs: + - clang-format-lint + - cppcheck + - clang-tidy + steps: + - name: Checkout + uses: actions/checkout@v2 + + - name: Run charuco boards generation app + uses: addnab/docker-run-action@v3 + with: + image: ${{env.MC_CALIB_PROD_DOCKER_IMG}} + options: -v ${{ github.workspace }}:/home/MC-Calib:rw + run: | + mkdir MC-Calib/build && cd MC-Calib/build + cmake -DCMAKE_BUILD_TYPE=Release .. + make -j4 + ./apps/create_charuco_boards/generate_charuco ../tests/configs_for_end2end_tests/calib_param_synth_Scenario1.yml + + - name: Archive results artifacts + uses: actions/upload-artifact@v4 + with: + name: charuco_boards + path: ${{ github.workspace }}/build/charuco_boards + + unit-tests-with-sanitizers: if: ${{ false }} # TODO: disable for now until understand how to suppress leaks from external libraries like OpenCV runs-on: ubuntu-latest @@ -146,7 +174,7 @@ jobs: ./apps/calibrate/calibrate ../tests/configs_for_end2end_tests/calib_param_synth_Scenario1.yml - unit-tests-in-release-mode: + unit-tests-in-release-mode-opencv4100: runs-on: ubuntu-latest needs: - clang-format-lint @@ -208,6 +236,67 @@ jobs: name: results_blender_sequences path: ${{ github.workspace }}/data/Blender_Images/Results_Blender_Sequences + unit-tests-in-release-mode-opencv455: + runs-on: ubuntu-latest + needs: + - clang-format-lint + - cppcheck + - clang-tidy + steps: + - name: Checkout + uses: actions/checkout@v2 + + - name: Checkout MC-Calib-data + uses: actions/checkout@v4 + with: + repository: BAILOOL/MC-Calib-data + path: ${{ github.workspace }}/data + lfs: 'true' + + - name: Unzip MC-Calib-data + run: tar xf ${{ github.workspace }}/data/Blender_Images.tar.gz -C ${{ github.workspace }}/data + + - name: Run tests + uses: addnab/docker-run-action@v3 + with: + image: bailool/mc-calib-prod:opencv455 + options: -v ${{ github.workspace }}:/home/MC-Calib:rw + run: | + mkdir MC-Calib/build && cd MC-Calib/build + cmake -DCMAKE_BUILD_TYPE=Release .. + make -j4 + ./tests/boost_tests_run + + unit-tests-in-release-mode-opencv420: + runs-on: ubuntu-latest + needs: + - clang-format-lint + - cppcheck + - clang-tidy + steps: + - name: Checkout + uses: actions/checkout@v2 + + - name: Checkout MC-Calib-data + uses: actions/checkout@v4 + with: + repository: BAILOOL/MC-Calib-data + path: ${{ github.workspace }}/data + lfs: 'true' + + - name: Unzip MC-Calib-data + run: tar xf ${{ github.workspace }}/data/Blender_Images.tar.gz -C ${{ github.workspace }}/data + + - name: Run tests + uses: addnab/docker-run-action@v3 + with: + image: bailool/mc-calib-prod:opencv420 + options: -v ${{ github.workspace }}:/home/MC-Calib:rw + run: | + mkdir MC-Calib/build && cd MC-Calib/build + cmake -DCMAKE_BUILD_TYPE=Release .. + make -j4 + ./tests/boost_tests_run code-coverage-testing: runs-on: ubuntu-latest @@ -262,7 +351,7 @@ jobs: python-utils-linters: runs-on: ubuntu-latest needs: - - unit-tests-in-release-mode + - unit-tests-in-release-mode-opencv4100 steps: - name: Checkout uses: actions/checkout@v2 @@ -282,7 +371,7 @@ jobs: runs-on: ubuntu-latest needs: - python-utils-linters - - unit-tests-in-release-mode + - unit-tests-in-release-mode-opencv4100 steps: - name: Checkout uses: actions/checkout@v2 diff --git a/CMakeLists.txt b/CMakeLists.txt index afde1551..9b19dc38 100755 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -34,7 +34,8 @@ if(ENABLE_COVERAGE) # add coverage target add_custom_target(coverage # gather data - COMMAND ${LCOV} --directory . --capture --output-file coverage.info --exclude '/usr/*' + COMMAND ${LCOV} --directory . --capture --output-file coverage.info --exclude '/usr/*' + --ignore-errors mismatch,negative # generate report COMMAND ${GENHTML} --demangle-cpp -o coverage coverage.info WORKING_DIRECTORY ${CMAKE_BINARY_DIR}) @@ -80,7 +81,7 @@ endif (DOXYGEN_FOUND) ########################################################################## -add_subdirectory(apps/create_charuco_boards) add_subdirectory(McCalib) +add_subdirectory(apps/create_charuco_boards) add_subdirectory(apps/calibrate) add_subdirectory(tests) diff --git a/Dockerfile b/Dockerfile index c86218a9..36e42fa4 100755 --- a/Dockerfile +++ b/Dockerfile @@ -1,4 +1,4 @@ -FROM ubuntu:20.04 as prod +FROM ubuntu:24.04 as prod ENV DEBIAN_FRONTEND noninteractive RUN apt update && apt install -y --no-install-recommends apt-utils && \ @@ -15,14 +15,14 @@ WORKDIR /home #------------------------------ # # INSTALL OPENCV 4 # #------------------------------ # -RUN wget -O opencv.zip https://github.com/opencv/opencv/archive/4.2.0.zip && \ - wget -O opencv_contrib.zip https://github.com/opencv/opencv_contrib/archive/4.2.0.zip && \ +RUN wget -O opencv.zip https://github.com/opencv/opencv/archive/4.10.0.zip && \ + wget -O opencv_contrib.zip https://github.com/opencv/opencv_contrib/archive/4.10.0.zip && \ unzip opencv.zip && unzip opencv_contrib.zip && \ mkdir -p build && cd build && \ - cmake -DOPENCV_EXTRA_MODULES_PATH=../opencv_contrib-4.2.0/modules ../opencv-4.2.0 && \ + cmake -DOPENCV_EXTRA_MODULES_PATH=../opencv_contrib-4.10.0/modules ../opencv-4.10.0 && \ cmake --build . --target install -- -j4 && \ cd /home && rm opencv.zip && rm opencv_contrib.zip && \ - rm -rf opencv-4.2.0 && rm -rf opencv_contrib-4.2.0 && rm -rf build && \ + rm -rf opencv-4.10.0 && rm -rf opencv_contrib-4.10.0 && rm -rf build && \ rm -rf /var/lib/apt/lists/* #------------------------------ # @@ -49,8 +49,8 @@ RUN git clone --branch 2.2.0 --single-branch https://github.com/ceres-solver/cer # Install python requirements for python_utils scripts RUN --mount=type=bind,source=python_utils/requirements_prod.txt,target=/tmp/requirements.txt \ - apt update && apt install -y libgl1 && \ - python -m pip install --requirement /tmp/requirements.txt && \ + apt update && apt install -y libgl1 libglib2.0-0 && \ + python -m pip install --requirement /tmp/requirements.txt --break-system-packages && \ rm -rf /var/lib/apt/lists/* FROM prod as dev @@ -75,5 +75,5 @@ RUN apt update && apt install -y cppcheck clang-tidy valgrind lcov && \ # Install python requirements for python_utils scripts RUN --mount=type=bind,source=python_utils/requirements_dev.txt,target=/tmp/requirements.txt \ - python -m pip install --requirement /tmp/requirements.txt && \ + python -m pip install --requirement /tmp/requirements.txt --break-system-packages && \ rm -rf /var/lib/apt/lists/* \ No newline at end of file diff --git a/McCalib/include/Board.hpp b/McCalib/include/Board.hpp index 35845cd4..265485e7 100644 --- a/McCalib/include/Board.hpp +++ b/McCalib/include/Board.hpp @@ -44,7 +44,7 @@ class Board final { std::map> frames_; // Charuco board - cv::Ptr charuco_board_; // vector of charuco boards + cv::Ptr charuco_board_; // Functions Board() = delete; diff --git a/McCalib/include/McCalib.hpp b/McCalib/include/McCalib.hpp index d64da630..044f4566 100644 --- a/McCalib/include/McCalib.hpp +++ b/McCalib/include/McCalib.hpp @@ -36,11 +36,22 @@ class Calibration final { public: // Parameters unsigned int nb_camera_, nb_board_; + +#if (defined(CV_VERSION_MAJOR) && CV_VERSION_MAJOR <= 4 && \ + defined(CV_VERSION_MINOR) && CV_VERSION_MINOR < 7) cv::Ptr dict_ = cv::aruco::getPredefinedDictionary( cv::aruco::DICT_6X6_1000); // load the dictionary that correspond to the // charuco board cv::Ptr charuco_params_ = cv::aruco::DetectorParameters::create(); // parameters for detection +#else + cv::aruco::Dictionary dict_ = cv::aruco::getPredefinedDictionary( + cv::aruco::DICT_6X6_1000); // load the dictionary that correspond to the + // charuco board + cv::aruco::DetectorParameters charuco_params_ = + cv::aruco::DetectorParameters(); // parameters for detection +#endif + float min_perc_pts_; // images path diff --git a/McCalib/include/point_refinement.h b/McCalib/include/point_refinement.h index 925c4db1..098875f2 100644 --- a/McCalib/include/point_refinement.h +++ b/McCalib/include/point_refinement.h @@ -1,13 +1,15 @@ -#include "opencv2/core/core.hpp" +#include #include -#include #include +#include "opencv2/core/core.hpp" +#include + namespace McCalib { /****** ******/ -float step_threshold = 0.001; +double step_threshold = 0.001; /** * @struct SaddlePoint @@ -36,7 +38,7 @@ void initSaddlePointRefinement(const int half_kernel_size, int cnt = 0; for (int y = -half_kernel_size; y <= half_kernel_size; y++) for (int x = -half_kernel_size; x <= half_kernel_size; x++) { - *w = maxVal - sqrt(x * x + y * y); + *w = maxVal - std::sqrt(x * x + y * y); if (*w > 0) cnt++; else @@ -138,22 +140,23 @@ void saddleSubpixelRefinement(const cv::Mat &smooth_input, pt.det; // k3 * k1 - 2 * k5 * k2 pt.x += dx; pt.y += dy; - dx = fabs(dx); - dy = fabs(dy); + dx = std::fabs(dx); + dy = std::fabs(dy); // iterations++; if (it == max_iterations || (step_threshold > dx && step_threshold > dy)) { // converged double k4mk5 = r[1] - r[0]; - pt.s = sqrt(r[2] * r[2] + k4mk5 * k4mk5); - pt.a1 = atan2(-r[2], k4mk5) / 2.0; - pt.a2 = acos((r[1] + r[0]) / pt.s) / 2.0; + pt.s = std::sqrt(r[2] * r[2] + k4mk5 * k4mk5); + pt.a1 = std::atan2(-r[2], k4mk5) / 2.0; + pt.a2 = std::acos((r[1] + r[0]) / pt.s) / 2.0; break; } else { // check for divergence - if (pt.det > 0 || fabs(pt.x - initial[idx].x) > window_half_size || - fabs(pt.y - initial[idx].y) > window_half_size) { + if (pt.det > 0 || + std::fabs(pt.x - initial[idx].x) > window_half_size || + std::fabs(pt.y - initial[idx].y) > window_half_size) { pt.x = pt.y = std::numeric_limits::infinity(); // diverged++; break; diff --git a/McCalib/include/utilities.hpp b/McCalib/include/utilities.hpp index e10aea32..71c40d51 100644 --- a/McCalib/include/utilities.hpp +++ b/McCalib/include/utilities.hpp @@ -1,12 +1,42 @@ #include +#include #include #include +#include +#include + namespace McCalib { std::filesystem::path convertStrToPath(const std::string &item_name); std::vector convertVecStrToVecPath(const std::vector &input); +#if (defined(CV_VERSION_MAJOR) && CV_VERSION_MAJOR <= 4 && \ + defined(CV_VERSION_MINOR) && CV_VERSION_MINOR < 7) + +std::map> +createCharucoBoards(const unsigned int num_board, + const std::vector &number_x_square_per_board, + const std::vector &number_y_square_per_board, + const float length_square, const float length_marker, + const cv::Ptr dict); +#else +std::map> +createCharucoBoards(const unsigned int num_board, + const std::vector &number_x_square_per_board, + const std::vector &number_y_square_per_board, + const float length_square, const float length_marker, + const cv::aruco::Dictionary &dict); +#endif + +std::vector +createCharucoBoardsImages(const unsigned int num_board, + const std::vector &number_x_square_per_board, + const std::vector &number_y_square_per_board, + const float length_square, const float length_marker, + const std::vector &resolution_x_per_board, + const std::vector &resolution_y_per_board); + } // namespace McCalib \ No newline at end of file diff --git a/McCalib/src/Camera.cpp b/McCalib/src/Camera.cpp index 1674aba8..79305a47 100644 --- a/McCalib/src/Camera.cpp +++ b/McCalib/src/Camera.cpp @@ -1,8 +1,11 @@ -#include "opencv2/core/core.hpp" +#include #include +#include +#include + +#include "opencv2/core/core.hpp" #include #include -#include #include "Camera.hpp" #include "OptimizationCeres.h" @@ -169,7 +172,9 @@ void Camera::initializeCalibration() { std::srand(unsigned(std::time(0))); std::vector shuffled_board_ind(indbv.size()); std::iota(shuffled_board_ind.begin(), shuffled_board_ind.end(), 0); - random_shuffle(shuffled_board_ind.begin(), shuffled_board_ind.end()); + std::random_device rd; + std::mt19937 g(rd()); + std::shuffle(shuffled_board_ind.begin(), shuffled_board_ind.end(), g); // nb of boards used for the initial estimation of intrinsic parameters //(at least 50 boards for perspective) diff --git a/McCalib/src/McCalib.cpp b/McCalib/src/McCalib.cpp index 60732ae1..b9b51ae7 100644 --- a/McCalib/src/McCalib.cpp +++ b/McCalib/src/McCalib.cpp @@ -117,30 +117,19 @@ Calibration::Calibration(const std::filesystem::path &config_path) { boards_index.resize(nb_board_); std::iota(boards_index.begin(), boards_index.end(), 0); } - std::map> charuco_boards; - int offset_count = 0; - for (int i = 0; i <= max_board_idx; i++) { - cv::Ptr charuco = cv::aruco::CharucoBoard::create( - number_x_square_per_board_[i], number_y_square_per_board_[i], - length_square, length_marker, dict_); - if (i != 0) // If it is the first board then just use the standard idx - { - int id_offset = charuco_boards[i - 1]->ids.size() + offset_count; - offset_count = id_offset; - for (auto &id : charuco->ids) - id += id_offset; - } - charuco_boards[i] = charuco; - } + + const auto charuco_boards = createCharucoBoards( + nb_board_, number_x_square_per_board_, number_y_square_per_board_, + length_square, length_marker, dict_); // Initialize the 3D boards - for (std::size_t i = 0; i < nb_board_; i++) { + for (auto const &[i, charuco_board] : charuco_boards) { // Initialize board std::shared_ptr new_board = std::make_shared(config_path, i); boards_3d_[i] = new_board; boards_3d_[i]->nb_pts_ = (boards_3d_[i]->nb_x_square_ - 1) * (boards_3d_[i]->nb_y_square_ - 1); - boards_3d_[i]->charuco_board_ = charuco_boards[boards_index[i]]; + boards_3d_[i]->charuco_board_ = charuco_board; boards_3d_[i]->pts_3d_.reserve(boards_3d_[i]->nb_pts_); // Prepare the 3D pts of the boards for (int y = 0; y < boards_3d_[i]->nb_y_square_ - 1; y++) { @@ -308,12 +297,27 @@ void Calibration::detectBoardsInImageWithCamera(const std::string &frame_path, // key == board id, value == ID corners on checkerboard std::map> charuco_idx; +#if (defined(CV_VERSION_MAJOR) && CV_VERSION_MAJOR <= 4 && \ + defined(CV_VERSION_MINOR) && CV_VERSION_MINOR < 7) charuco_params_->adaptiveThreshConstant = 1; +#else + charuco_params_.adaptiveThreshConstant = 1; +#endif for (std::size_t i = 0; i < nb_board_; i++) { + +#if (defined(CV_VERSION_MAJOR) && CV_VERSION_MAJOR <= 4 && \ + defined(CV_VERSION_MINOR) && CV_VERSION_MINOR < 7) + cv::aruco::detectMarkers(image, boards_3d_[i]->charuco_board_->dictionary, marker_corners[i], marker_idx[i], charuco_params_); +#else + cv::aruco::ArucoDetector detector( + boards_3d_[i]->charuco_board_->getDictionary(), charuco_params_); + detector.detectMarkers(image, marker_corners[i], marker_idx[i]); +#endif + if (marker_corners[i].size() > 0) { cv::aruco::interpolateCornersCharuco(marker_corners[i], marker_idx[i], image, boards_3d_[i]->charuco_board_, diff --git a/McCalib/src/geometrytools.cpp b/McCalib/src/geometrytools.cpp index 12b1d64e..a4af8b61 100644 --- a/McCalib/src/geometrytools.cpp +++ b/McCalib/src/geometrytools.cpp @@ -1,6 +1,8 @@ #include "opencv2/core/core.hpp" +#include #include #include +#include #include #include "geometrytools.hpp" @@ -169,7 +171,9 @@ void ransacTriangulation(const std::vector &point2d, // Ransac iterations while (N > trialcount && countit < it) { // pick 2 points - std::random_shuffle(myvector.begin(), myvector.end()); + std::random_device rd; + std::mt19937 g(rd()); + std::shuffle(myvector.begin(), myvector.end(), g); std::array idx = {myvector[0], myvector[1], myvector[2], myvector[3]}; @@ -249,9 +253,10 @@ cv::Mat ransacP3P(const std::vector &scenePoints, // Ransac iterations while (N > trialcount && countit < it) { - // pick 4 points - std::random_shuffle(myvector.begin(), myvector.end()); + std::random_device rd; + std::mt19937 g(rd()); + std::shuffle(myvector.begin(), myvector.end(), g); std::array idx = {myvector[0], myvector[1], myvector[2], myvector[3]}; diff --git a/McCalib/src/utilities.cpp b/McCalib/src/utilities.cpp index 468df8f5..d59b0a92 100644 --- a/McCalib/src/utilities.cpp +++ b/McCalib/src/utilities.cpp @@ -1,5 +1,7 @@ #include "utilities.hpp" +#include + namespace McCalib { std::filesystem::path convertStrToPath(const std::string &item_name) { @@ -18,4 +20,124 @@ convertVecStrToVecPath(const std::vector &input) { return out; } +#if (defined(CV_VERSION_MAJOR) && CV_VERSION_MAJOR <= 4 && \ + defined(CV_VERSION_MINOR) && CV_VERSION_MINOR < 7) + +std::map> +createCharucoBoards(const unsigned int num_board, + const std::vector &number_x_square_per_board, + const std::vector &number_y_square_per_board, + const float length_square, const float length_marker, + const cv::Ptr dict) { + std::map> charuco_boards; + int offset_count = 0; + for (std::size_t i = 0; i < num_board; i++) { + // declare the board + cv::Ptr charuco = cv::aruco::CharucoBoard::create( + number_x_square_per_board[i], number_y_square_per_board[i], + length_square, length_marker, dict); + // If it is the first board then just use the standard idx + if (i != 0) { + int id_offset = charuco_boards[i - 1]->ids.size() + offset_count; + offset_count = id_offset; + for (auto &id : charuco->ids) { + id += id_offset; + } + } + charuco_boards[i] = charuco; + } + assert(charuco_boards.size() == num_board); + return charuco_boards; +} + +std::vector +createCharucoBoardsImages(const unsigned int num_board, + const std::vector &number_x_square_per_board, + const std::vector &number_y_square_per_board, + const float length_square, const float length_marker, + const std::vector &resolution_x_per_board, + const std::vector &resolution_y_per_board) { + cv::Ptr dict = + cv::aruco::getPredefinedDictionary(cv::aruco::DICT_6X6_1000); + const std::map> charuco_boards = + createCharucoBoards(num_board, number_x_square_per_board, + number_y_square_per_board, length_square, + length_marker, dict); + + std::vector charuco_boards_images; + charuco_boards_images.reserve(num_board); + for (auto const &[i, charuco_board] : charuco_boards) { + cv::Mat board_image; + charuco_board->draw( + cv::Size(resolution_x_per_board[i], resolution_y_per_board[i]), + board_image, 10, 1); + charuco_boards_images.push_back(board_image); + } + return charuco_boards_images; +} + +#else + +std::map> +createCharucoBoards(const unsigned int num_board, + const std::vector &number_x_square_per_board, + const std::vector &number_y_square_per_board, + const float length_square, const float length_marker, + const cv::aruco::Dictionary &dict) { + std::map> charuco_boards; + int offset_count = 0; + for (std::size_t i = 0; i < num_board; i++) { + if (i == 0) { + // if it is the first board then just use the standard idx + charuco_boards[i] = cv::makePtr( + cv::aruco::CharucoBoard(cv::Size(number_x_square_per_board[i], + number_y_square_per_board[i]), + length_square, length_marker, dict)); + } else { + int id_offset = charuco_boards[i - 1]->getIds().size() + offset_count; + offset_count = id_offset; + + const std::size_t num_idxs = charuco_boards[i - 1]->getIds().size(); + std::vector cur_ids(num_idxs); + std::iota(cur_ids.begin(), cur_ids.end(), id_offset); + + charuco_boards[i] = cv::makePtr( + cv::aruco::CharucoBoard(cv::Size(number_x_square_per_board[i], + number_y_square_per_board[i]), + length_square, length_marker, dict, cur_ids)); + } + } + assert(charuco_boards.size() == num_board); + return charuco_boards; +} + +std::vector +createCharucoBoardsImages(const unsigned int num_board, + const std::vector &number_x_square_per_board, + const std::vector &number_y_square_per_board, + const float length_square, const float length_marker, + const std::vector &resolution_x_per_board, + const std::vector &resolution_y_per_board) { + const cv::aruco::Dictionary dict = + cv::aruco::getPredefinedDictionary(cv::aruco::DICT_6X6_1000); + const std::map> charuco_boards = + createCharucoBoards(num_board, number_x_square_per_board, + number_y_square_per_board, length_square, + length_marker, dict); + + std::vector charuco_boards_images; + charuco_boards_images.reserve(num_board); + for (auto const &[i, charuco_board] : charuco_boards) { + cv::Mat board_image; + charuco_board->generateImage( + cv::Size(resolution_x_per_board[i], resolution_y_per_board[i]), + board_image, 10, 1); + charuco_boards_images.push_back(board_image); + } + + return charuco_boards_images; +} + +#endif + } // namespace McCalib \ No newline at end of file diff --git a/README.md b/README.md index 3a3adee1..092b4b16 100755 --- a/README.md +++ b/README.md @@ -7,7 +7,7 @@ Toolbox described in the paper ["MC-Calib: A generic and robust calibration tool # Installation -Requirements: Ceres, Boost, OpenCV 4.2.0, c++17 +Requirements: Ceres, Boost, OpenCV {4.2.0, 4.5.5, 4.10.0}, c++17 For Windows users, follow [this installation guide](/docs/Windows.md) @@ -20,8 +20,8 @@ There are several ways to get the environment ready. Choose any of them: - Pull the image: ```bash - docker pull bailool/mc-calib-prod:opencv420 # production environment - docker pull bailool/mc-calib-dev:opencv420 # development environment + docker pull bailool/mc-calib-prod:opencv4100 # production environment + docker pull bailool/mc-calib-dev:opencv4100 # development environment ``` - Run pulled image (set `PATH_TO_REPO_ROOT` and `PATH_TO_DATA` appropriately): @@ -31,7 +31,7 @@ There are several ways to get the environment ready. Choose any of them: -ti --rm \ --volume="$PATH_TO_REPO_ROOT:/home/MC-Calib" \ --volume="$PATH_TO_DATA:/home/MC-Calib/data" \ - bailool/mc-calib-prod:opencv420 + bailool/mc-calib-prod:opencv4100 ``` 2. It is also possible to build the docker environment manually (see [instructions](/docs/Docker.md)) diff --git a/apps/create_charuco_boards/CMakeLists.txt b/apps/create_charuco_boards/CMakeLists.txt index 3b01910d..d63910a3 100644 --- a/apps/create_charuco_boards/CMakeLists.txt +++ b/apps/create_charuco_boards/CMakeLists.txt @@ -3,4 +3,4 @@ set(SOURCES ) add_executable(generate_charuco ${SOURCES}) -target_link_libraries(generate_charuco -L/usr/local/lib ${OpenCV_LIBS}) \ No newline at end of file +target_link_libraries(generate_charuco -L/usr/local/lib ${OpenCV_LIBS} McCalib) \ No newline at end of file diff --git a/apps/create_charuco_boards/src/create_charuco_boards.cpp b/apps/create_charuco_boards/src/create_charuco_boards.cpp index 2aedec0b..b0fabecf 100644 --- a/apps/create_charuco_boards/src/create_charuco_boards.cpp +++ b/apps/create_charuco_boards/src/create_charuco_boards.cpp @@ -2,9 +2,30 @@ #include #include -#include #include +#include "McCalib.hpp" +#include "utilities.hpp" + +void saveBoards(const std::vector boards) { + std::filesystem::path charuco_boards_path = "charuco_boards"; + std::string char_name = "charuco_board_"; + std::string ext_name = ".bmp"; + if (!std::filesystem::exists(charuco_boards_path)) { + std::filesystem::create_directories(charuco_boards_path); + } + for (std::size_t board_idx = 0u; board_idx < boards.size(); ++board_idx) { + // Save the markers + std::ostringstream ss; + ss << std::setw(3) << std::setfill('0') << board_idx; + std::string s1 = ss.str(); + std::string save_name = char_name + s1 + ext_name; + std::filesystem::path save_path = charuco_boards_path / save_name; + std::cout << "save_name: " << save_path << std::endl; + cv::imwrite(save_path, boards[board_idx]); + } +} + int main(int argc, char *argv[]) { if (argc != 2) { @@ -39,7 +60,7 @@ int main(int argc, char *argv[]) { fs["number_board"] >> NbBoard; assert(NbBoard > 0); - unsigned int num_board = static_cast(NbBoard); + const unsigned int num_board = static_cast(NbBoard); fs["square_size_per_board"] >> square_size_per_board; fs["number_x_square_per_board"] >> number_x_square_per_board; @@ -59,44 +80,12 @@ int main(int argc, char *argv[]) { } } - // Create the charuco - cv::Ptr dict = - cv::aruco::getPredefinedDictionary(cv::aruco::DICT_6X6_1000); - std::vector> charucoBoards; - int offset_count = 0; - for (std::size_t i = 0; i < num_board; i++) { - // declare the board - cv::Ptr charuco = cv::aruco::CharucoBoard::create( - number_x_square_per_board[i], number_y_square_per_board[i], - length_square, length_marker, dict); - // If it is the first board then just use the standard idx - if (i != 0) { - int id_offset = charucoBoards[i - 1]->ids.size() + offset_count; - offset_count = id_offset; - for (auto &id : charuco->ids) { - id += id_offset; - } - } - // create the charuco board - charucoBoards.push_back(charuco); - cv::Mat boardImage; - charucoBoards[i]->draw( - cv::Size(resolution_x_per_board[i], resolution_y_per_board[i]), - boardImage, 10, 1); - // Display marker - // cv::imshow("My Charuco", boardImage); - // cv::waitKey(1); - // Save the marker - std::ostringstream ss; - ss << std::setw(3) << std::setfill('0') << i; - std::string s1 = ss.str(); - std::string charname = "charuco_board_"; - std::string extname = ".bmp"; - std::string savename = charname + s1; - savename += extname; - std::cout << "save_name " << savename << std::endl; - cv::imwrite(savename, boardImage); - } + const std::vector charuco_boards_images = + McCalib::createCharucoBoardsImages( + num_board, number_x_square_per_board, number_y_square_per_board, + length_square, length_marker, resolution_x_per_board, + resolution_y_per_board); + saveBoards(charuco_boards_images); return 0; } diff --git a/python_utils/requirements_dev.txt b/python_utils/requirements_dev.txt index 2f2858b1..b5cb3329 100644 --- a/python_utils/requirements_dev.txt +++ b/python_utils/requirements_dev.txt @@ -1,4 +1,4 @@ isort==5.13.2 -black==24.4.2 -mypy==1.10.0 -pylint==3.2.2 \ No newline at end of file +black==24.8.0 +mypy==1.11.2 +pylint==3.2.6 \ No newline at end of file diff --git a/python_utils/requirements_prod.txt b/python_utils/requirements_prod.txt index 158559c4..4489ff32 100755 --- a/python_utils/requirements_prod.txt +++ b/python_utils/requirements_prod.txt @@ -1,3 +1,3 @@ -numpy==1.24.4 -matplotlib==3.7.5 -opencv-python==4.9.0.80 +numpy==2.1.0 +matplotlib==3.9.2 +opencv-python==4.10.0.84 \ No newline at end of file diff --git a/tests/test_calibration.cpp b/tests/test_calibration.cpp index 4673fc4d..938f9e8c 100644 --- a/tests/test_calibration.cpp +++ b/tests/test_calibration.cpp @@ -11,9 +11,9 @@ #define PI 3.14159265 -double INTRINSICS_TOLERANCE = 4.0; // in percentage -double TRANSLATION_ERROR_TOLERANCE = 0.005; // in meters -double ROTATION_ERROR_TOLERANCE = 1.0; // in degrees +constexpr double INTRINSICS_TOLERANCE = 4.0; // in percentage +constexpr double TRANSLATION_ERROR_TOLERANCE = 0.005; // in meters +constexpr double ROTATION_ERROR_TOLERANCE = 1.0; // in degrees double getTranslationError(cv::Mat a, cv::Mat b) { double dist = cv::norm(a, b, cv::NORM_L2); @@ -60,7 +60,10 @@ void calibrate(McCalib::Calibration &Calib) { } void calibrateAndCheckGt(const std::filesystem::path &config_path, - const std::filesystem::path >_path) { + const std::filesystem::path >_path, + const double intrinsics_tolerance, + const double translation_error_tolerance, + const double rotation_error_tolerance) { McCalib::Calibration Calib(config_path); calibrate(Calib); @@ -110,12 +113,12 @@ void calibrateAndCheckGt(const std::filesystem::path &config_path, double rot_error = getRotationError(rot_pred, rot_gt); // perform verifications - BOOST_CHECK_CLOSE(fx_pred, fx_gt, INTRINSICS_TOLERANCE); - BOOST_CHECK_CLOSE(fy_pred, fy_gt, INTRINSICS_TOLERANCE); - BOOST_CHECK_CLOSE(cx_pred, cx_gt, INTRINSICS_TOLERANCE); - BOOST_CHECK_CLOSE(cy_pred, cy_gt, INTRINSICS_TOLERANCE); - BOOST_CHECK_SMALL(tran_error, TRANSLATION_ERROR_TOLERANCE); - BOOST_CHECK_SMALL(rot_error, ROTATION_ERROR_TOLERANCE); + BOOST_CHECK_CLOSE(fx_pred, fx_gt, intrinsics_tolerance); + BOOST_CHECK_CLOSE(fy_pred, fy_gt, intrinsics_tolerance); + BOOST_CHECK_CLOSE(cx_pred, cx_gt, intrinsics_tolerance); + BOOST_CHECK_CLOSE(cy_pred, cy_gt, intrinsics_tolerance); + BOOST_CHECK_SMALL(tran_error, translation_error_tolerance); + BOOST_CHECK_SMALL(rot_error, rotation_error_tolerance); } } @@ -134,7 +137,8 @@ BOOST_AUTO_TEST_CASE(CheckCalibrationSyntheticScenario1) { "../data/Blender_Images/Scenario_1/GroundTruth.yml"; BOOST_REQUIRE_EQUAL(std::filesystem::exists(config_path), true); BOOST_REQUIRE_EQUAL(std::filesystem::exists(gt_path), true); - calibrateAndCheckGt(config_path, gt_path); + calibrateAndCheckGt(config_path, gt_path, INTRINSICS_TOLERANCE, + TRANSLATION_ERROR_TOLERANCE, ROTATION_ERROR_TOLERANCE); } BOOST_AUTO_TEST_CASE(CheckCalibrationSyntheticScenario2) { @@ -144,7 +148,8 @@ BOOST_AUTO_TEST_CASE(CheckCalibrationSyntheticScenario2) { "../data/Blender_Images/Scenario_2/GroundTruth.yml"; BOOST_REQUIRE_EQUAL(std::filesystem::exists(config_path), true); BOOST_REQUIRE_EQUAL(std::filesystem::exists(gt_path), true); - calibrateAndCheckGt(config_path, gt_path); + calibrateAndCheckGt(config_path, gt_path, INTRINSICS_TOLERANCE, + TRANSLATION_ERROR_TOLERANCE, ROTATION_ERROR_TOLERANCE); } BOOST_AUTO_TEST_CASE(CheckCalibrationSyntheticScenario3) { @@ -154,7 +159,8 @@ BOOST_AUTO_TEST_CASE(CheckCalibrationSyntheticScenario3) { "../data/Blender_Images/Scenario_3/GroundTruth.yml"; BOOST_REQUIRE_EQUAL(std::filesystem::exists(config_path), true); BOOST_REQUIRE_EQUAL(std::filesystem::exists(gt_path), true); - calibrateAndCheckGt(config_path, gt_path); + calibrateAndCheckGt(config_path, gt_path, INTRINSICS_TOLERANCE, + TRANSLATION_ERROR_TOLERANCE, ROTATION_ERROR_TOLERANCE); } BOOST_AUTO_TEST_CASE(CheckCalibrationSyntheticScenario4) { @@ -164,7 +170,8 @@ BOOST_AUTO_TEST_CASE(CheckCalibrationSyntheticScenario4) { "../data/Blender_Images/Scenario_4/GroundTruth.yml"; BOOST_REQUIRE_EQUAL(std::filesystem::exists(config_path), true); BOOST_REQUIRE_EQUAL(std::filesystem::exists(gt_path), true); - calibrateAndCheckGt(config_path, gt_path); + calibrateAndCheckGt(config_path, gt_path, INTRINSICS_TOLERANCE, + TRANSLATION_ERROR_TOLERANCE, ROTATION_ERROR_TOLERANCE); } BOOST_AUTO_TEST_CASE(CheckCalibrationSyntheticScenario5) { @@ -174,7 +181,9 @@ BOOST_AUTO_TEST_CASE(CheckCalibrationSyntheticScenario5) { "../data/Blender_Images/Scenario_5/GroundTruth.yml"; BOOST_REQUIRE_EQUAL(std::filesystem::exists(config_path), true); BOOST_REQUIRE_EQUAL(std::filesystem::exists(gt_path), true); - calibrateAndCheckGt(config_path, gt_path); + calibrateAndCheckGt(config_path, gt_path, INTRINSICS_TOLERANCE, + 3 * TRANSLATION_ERROR_TOLERANCE, + ROTATION_ERROR_TOLERANCE); } BOOST_AUTO_TEST_SUITE_END() \ No newline at end of file