Skip to content

Commit

Permalink
Creating static library (#39)
Browse files Browse the repository at this point in the history
  • Loading branch information
BAILOOL authored Apr 4, 2023
1 parent dca41de commit 5b3638d
Show file tree
Hide file tree
Showing 39 changed files with 64 additions and 66 deletions.
27 changes: 6 additions & 21 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 2.8.3)
project(MC-Calib)
cmake_minimum_required(VERSION 3.0)
project(MC-Calib VERSION 1.2.0 DESCRIPTION "MC-Calib: A generic and robust calibration toolbox for multi-camera systems")

add_definitions(-std=c++17)
set(CMAKE_CXX_FLAGS "-std=c++17") # required for Ceres https://github.com/colmap/colmap/issues/905#issuecomment-731138700
Expand Down Expand Up @@ -69,23 +69,8 @@ endif (DOXYGEN_FOUND)


##########################################################################

file(GLOB MC_CALIB_SRC CONFIGURE_DEPENDS src/*.cpp src/*.hpp src/*.h)
list(REMOVE_ITEM MC_CALIB_SRC ${PROJECT_SOURCE_DIR}/src/main_calibrate.cpp ${PROJECT_SOURCE_DIR}/src/main_create_charuco.cpp)

## Single calibration camera + cube
add_executable(calibrate src/main_calibrate.cpp ${MC_CALIB_SRC})

target_link_libraries(calibrate
-L/usr/local/lib ${OpenCV_LIBS} ${CERES_LIBRARIES} Boost::log Boost::system Boost::filesystem
)

##################Generate Charuco######################
add_executable(generate_charuco src/main_create_charuco.cpp)

target_link_libraries(generate_charuco
-L/usr/local/lib ${OpenCV_LIBS} ${CERES_LIBRARIES} Boost::log Boost::system Boost::filesystem
)

# unit tests related
add_subdirectory(apps/create_charuco_boards)
add_subdirectory(McCalib)
find_library(McCalib REQUIRED)
add_subdirectory(apps/calibrate)
add_subdirectory(tests)
8 changes: 8 additions & 0 deletions McCalib/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
file(GLOB MC_CALIB_HEADERS include/*.hpp include/*.h)
file(GLOB MC_CALIB_SOURCES CONFIGURE_DEPENDS src/*.cpp)

add_library(McCalib STATIC ${MC_CALIB_HEADERS} ${MC_CALIB_SOURCES})
set_target_properties(McCalib PROPERTIES VERSION ${PROJECT_VERSION})
target_include_directories(McCalib PUBLIC include)
target_include_directories(McCalib PUBLIC src)
target_link_libraries(McCalib PUBLIC -L/usr/local/lib ${OpenCV_LIBS} ${CERES_LIBRARIES} Boost::log Boost::system Boost::filesystem)
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
4 changes: 4 additions & 0 deletions src/Calibration.hpp → McCalib/include/McCalib.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,8 @@
#include "Object3DObs.hpp"
#include "geometrytools.hpp"

namespace McCalib {

/**
* @class Calibration
*
Expand Down Expand Up @@ -229,3 +231,5 @@ class Calibration final {

std::mutex insert_new_board_lock_;
};

} // namespace McCalib
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
6 changes: 5 additions & 1 deletion src/Calibration.cpp → McCalib/src/McCalib.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,14 +5,16 @@
#include <random>
#include <stdio.h>

#include "Calibration.hpp"
#include "McCalib.hpp"
#include "logger.h"
#include "point_refinement.h"

#include <boost/asio/post.hpp>
#include <boost/asio/thread_pool.hpp>
#include <thread>

namespace McCalib {

/**
* @brief Initialize the number of cameras and the 3D Boards
*
Expand Down Expand Up @@ -2215,3 +2217,5 @@ void Calibration::refineAllCameraGroupAndObjectsAndIntrinsic() {
for (const auto &it : cams_group_obs_)
it.second->updateObjObsPose();
}

} // namespace McCalib
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
20 changes: 10 additions & 10 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -108,11 +108,11 @@ Then the following should do the job of compiling the code inside the `MC-Calib`

1. **Generate your own Charuco boards**

If all your boards are similar (same number of squares in the x and y directions), you only need to specify the `number_x_square`, `number_y_square` and `number_board`. Then you can run the Charuco board generator:
If all your boards are similar (same number of squares in the x and y directions), you only need to specify the `number_x_square`, `number_y_square`, and `number_board`. Then you can run the Charuco board generator:
```bash
./generate_charuco ../configs/calib_param.yml
./apps/create_charuco_boards/generate_charuco ../configs/calib_param.yml
```
If each board have a specific format (different number of squares), then you need to specify it in the fields `number_x_square_per_board` and `number_y_square_per_board`. For instance, if you want to use two boards of size [10x3] and [5x4] respectively, you have to set:
If each board has a specific format (different number of squares), then you need to specify it in the fields `number_x_square_per_board` and `number_y_square_per_board`. For instance, if you want to use two boards of size [10x3] and [5x4] respectively, you have to set:
```
number_board: 2
number_x_square_per_board: [10,5]
Expand All @@ -125,15 +125,15 @@ Then the following should do the job of compiling the code inside the `MC-Calib`

3. **Measure the size of the squares on your boards**

If the boards have all the same square size, you just need to specify it in `square_size` and leave `square_size_per_board` empty. If each board has a different size, specify it in `square_size_per_board`. For instance `square_size_per_board: [1, 25]` means that the first and second boards are composed of square of size `0.1cm` and `0.25cm` respectively. Note that the square size can be in any unit you prefer (m, cm, inch, etc.) and the resulting calibration will also be expressed in this unit.
If the boards have all the same square size, you just need to specify it in `square_size` and leave `square_size_per_board` empty. If each board has a different size, specify it in `square_size_per_board`. For instance, `square_size_per_board: [1, 25]` means that the first and second boards are composed of square of size `0.1cm` and `0.25cm` respectively. Note that the square size can be in any unit you prefer (m, cm, inch, etc.) and the resulting calibration will also be expressed in this unit.

4. **Acquire your images**

MC-Calib has been designed for synchronized cameras, therefore, you have to make sure that all the cameras in the rig capture images at the exact same time. Additionally, this toolbox has been designed and tested for global shutter cameras, therefore we cannot guarantee highly accurate results if you are using rolling shutter sensors. For high-quality calibration, make sure to have a limited quantity of motion blur during your sequence.

5. **Prepare your video sequences**

The images extracted from each cameras have to be stored in a different folders with a common prefix followed by a 3 digits index (starting from 001), for instance if two cameras are used the folder can be called: 'Cam_001' and 'Cam_002'.
The images extracted from each camera have to be stored in different folders with a common prefix followed by a three digits index (starting from 001). For instance, if two cameras are used, the folder can be called: 'Cam_001' and 'Cam_002'.

6. **Setup the configuration file for your system**

Expand All @@ -149,7 +149,7 @@ Then the following should do the job of compiling the code inside the `MC-Calib`
* *Set the outputs:*
By default, MC-Calib will generate the camera calibration results, the reprojection error log, the 3D object structure and the pose of the object for each frames where it has been detected. Additionally, you can save the detection and reprojection images by setting `save_detection` and `save_reprojection` to `1`.
By default, MC-Calib will generate the camera calibration results, the reprojection error log, the 3D object structure, and the pose of the object for each frame where it has been detected. Additionally, you can save the detection and reprojection images by setting `save_detection` and `save_reprojection` to `1`.
* *Using only certain boards:*
Expand All @@ -163,7 +163,7 @@ Then the following should do the job of compiling the code inside the `MC-Calib`
7. **Run the calibration**

```bash
./calibrate_stereo ../configs/calib_param.yml
./apps/calibrate/calibrate ../configs/calib_param.yml
```

## Calibration file
Expand Down Expand Up @@ -194,7 +194,7 @@ number_camera: 2 # number of cameras in the rig to calibrate
refine_corner: 1 # activate or deactivate the corner refinement
min_perc_pts: 0.5 # min percentage of points visible to assume a good detection
cam_params_path: "None" # file with cameras intrinsics to initialize the intrinsic, write "None" if no initialization available
cam_params_path: "None" # file with cameras intrinsics to initialize the intrinsic, write "None" if no initialization available
######################################## Images Parameters ###################################################
root_path: "../data/Synthetic_calibration_image/Scenario_1/Images/"
Expand All @@ -205,7 +205,7 @@ ransac_threshold: 10 # RANSAC threshold in pixel (keep it high just to re
number_iterations: 1000 # Max number of iterations for the non linear refinement
######################################## Hand-eye method #############################################
he_approach: 0 #0: bootstrapped he technique, 1: traditional he
he_approach: 0 #0: bootstrapped he technique, 1: traditional he
######################################## Output Parameters ###################################################
save_path: "experiments/Synthetic_calibration_image/Scenario_1/"
Expand All @@ -216,7 +216,7 @@ camera_params_file_name: "" # "name.yml"

## Output explanation

The calibration toolbox automatically output four ```*.yml``` files. To illustrate them, we propose to display the results obtained from the calibration of a hybrid stereo-vision system.
The calibration toolbox automatically outputs four ```*.yml``` files. To illustrate them, we propose to display the results obtained from the calibration of a hybrid stereo-vision system.

* **Camera parameters:** `calibrated_cameras_data.yml`

Expand Down
6 changes: 6 additions & 0 deletions apps/calibrate/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
set(SOURCES
src/calibrate.cpp
)

add_executable(calibrate ${SOURCES})
target_link_libraries(calibrate -L/usr/local/lib ${OpenCV_LIBS} ${CERES_LIBRARIES} Boost::log Boost::system Boost::filesystem McCalib)
12 changes: 2 additions & 10 deletions src/main_calibrate.cpp → apps/calibrate/src/calibrate.cpp
Original file line number Diff line number Diff line change
@@ -1,21 +1,13 @@
#include <chrono>
#include <iomanip>
#include <opencv2/aruco/charuco.hpp>
#include <opencv2/opencv.hpp>
#include <stdio.h>

#include "Board.hpp"
#include "BoardObs.hpp"
#include "Calibration.hpp"
#include "Camera.hpp"
#include "CameraObs.hpp"
#include "Frame.hpp"

#include "McCalib.hpp"
#include "logger.h"

void runCalibrationWorkflow(std::string config_path) {
// Instantiate the calibration and initialize the parameters
Calibration Calib(config_path);
McCalib::Calibration Calib(config_path);
Calib.boardExtraction();
LOG_INFO << "Board extraction done!";

Expand Down
6 changes: 6 additions & 0 deletions apps/create_charuco_boards/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
set(SOURCES
src/create_charuco_boards.cpp
)

add_executable(generate_charuco ${SOURCES})
target_link_libraries(generate_charuco -L/usr/local/lib ${OpenCV_LIBS} Boost::filesystem)
Original file line number Diff line number Diff line change
@@ -1,8 +1,9 @@
#include "boost/filesystem.hpp"
#include <iomanip>
#include <stdio.h>

#include "boost/filesystem.hpp"
#include <opencv2/aruco/charuco.hpp>
#include <opencv2/opencv.hpp>
#include <stdio.h>

int main(int argc, char *argv[]) {

Expand Down
12 changes: 5 additions & 7 deletions tests/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,10 +1,8 @@
find_package (Boost REQUIRED COMPONENTS unit_test_framework log_setup log filesystem REQUIRED)

include_directories (${Boost_INCLUDE_DIRS} ${PROJECT_SOURCE_DIR}/src)
set(SOURCES
main.cpp test_graph.cpp test_calibration.cpp simple_unit_tests_example.cpp
)

file(GLOB MC_CALIB_SRC CONFIGURE_DEPENDS ${PROJECT_SOURCE_DIR}/src/*.cpp ${PROJECT_SOURCE_DIR}/src/*.hpp ${PROJECT_SOURCE_DIR}/src/*.h)
list(REMOVE_ITEM MC_CALIB_SRC ${PROJECT_SOURCE_DIR}/src/main_calibrate.cpp ${PROJECT_SOURCE_DIR}/src/main_create_charuco.cpp)

add_executable (boost_tests_run main.cpp test_graph.cpp test_calibration.cpp ${MC_CALIB_SRC})

target_link_libraries (boost_tests_run ${OpenCV_LIBS} ${CERES_LIBRARIES} ${Boost_LIBRARIES} -lpthread -lboost_log_setup -lboost_log -lboost_unit_test_framework)
add_executable(boost_tests_run ${SOURCES})
target_link_libraries(boost_tests_run ${OpenCV_LIBS} ${CERES_LIBRARIES} ${Boost_LIBRARIES} -lpthread -lboost_log_setup -lboost_log -lboost_unit_test_framework McCalib)
5 changes: 2 additions & 3 deletions tests/simple_unit_tests_example.cpp
100755 → 100644
Original file line number Diff line number Diff line change
@@ -1,10 +1,9 @@
#define BOOST_TEST_DYN_LINK

#include <boost/test/unit_test.hpp>

#include "opencv2/opencv.hpp"
#include <boost/test/unit_test.hpp>

#include <../src/geometrytools.hpp>
#include <geometrytools.hpp>

BOOST_AUTO_TEST_SUITE(CheckGeometryTools)

Expand Down
17 changes: 6 additions & 11 deletions tests/test_calibration.cpp
Original file line number Diff line number Diff line change
@@ -1,17 +1,12 @@
#include <boost/test/unit_test.hpp>

#include <iomanip>
#include <math.h>
#include <stdio.h>

#include <boost/test/unit_test.hpp>
#include <opencv2/aruco/charuco.hpp>
#include <opencv2/opencv.hpp>
#include <stdio.h>

#include <../src/Board.hpp>
#include <../src/BoardObs.hpp>
#include <../src/Calibration.hpp>
#include <../src/Camera.hpp>
#include <../src/CameraObs.hpp>
#include <../src/Frame.hpp>
#include <McCalib.hpp>

#define PI 3.14159265

Expand All @@ -32,7 +27,7 @@ double getRotationError(cv::Mat a, cv::Mat b) {
return rot_error;
}

void calibrate(Calibration &Calib) {
void calibrate(McCalib::Calibration &Calib) {
// calibrate
Calib.boardExtraction();
Calib.initIntrinsic();
Expand All @@ -57,7 +52,7 @@ void calibrate(Calibration &Calib) {
}

void calibrateAndCheckGt(std::string config_path, std::string gt_path) {
Calibration Calib(config_path);
McCalib::Calibration Calib(config_path);
calibrate(Calib);

// read ground truth
Expand Down
2 changes: 1 addition & 1 deletion tests/test_graph.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#include <boost/test/unit_test.hpp>

#include <../src/Graph.hpp>
#include <Graph.hpp>

BOOST_AUTO_TEST_SUITE(CheckGraph)

Expand Down

0 comments on commit 5b3638d

Please sign in to comment.