forked from PJLab-ADG/SensorsCalibration
-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
- Loading branch information
yanguohang
committed
May 26, 2023
1 parent
ea3ecb6
commit 7fa0709
Showing
75 changed files
with
6,092 additions
and
0 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,11 @@ | ||
# surround-camera_calib | ||
surround-camera_calib is a calibration toolbox for surround view cameras or surround view fisheye cameras, which contains four tools, as shown in the table below. For more calibration codes, please refer to the link <a href="https://github.com/PJLab-ADG/SensorsCalibration" title="SensorsCalibration">SensorsCalibration</a> | ||
<!-- CITATION --> | ||
|
||
| calibration param |calibration type| calibration method | mannual calibration | auto calibration | usage documentation | | ||
| :--------------: |:--------------:| :------------: | :--------------: | :------------: | :------------: | | ||
| surround_cameras (fisheye) | extrinsic | target-less | ✔ | |[manual_calib](manual_calib/README.md)| | ||
| surround_cameras (fisheye) | extrinsic | target-less | | ✔ |[auto_calib_fisheye](auto_calib_fisheye/README.md)| | ||
| surround_cameras | extrinsic | target-less | | ✔ |[auto_calib](auto_calib/README.md)| | ||
| surround_cameras | extrinsic | target | | ✔ |[auto_calib_target](auto_calib_target/README.md)| | ||
|
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,22 @@ | ||
cmake_minimum_required(VERSION 2.8) | ||
project(online_Calibration) | ||
set(CMAKE_CXX_FLAGS "-std=c++17 -g -Wall") | ||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++17 -pthread") | ||
SET(CMAKE_BUILD_TYPE "Release") | ||
|
||
include_directories("/usr/include/eigen3") | ||
find_package(OpenCV REQUIRED ) | ||
|
||
include_directories(${OpenCV_INCLUDE_DIRS}) | ||
link_directories(${OpenCV_INSTALL_PATH}/lib) | ||
include_directories(${PROJECT_SOURCE_DIR}/include) | ||
include_directories(${PROJECT_SOURCE_DIR}/src) | ||
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${PROJECT_SOURCE_DIR}/bin) | ||
|
||
file(GLOB_RECURSE PARSER_PATH src/*.cpp) | ||
add_library(${PROJECT_NAME} STATIC ${PARSER_PATH}) | ||
target_link_libraries(${PROJECT_NAME} ${OpenCV_LIBS}) | ||
|
||
add_executable(run_AVM_Calibration src/calibration.cpp) | ||
target_link_libraries(run_AVM_Calibration ${PROJECT_NAME}) | ||
|
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,20 @@ | ||
# auto_calib | ||
This is an auto-calibration tool based on surround-view cameras. | ||
|
||
## Compile | ||
```shell | ||
# mkdir build | ||
mkdir -p build && cd build | ||
# build | ||
cmake .. && make | ||
``` | ||
## Run the test sample: | ||
The executable file is under the bin folder. | ||
``` | ||
cd ~./auto_calib/ | ||
./bin/run_AVM_Calibration | ||
``` | ||
Before calibration (the calibration board here only provides some texture information.) | ||
<img src="./before_all_calib.png" width="100%" height="100%" alt="Calibration result" div align=center /> | ||
After calibration | ||
<img src="./after_all_calib.png" width="100%" height="100%" alt="Calibration result" div align=center /> |
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,220 @@ | ||
#ifndef OPTIMIZER_H_ | ||
#define OPTIMIZER_H_ | ||
|
||
#include <Eigen/Dense> | ||
#include <mutex> | ||
#include <opencv2/highgui/highgui.hpp> | ||
#include <opencv2/imgproc/imgproc.hpp> | ||
#include <opencv2/opencv.hpp> | ||
|
||
using namespace cv; | ||
using namespace std; | ||
|
||
class Optimizer { | ||
private: | ||
mutable std::mutex mutexfront; | ||
mutable std::mutex mutexleft; | ||
mutable std::mutex mutexright; | ||
mutable std::mutex mutexbehind; | ||
mutable std::mutex mutexval; | ||
|
||
public: | ||
// data set index | ||
string data_index; | ||
|
||
// prefix | ||
string prefix; | ||
|
||
// camera_model | ||
int camera_model; | ||
|
||
// which camera fixed | ||
string fixed; | ||
|
||
// if add coarse search(1st search) | ||
int coarse_flag; | ||
|
||
// bev rows、cols | ||
int brows; | ||
int bcols; | ||
|
||
// SVS cameras intrinsic-T | ||
Eigen::Matrix3d intrinsic_front; | ||
Eigen::Matrix3d intrinsic_left; | ||
Eigen::Matrix3d intrinsic_behind; | ||
Eigen::Matrix3d intrinsic_right; | ||
|
||
// K_G | ||
Eigen::Matrix3d KG; | ||
|
||
// initial SVS cameras extrinsics-T(SVS cameras->BEV) | ||
Eigen::Matrix4d extrinsic_front; | ||
Eigen::Matrix4d extrinsic_left; | ||
Eigen::Matrix4d extrinsic_behind; | ||
Eigen::Matrix4d extrinsic_right; | ||
|
||
// SVS cameras extrinsics-T after optimization | ||
Eigen::Matrix4d extrinsic_front_opt; | ||
Eigen::Matrix4d extrinsic_left_opt; | ||
Eigen::Matrix4d extrinsic_behind_opt; | ||
Eigen::Matrix4d extrinsic_right_opt; | ||
|
||
// distortion papameters | ||
vector<double> distortion_params_front; | ||
vector<double> distortion_params_left; | ||
vector<double> distortion_params_behind; | ||
vector<double> distortion_params_right; | ||
|
||
// SVS cameras height | ||
double hf, hl, hb, hr; | ||
|
||
// tail size | ||
int sizef, sizel, sizeb, sizer; | ||
|
||
// SVS luminosity loss after optimization | ||
double cur_front_loss; | ||
double cur_left_loss; | ||
double cur_right_loss; | ||
double cur_behind_loss; | ||
|
||
// initial SVS luminosity loss | ||
double max_front_loss; | ||
double max_left_loss; | ||
double max_right_loss; | ||
double max_behind_loss; | ||
|
||
// bev texture pixel | ||
Mat pG_fl; | ||
Mat pG_fr; | ||
Mat pG_bl; | ||
Mat pG_br; | ||
|
||
// bev texture project to camera coordinate | ||
Mat PG_fl; | ||
Mat PG_fr; | ||
Mat PG_bl; | ||
Mat PG_br; | ||
|
||
// SVS gray images | ||
Mat imgf_gray; | ||
Mat imgl_gray; | ||
Mat imgb_gray; | ||
Mat imgr_gray; | ||
|
||
// SVS rgb images | ||
Mat imgf_rgb; | ||
Mat imgl_rgb; | ||
Mat imgb_rgb; | ||
Mat imgr_rgb; | ||
|
||
// front camera generated BEV image's texture 2d pixels | ||
vector<Point> fl_pixels_texture; | ||
vector<Point> fr_pixels_texture; | ||
vector<Point> bl_pixels_texture; | ||
vector<Point> br_pixels_texture; | ||
|
||
// euler angles(3) and t parameters(3) to recover precise SVS cameras | ||
// extrinsics | ||
vector<vector<double>> bestVal_; //(3*6) | ||
|
||
// SVS generated BEV gray images | ||
Mat imgf_bev; // initially | ||
Mat imgl_bev; | ||
Mat imgr_bev; | ||
Mat imgb_bev; | ||
|
||
// SVS generated BEV rgb images | ||
Mat imgf_bev_rgb; // initially | ||
Mat imgl_bev_rgb; | ||
Mat imgr_bev_rgb; | ||
Mat imgb_bev_rgb; | ||
|
||
// ncoef-commonView mean luminorsity ratio | ||
double ncoef_fl, ncoef_fr, ncoef_bl, ncoef_br; | ||
|
||
// Optimizer(); | ||
Optimizer(const Mat *imgf, const Mat *imgl, const Mat *imgb, const Mat *imgr, | ||
int camera_model_index, int rows, int cols, string first_order, | ||
int flag, string data_set); | ||
~Optimizer(); | ||
void initializeK(); | ||
void initializeD(); | ||
void initializePose(); | ||
void initializeKG(); | ||
void initializeHeight(); | ||
void initializetailsize(); | ||
Mat tail(Mat img, string index); | ||
void Calibrate_left(int search_count, double roll_ep0, double roll_ep1, | ||
double pitch_ep0, double pitch_ep1, double yaw_ep0, | ||
double yaw_ep1, double t0_ep0, double t0_ep1, | ||
double t1_ep0, double t1_ep1, double t2_ep0, | ||
double t2_ep1); | ||
void Calibrate_right(int search_count, double roll_ep0, double roll_ep1, | ||
double pitch_ep0, double pitch_ep1, double yaw_ep0, | ||
double yaw_ep1, double t0_ep0, double t0_ep1, | ||
double t1_ep0, double t1_ep1, double t2_ep0, | ||
double t2_ep1); | ||
void Calibrate_behind(int search_count, double roll_ep0, double roll_ep1, | ||
double pitch_ep0, double pitch_ep1, double yaw_ep0, | ||
double yaw_ep1, double t0_ep0, double t0_ep1, | ||
double t1_ep0, double t1_ep1, double t2_ep0, | ||
double t2_ep1); | ||
void Calibrate_front(int search_count, double roll_ep0, double roll_ep1, | ||
double pitch_ep0, double pitch_ep1, double yaw_ep0, | ||
double yaw_ep1, double t0_ep0, double t0_ep1, | ||
double t1_ep0, double t1_ep1, double t2_ep0, | ||
double t2_ep1); | ||
void fine_Calibrate_right(int search_count, double roll_ep0, double roll_ep1, | ||
double pitch_ep0, double pitch_ep1, double yaw_ep0, | ||
double yaw_ep1, double t0_ep0, double t0_ep1, | ||
double t1_ep0, double t1_ep1, double t2_ep0, | ||
double t2_ep1); | ||
void fine_Calibrate_left(int search_count, double roll_ep0, double roll_ep1, | ||
double pitch_ep0, double pitch_ep1, double yaw_ep0, | ||
double yaw_ep1, double t0_ep0, double t0_ep1, | ||
double t1_ep0, double t1_ep1, double t2_ep0, | ||
double t2_ep1); | ||
void fine_Calibrate_behind(int search_count, double roll_ep0, double roll_ep1, | ||
double pitch_ep0, double pitch_ep1, double yaw_ep0, | ||
double yaw_ep1, double t0_ep0, double t0_ep1, | ||
double t1_ep0, double t1_ep1, double t2_ep0, | ||
double t2_ep1); | ||
void fine_Calibrate_front(int search_count, double roll_ep0, double roll_ep1, | ||
double pitch_ep0, double pitch_ep1, double yaw_ep0, | ||
double yaw_ep1, double t0_ep0, double t0_ep1, | ||
double t1_ep0, double t1_ep1, double t2_ep0, | ||
double t2_ep1); | ||
double CostFunction(const vector<double> var, string idx); | ||
double fine_CostFunction(const vector<double> var, string idx); | ||
void SaveOptResult(const string img_name); | ||
void show(string idx, string filename); | ||
cv::Mat eigen2mat(Eigen::MatrixXd A); | ||
Mat gray_gamma(Mat img); | ||
void world2cam(double point2D[2], double point3D[3], Eigen::Matrix3d K, | ||
vector<double> D); | ||
void distortPoints(cv::Mat &P_GC1, cv::Mat &p_GC, Eigen::Matrix3d &K_C); | ||
void distortPointsOcam(cv::Mat &P_GC1, cv::Mat &p_GC, Eigen::Matrix3d &K_C, | ||
vector<double> &D_C); | ||
void random_search_params(int search_count, double roll_ep0, double roll_ep1, | ||
double pitch_ep0, double pitch_ep1, double yaw_ep0, | ||
double yaw_ep1, double t0_ep0, double t0_ep1, | ||
double t1_ep0, double t1_ep1, double t2_ep0, | ||
double t2_ep1, string idx); | ||
void fine_random_search_params(int search_count, double roll_ep0, | ||
double roll_ep1, double pitch_ep0, | ||
double pitch_ep1, double yaw_ep0, | ||
double yaw_ep1, double t0_ep0, double t0_ep1, | ||
double t1_ep0, double t1_ep1, double t2_ep0, | ||
double t2_ep1, string idx); | ||
|
||
Mat generate_surround_view(Mat img_GF, Mat img_GL, Mat img_GB, Mat img_GR); | ||
vector<Point> readfromcsv(string filename); | ||
Mat project_on_ground(cv::Mat img, Eigen::Matrix4d T_CG, Eigen::Matrix3d K_C, | ||
vector<double> D_C, Eigen::Matrix3d K_G, int rows, | ||
int cols, float height); | ||
double back_camera_and_compute_loss(Mat img1, Mat img2, Eigen::Matrix4d T, | ||
string idx); | ||
double getPixelValue(Mat *image, float x, float y); | ||
}; | ||
|
||
#endif // OPTIMIZER_H_ |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,53 @@ | ||
#include <Eigen/Core> | ||
#include <Eigen/Dense> | ||
#include <glog/logging.h> | ||
#include <iostream> | ||
#include <math.h> | ||
#include <opencv2/core/eigen.hpp> | ||
#include <opencv2/features2d/features2d.hpp> | ||
#include <opencv2/opencv.hpp> | ||
#include <random> | ||
#include <stdlib.h> | ||
#include <time.h> | ||
#include <vector> | ||
using namespace std; | ||
using namespace cv; | ||
using namespace Eigen; | ||
|
||
class extractor { | ||
public: | ||
Mat img1_bev; | ||
Mat img2_bev; | ||
|
||
Mat intrinsic1; | ||
Mat intrinsic2; | ||
|
||
Mat bin_of_imgs; | ||
Mat bev_of_imgs; | ||
|
||
int edge_flag; // if filter edge | ||
|
||
int exposure_flag; // if add exposure solution | ||
|
||
double ncoef; // exposure coefficients | ||
|
||
vector<vector<Point>> contours; | ||
|
||
Eigen::Matrix4d extrinsic1; | ||
Eigen::Matrix4d extrinsic2; | ||
|
||
extractor(Mat img1_bev, Mat img2_bev, int edge_flag, int exposure_flag); | ||
extractor(Mat img1_bev, Mat img2_bev, Mat intrinsic1, Mat intrinsic2, | ||
Eigen::Matrix4d extrinsic1, Eigen::Matrix4d extrinsic2); | ||
~extractor(); | ||
void Binarization(); | ||
void writetocsv(string filename, vector<Point> vec); | ||
void findcontours(); | ||
std::vector<std::vector<cv::Point>> | ||
fillContour(const std::vector<std::vector<cv::Point>> &_contours); | ||
vector<cv::Point> extrac_textures_and_save(string pic_filename, | ||
string csv_filename, string idx, | ||
double size); | ||
static bool cmpx(Point p1, Point p2) { return p1.x < p2.x; }; | ||
static bool cmpy(Point p1, Point p2) { return p1.y < p2.y; }; | ||
}; |
Oops, something went wrong.