提交 7a4fb5a2 编写于 作者: G gineshidalgo99

Calibration: Improved and added BA steps to doc

上级 063f84e9
......@@ -37,15 +37,12 @@
## Latest Features
- Dec 2018: [**Foot dataset and new paper released**](https://cmu-perceptual-computing-lab.github.io/foot_keypoint_dataset)!
- Dec 2018: [**Foot dataset**](https://cmu-perceptual-computing-lab.github.io/foot_keypoint_dataset) [**and new paper released**](https://arxiv.org/abs/1812.08008)!
- Sep 2018: [**Experimental single-person tracker**](doc/quick_start.md#tracking) for further speed up or visual smoothing!
- Jun 2018: [**Combined body-foot model released! 40% faster and 5% more accurate**](doc/installation.md)!
- Jun 2018: [**Python API**](doc/modules/python_module.md) released!
- Jun 2018: [**OpenCL/AMD graphic card version**](doc/installation.md) released!
- Jun 2018: [**Calibration toolbox**](doc/modules/calibration_module.md) released!
- Jun 2018: [**Mac OSX version (CPU)**](doc/installation.md) released!
- Mar 2018: [**CPU version**](doc/installation.md#cpu-version)!
- Mar 2018: [**3-D keypoint reconstruction module**](doc/modules/3d_reconstruction_module.md) (from multiple camera views)!
For further details, check [all released features](doc/released_features.md) and [release notes](doc/release_notes.md).
......@@ -164,7 +161,7 @@ Just comment on GitHub or make a pull request and we will answer as soon as poss
## Authors and Contributors
OpenPose is authored by [Gines Hidalgo](https://www.gineshidalgo.com/), [Zhe Cao](http://www.andrew.cmu.edu/user/zhecao), [Tomas Simon](http://www.cs.cmu.edu/~tsimon/), [Shih-En Wei](https://scholar.google.com/citations?user=sFQD3k4AAAAJ&hl=en), [Hanbyul Joo](http://www.cs.cmu.edu/~hanbyulj/), and [Yaser Sheikh](http://www.cs.cmu.edu/~yaser/). Currently, it is being maintained by [Gines Hidalgo](https://www.gineshidalgo.com/) and [Yaadhav Raaj](https://www.linkedin.com/in/yaadhavraaj). The [original CVPR 2017 repo](https://github.com/ZheC/Multi-Person-Pose-Estimation) includes Matlab and Python versions, as well as the training code. The body pose estimation work is based on [the original ECCV 2016 demo](https://github.com/CMU-Perceptual-Computing-Lab/caffe_rtpose).
OpenPose is authored by [Gines Hidalgo](https://www.gineshidalgo.com/), [Zhe Cao](http://www.andrew.cmu.edu/user/zhecao), [Tomas Simon](http://www.cs.cmu.edu/~tsimon), [Shih-En Wei](https://scholar.google.com/citations?user=sFQD3k4AAAAJ&hl=en), [Hanbyul Joo](http://www.cs.cmu.edu/~hanbyulj), and [Yaser Sheikh](http://www.cs.cmu.edu/~yaser). Currently, it is being maintained by [Gines Hidalgo](https://www.gineshidalgo.com/) and [Yaadhav Raaj](https://www.linkedin.com/in/yaadhavraaj). The [original CVPR 2017 repo](https://github.com/ZheC/Multi-Person-Pose-Estimation) includes Matlab and Python versions, as well as the training code. The body pose estimation work is based on [the original ECCV 2016 demo](https://github.com/CMU-Perceptual-Computing-Lab/caffe_rtpose).
In addition, OpenPose would not be possible without the [CMU Panoptic Studio dataset](http://domedb.perception.cs.cmu.edu/).
......
......@@ -13,6 +13,6 @@ We would also like to thank the following people who have highly contributed to
1. [Yaadhav Raaj](https://www.linkedin.com/in/yaadhavraaj): OpenPose maintainer, CPU version, OpenCL version, Mac version, Python API, and person tracker.
2. [Bikramjot Hanzra](https://www.linkedin.com/in/bikz05): Former OpenPose maintainer, CMake (Ubuntu and Windows) version, and Travis Build.
3. [Donglai Xiang](https://xiangdonglai.github.io/): Camera calibration toolbox improvement, including the implementation of its bundle adjustment algorithm.
4. [Luis Fernando Fraga](https://github.com/fragalfernando/): Implementation of Lukas-Kanade algorith and person ID extractor.
3. [Donglai Xiang](https://xiangdonglai.github.io): Camera calibration toolbox improvement, including the implementation of its bundle adjustment algorithm.
4. [Luis Fernando Fraga](https://github.com/fragalfernando): Implementation of Lukas-Kanade algorith and person ID extractor.
5. [Helen Medina](https://github.com/helen-medina): Initial Windows version.
......@@ -104,7 +104,7 @@ Examples:
### Step 2 - Extrinsic Parameter Calibration
1. **VERY IMPORTANT NOTE**: If you want to re-run the extrinsic parameter calibration over the same intrinsic XML files (e.g., if you move the camera location, but you know the instrinsics are the same), you must manually re-set to `1 0 0 0 0 1 0 0 0 0 1 0` the camera matrix of each XML file.
1. **VERY IMPORTANT NOTE**: If you want to re-run the extrinsic parameter calibration over the same intrinsic XML files (e.g., if you move the camera location, but you know the instrinsics are the same), you must manually re-set to `1 0 0 0 0 1 0 0 0 0 1 0` the camera matrix of each XML file that will be used for `--combine_cam0_extrinsics`.
2. After intrinsics calibration, save undirtoted images for all the camera views:
```sh
./build/examples/openpose/openpose.bin --num_gpu 0 --flir_camera --write_images ~/Desktop/extrinsics
......@@ -125,7 +125,16 @@ Examples:
:: Windows
:: build\x64\Release\calibration.exe with the same flags as above
```
4. Hint to verify extrinsic calibration is successful:
4. If you use Ceres solver (`WITH_CERES` flag in CMake), you can improve the calibration results by performing an additional Bundle Adjustment refinement step on top of the previous results. We use camera 0 as the baseline for the internal computation, so try to avoid weird camera configurations in which camera 0 is completely isolated from the other cameras. Ideally, camera 0 should physically be the closest to all other cameras (i.e., the one more centered). But in practice, the accuracy improvement is almost none (as long as it is not too far from the others). To perform this bundle adjustment refinement for the example above, simply run the following line:
```
# Ubuntu and Mac
./build/examples/calibration/calibration.bin --mode 3 --grid_square_size_mm 127.0 --grid_number_inner_corners 9x6 --omit_distortion --calibration_image_dir ~/Desktop/extrinsics/ --number_cameras 4
```
```
:: Windows
:: Ceres-compatible version not implemented for Windows yet. Make a pull request if you have a working version in Windows.
```
5. Hint to verify extrinsic calibration is successful:
1. Translation vector - Global distance:
1. Manually open each one of the generated XML files from the folder indicated by the flag `--camera_parameter_path` (or the default one indicated by the `--help` flag if the former was not used).
2. The field `CameraMatrix` is a 3 x 4 matrix (you can see that the subfield `rows` in that file is 3 and `cols` is 4).
......
OpenPose Library - All Released Features
====================================
- Dec 2018: [**Foot dataset and new paper released**](https://cmu-perceptual-computing-lab.github.io/foot_keypoint_dataset)!
- Dec 2018: [**Foot dataset**](https://cmu-perceptual-computing-lab.github.io/foot_keypoint_dataset) [**and new paper released**](https://arxiv.org/abs/1812.08008)!
- Sep 2018: [**Experimental tracker**](./quick_start.md#tracking)!
- Jun 2018: [**Combined body-foot model released! 40% faster and 5% more accurate**](./installation.md)!
- Jun 2018: [**Python API**](./modules/python_module.md) released!
......
......@@ -1811,6 +1811,12 @@ namespace op
{
try
{
// Sanity check
auto normCam0Identity = cv::norm(
refinedExtrinsics[0] - cv::Mat::eye(3, 4, refinedExtrinsics[0].type()));
if (normCam0Identity > 1e-9) // std::cout prints exactly 0
error("Camera 0 should be [I, 0] for this algorithm to run. Norm cam0-[I,0] = "
+ std::to_string(normCam0Identity), __LINE__, __FUNCTION__, __FILE__);
// Prepare the camera extrinsics
Eigen::Matrix<double, 6, Eigen::Dynamic> cameraRt(6, numberCameras); // Angle axis + translation
for (auto cameraIndex = 0 ; cameraIndex < numberCameras ; cameraIndex++)
......@@ -1895,13 +1901,18 @@ namespace op
// problem.AddResidualBlock(costFunction, new ceres::HuberLoss(2.0), points3D.data() + 3 * i);
// }
// }
// Ceres verbose
ceres::Solver::Summary summary;
ceres::Solve(options, &problem, &summary);
log(summary.FullReport(), Priority::High);
// The first one should be [I | 0], but we would enforce this at the end
for (auto cameraIndex = 0 ; cameraIndex < numberCameras ; cameraIndex++)
// Sanity check
normCam0Identity = cv::norm(
refinedExtrinsics[0] - cv::Mat::eye(3, 4, refinedExtrinsics[0].type()));
if (normCam0Identity > 1e-9) // std::cout prints exactly 0
error("Camera 0 should not be modified by our implementation of bundle adjustment, notify us!"
" Norm: " + std::to_string(normCam0Identity), __LINE__, __FUNCTION__, __FILE__);
// The first one should be [I | 0] and it is not modified by our Ceres optimization
for (auto cameraIndex = 1 ; cameraIndex < numberCameras ; cameraIndex++)
{
cv::Mat extrinsics(3, 4, refinedExtrinsics[0].type());
extrinsics.at<double>(0, 3) = cameraRt.data()[6 * cameraIndex + 3];
......@@ -2044,6 +2055,27 @@ namespace op
error(e.what(), __LINE__, __FUNCTION__, __FILE__);
}
}
void cameraXAsOrigin(
std::vector<cv::Mat>& cameraExtrinsics, cv::Mat& cameraOriginInv, const cv::Mat& cameraOrigin)
{
try
{
// Extrinsics = cameraOrigin will turn into [I | 0]
// All the others are transformed accordingly by multiplying them by inv(cameraOrigin)
cameraOriginInv = cv::Mat::eye(4, 4, cameraOrigin.type());
for (auto i = 0 ; i < 3 ; i++)
for (auto j = 0 ; j < 4 ; j++)
cameraOriginInv.at<double>(i, j) = cameraOrigin.at<double>(i, j);
cameraOriginInv = cameraOriginInv.inv();
for (auto& cameraExtrinsic : cameraExtrinsics)
cameraExtrinsic = cameraExtrinsic * cameraOriginInv;
}
catch (const std::exception& e)
{
error(e.what(), __LINE__, __FUNCTION__, __FILE__);
}
}
#endif
void refineAndSaveExtrinsics(
......@@ -2084,8 +2116,14 @@ namespace op
break;
}
}
const auto cameraExtrinsics = (initialEmpty
// Camera extrinsics
log("", Priority::Low, __LINE__, __FUNCTION__, __FILE__);
auto cameraExtrinsics = (initialEmpty
? cameraParameterReader.getCameraExtrinsics() : cameraExtrinsicsInitial);
// The first one should be [I | 0]: Multiply them all by inv(camera 0 extrinsics)
cv::Mat cameraOriginInv;
cameraXAsOrigin(cameraExtrinsics, cameraOriginInv, cameraExtrinsics.at(0).clone());
// Camera intrinsics and distortion
const auto cameraIntrinsics = cameraParameterReader.getCameraIntrinsics();
const auto cameraDistortions = (
imagesAreUndistorted
......@@ -2203,22 +2241,22 @@ namespace op
refinedExtrinsics, points3D, points2DVectorsExtrinsic, BAValid, cameraIntrinsics,
numberCameras, 0.5, false);
// The first one should be [I | 0]: Multiply them all by inv(camera 0 extrinsics)
// Note: Given that camera 0 will have 0 translation, rescaling will not affect it
log("", Priority::Low, __LINE__, __FUNCTION__, __FILE__);
cv::Mat extrinsicsCam0Inv = cv::Mat::eye(4, 4, refinedExtrinsics[0].type());
for (auto i = 0 ; i < 3 ; i++)
for (auto j = 0 ; j < 3 ; j++)
extrinsicsCam0Inv.at<double>(i, j) = refinedExtrinsics[0].at<double>(i, j);
extrinsicsCam0Inv = extrinsicsCam0Inv.inv();
for (auto& refinedExtrinsic : refinedExtrinsics)
refinedExtrinsic = refinedExtrinsic * extrinsicsCam0Inv;
// Rescale the 3D points and translation based on the grid size
rescaleExtrinsicsAndPoints3D(
refinedExtrinsics, points3D, points2DVectorsExtrinsic, BAValid, cameraIntrinsics, numberCameras,
numberCorners, gridSquareSizeMm, gridInnerCorners);
// Revert back to refinedExtrinsics[0] = cameraExtrinsics[0] (rather than [I,0])
// Note: Given that inv([R,t;0,1]) is another [R',t';0,1], scaling is maintained
log("", Priority::Low, __LINE__, __FUNCTION__, __FILE__);
cv::Mat cameraOriginInv2;
cameraXAsOrigin(refinedExtrinsics, cameraOriginInv2, cameraOriginInv);
// Sanity check
auto normCam0Identity = cv::norm(refinedExtrinsics[0] - cameraExtrinsics[0]);
if (normCam0Identity > 1e-9) // std::cout prints exactly 0
error("Unexpected error, notify us. Norm difference: "
+ std::to_string(normCam0Identity), __LINE__, __FUNCTION__, __FILE__);
// Final projection matrix
log("", Priority::Low, __LINE__, __FUNCTION__, __FILE__);
log("\nFinal projection matrix w.r.t. global origin (meters):", Priority::High);
......
......@@ -96,6 +96,14 @@ ifneq ($(WITH_CERES), 0)
# Ceres
LIBRARIES += ceres
INCLUDE_DIRS += $(EIGEN_DIR)
# If Ceres was built with Suitesparse:
LIBRARIES += lapack camd amd ccolamd colamd cholmod
# If Ceres was built with CXSparse:
LIBRARIES += cxsparse
# If Ceres was built with OpenMP:
LIBRARIES += pthread gomp m
CXXFLAGS += -fopenmp
LINKFLAGS += -fopenmp
endif
# Eigen support
WITH_EIGEN ?= 0
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册