提交 66b02dbd 编写于 作者: G gineshidalgo99

Calibration mode 3 improved

上级 cc078846
......@@ -124,7 +124,7 @@ The instructions in this section describe the steps to build OpenPose using CMak
- [Caffe dependencies](http://posefs1.perception.cs.cmu.edu/OpenPose/3rdparty/windows/caffe3rdparty_2017_07_14.zip): Unzip as `3rdparty/windows/caffe3rdparty/`.
- [OpenCV 3.1](http://posefs1.perception.cs.cmu.edu/OpenPose/3rdparty/windows/opencv_310.zip): Unzip as `3rdparty/windows/opencv/`.
6. Mac - **Caffe, OpenCV, and Caffe prerequisites**:
- Install deps by running `sudo bash 3rdparty/osx/install_deps.sh` on your terminal.
- Install deps by running `bash 3rdparty/osx/install_deps.sh` on your terminal.
- Current OSX has only been tested with the CPU Version, and hence must be compiled with the `-DGPU_MODE=CPU_ONLY` flag.
7. **Eigen prerequisite**:
- Note: This step is optional, only required for some specific extra functionality, such as extrinsic camera calibration.
......
......@@ -24,7 +24,7 @@ DEFINE_int32(logging_level, 3, "The logging level. Inte
" 255 will not output any. Current OpenPose library messages are in the range 0-4: 1 for"
" low priority messages and 4 for important ones.");
// Calibration
DEFINE_int32(mode, 1, "Select 1 for intrinsic camera parameter calibration, 2 for extrinsic ones.");
DEFINE_int32(mode, 1, "Select 1 for intrinsic camera parameter calibration, 2 for extrinsic calibration.");
DEFINE_string(calibration_image_dir, "images/intrinsics/", "Directory where the images for camera parameter calibration are placed.");
DEFINE_double(grid_square_size_mm, 127.0, "Chessboard square length (in millimeters).");
DEFINE_string(grid_number_inner_corners,"9x6", "Number of inner corners in width and height, i.e., number of total squares in width"
......@@ -95,7 +95,7 @@ int openPoseDemo()
op::log("Extrinsic calibration completed!", op::Priority::High);
}
// // Calibration - Extrinsics for Visual SFM
// // Calibration - Extrinsics Refinement with Visual SFM
// else if (FLAGS_mode == 3)
// {
// op::log("Running calibration (intrinsic parameters)...", op::Priority::High);
......@@ -105,7 +105,7 @@ int openPoseDemo()
// // const auto saveImagesWithCorners = true;
// // Run camera calibration code
// op::estimateAndSaveSiftFile(gridInnerCorners,
// op::formatAsDirectory(FLAGS_camera_parameter_folder),
// op::formatAsDirectory(FLAGS_calibration_image_dir),
// FLAGS_number_cameras,
// saveImagesWithCorners);
// op::log("Intrinsic calibration completed!", op::Priority::High);
......
......@@ -306,6 +306,7 @@ namespace op
}
}
// 3D reconstruction
auto reprojectionErrorTotal = 0.0;
keypoints3D.reset({ 1, numberBodyParts, 4 }, 0);
if (!xyPoints.empty())
{
......@@ -314,10 +315,13 @@ namespace op
for (auto i = 0u; i < xyPoints.size(); i++)
{
cv::Mat reconstructedPoint;
triangulateWithOptimization(reconstructedPoint, cameraMatricesPerPoint[i], xyPoints[i]);
reprojectionErrorTotal += triangulateWithOptimization(reconstructedPoint,
cameraMatricesPerPoint[i],
xyPoints[i]);
xyzPoints[i] = cv::Point3d{reconstructedPoint.at<double>(0), reconstructedPoint.at<double>(1),
reconstructedPoint.at<double>(2)};
}
reprojectionErrorTotal /= xyPoints.size();
// 3D points to pose
// OpenCV alternative:
......@@ -339,6 +343,7 @@ namespace op
}
}
}
// log("Reprojection error: " + std::to_string(reprojectionErrorTotal)); // To debug reprojection error
}
return keypoints3D;
}
......
#include <fstream>
#include <numeric> // std::accumulate
#include <thread>
#include <opencv2/core/core.hpp>
#ifdef WITH_EIGEN
#include <Eigen/Dense>
......@@ -732,6 +733,127 @@ namespace op
log("Cannot write on " + fileName, Priority::High);
}
std::string getFileNameFromCameraIndex(const int cameraIndex)
{
try
{
// Security checks
if (cameraIndex >= 100)
error("Only implemented for up to 99 cameras.", __LINE__, __FUNCTION__, __FILE__);
// Return result
return (cameraIndex < 10 ? "00_0" : "00_") + std::to_string(cameraIndex);
}
catch (const std::exception& e)
{
error(e.what(), __LINE__, __FUNCTION__, __FILE__);
return "";
}
}
void estimateAndSaveSiftFileSubThread(std::vector<cv::Point2f>* points2DExtrinsicPtr,
std::vector<unsigned int>* matchIndexesCameraPtr,
const int cameraIndex,
const int numberCameras,
const int numberCorners,
const unsigned int numberViews,
const bool saveImagesWithCorners,
const std::string& imagesFolder,
const cv::Size& gridInnerCornersCvSize,
const cv::Size& imageSize,
const std::vector<std::pair<cv::Mat, std::string>>& imageAndPaths)
{
try
{
// Security checks
if (points2DExtrinsicPtr == nullptr || matchIndexesCameraPtr == nullptr)
error("Make sure than points2DExtrinsicPtr != nullptr && matchIndexesCameraPtr != nullptr.",
__LINE__, __FUNCTION__, __FILE__);
std::vector<cv::Point2f>& points2DExtrinsic = *points2DExtrinsicPtr;
std::vector<unsigned int>& matchIndexesCamera = *matchIndexesCameraPtr;
std::vector<cv::Mat> imagesWithCorners;
for (auto viewIndex = 0u ; viewIndex < numberViews ; viewIndex++)
{
// Get right image
const auto& imageAndPath = imageAndPaths.at(viewIndex * numberCameras + cameraIndex);
const auto& image = imageAndPath.first;
if (viewIndex % std::max(1, int(numberViews/6)) == 0)
log("Camera " + std::to_string(cameraIndex) + " - Image view "
+ std::to_string(viewIndex+1) + "/" + std::to_string(numberViews),
Priority::High);
// Security check
if (imageSize.width != image.cols || imageSize.height != image.rows)
error("Detected images with different sizes in `" + imagesFolder + "` All images"
" must have the same resolution.", __LINE__, __FUNCTION__, __FILE__);
// Find grid corners
bool found;
std::vector<cv::Point2f> points2DVector;
std::tie(found, points2DVector) = findAccurateGridCorners(image, gridInnerCornersCvSize);
// Reorder & save 2D pixels points
if (found)
{
reorderPoints(points2DVector, gridInnerCornersCvSize, Points2DOrigin::TopLeft);
for (auto i = 0 ; i < numberCorners ; i++)
matchIndexesCamera.emplace_back(viewIndex * numberCorners + i);
}
else
{
points2DVector.clear();
points2DVector.resize(numberCorners, cv::Point2f{-1.f,-1.f});
log("Camera " + std::to_string(cameraIndex) + " - Image view "
+ std::to_string(viewIndex+1) + "/" + std::to_string(numberViews)
+ " - Chessboard not found.", Priority::High);
}
points2DExtrinsic.insert(points2DExtrinsic.end(), points2DVector.begin(), points2DVector.end());
// Show image (with chessboard corners if found)
if (saveImagesWithCorners)
{
cv::Mat imageToPlot = image.clone();
if (found)
drawGridCorners(imageToPlot, gridInnerCornersCvSize, points2DVector);
imagesWithCorners.emplace_back(imageToPlot);
}
}
// Save *.sift file for camera
// const auto fileName = getFullFilePathNoExtension(imageAndPaths.at(cameraIndex).second) + ".sift";
const auto fileName = getFileParentFolderPath(imageAndPaths.at(cameraIndex).second)
+ getFileNameFromCameraIndex(cameraIndex) + ".sift";
writeVisualSFMSiftGPU(fileName, points2DExtrinsic);
// Save images with corners
if (saveImagesWithCorners)
{
const auto folderWhereSavingImages = imagesFolder + "images_with_corners/";
// Create directory in case it did not exist
makeDirectory(folderWhereSavingImages);
const auto pathWhereSavingImages = folderWhereSavingImages + std::to_string(cameraIndex) + "_";
// Save new images
const std::string extension{".png"};
auto fileRemoved = true;
for (auto i = 0u ; i < imagesWithCorners.size() || fileRemoved; i++)
{
const auto finalPath = pathWhereSavingImages + std::to_string(i+1) + extension;
// remove leftovers/previous files
// Note: If file is not deleted before cv::imwrite, Windows considers that the file
// was "only" modified at that time, not created
fileRemoved = {remove(finalPath.c_str()) == 0};
// save images on hhd in the desired place
if (i < imagesWithCorners.size())
saveImage(imagesWithCorners.at(i), finalPath);
}
}
}
catch (const std::exception& e)
{
error(e.what(), __LINE__, __FUNCTION__, __FILE__);
}
}
......@@ -782,13 +904,16 @@ namespace op
std::cerr << "Chessboard not found in this image." << std::endl;
// Show image (with chessboard corners if found)
cv::Mat imageToPlot = image.clone();
if (found)
drawGridCorners(imageToPlot, gridInnerCornersCvSize, points2DVector);
// cv::pyrDown(imageToPlot, imageToPlot);
// cv::imshow("Image View", imageToPlot);
// cv::waitKey(delayMilliseconds);
imagesWithCorners.emplace_back(imageToPlot);
if (saveImagesWithCorners)
{
cv::Mat imageToPlot = image.clone();
if (found)
drawGridCorners(imageToPlot, gridInnerCornersCvSize, points2DVector);
// cv::pyrDown(imageToPlot, imageToPlot);
// cv::imshow("Image View", imageToPlot);
// cv::waitKey(delayMilliseconds);
imagesWithCorners.emplace_back(imageToPlot);
}
}
// Run calibration
......@@ -1083,58 +1208,27 @@ namespace op
std::vector<cv::Mat> imagesWithCorners;
const auto imageSize = imageAndPaths.at(0).first.size();
const auto numberViews = imageAndPaths.size() / numberCameras;
log("Processing cameras...", Priority::High);
std::vector<std::thread> threads;
for (auto cameraIndex = 0 ; cameraIndex < numberCameras ; cameraIndex++)
{
log("Processing camera " + std::to_string(cameraIndex) + "...", Priority::High);
auto& points2DExtrinsic = points2DVectorsExtrinsic[cameraIndex];
auto& matchIndexesCamera = matchIndexes[cameraIndex];
for (auto viewIndex = 0u ; viewIndex < numberViews ; viewIndex++)
{
// Get right image
const auto& imageAndPath = imageAndPaths.at(viewIndex * numberCameras + cameraIndex);
const auto& image = imageAndPath.first;
if (viewIndex % std::max(1, int(numberViews/10)) == 0)
log("Image view " + std::to_string(viewIndex+1) + "/" + std::to_string(numberViews),
Priority::High);
// Security check
if (imageSize.width != image.cols || imageSize.height != image.rows)
error("Detected images with different sizes in `" + imagesFolder + "` All images"
" must have the same resolution.", __LINE__, __FUNCTION__, __FILE__);
// Find grid corners
bool found;
std::vector<cv::Point2f> points2DVector;
std::tie(found, points2DVector) = findAccurateGridCorners(image, gridInnerCornersCvSize);
// Reorder & save 2D pixels points
if (found)
{
reorderPoints(points2DVector, gridInnerCornersCvSize, Points2DOrigin::TopLeft);
for (auto i = 0 ; i < numberCorners ; i++)
matchIndexesCamera.emplace_back(viewIndex * numberCorners + i);
}
else
{
points2DVector.clear();
points2DVector.resize(numberCorners, cv::Point2f{-1.f,-1.f});
log("Chessboard not found in view " + std::to_string(viewIndex)
+ ", camera " + std::to_string(cameraIndex) + ".", Priority::High);
}
points2DExtrinsic.insert(points2DExtrinsic.end(), points2DVector.begin(), points2DVector.end());
// Show image (with chessboard corners if found)
cv::Mat imageToPlot = image.clone();
if (found)
drawGridCorners(imageToPlot, gridInnerCornersCvSize, points2DVector);
imagesWithCorners.emplace_back(imageToPlot);
}
// Save *.sift file for camera
const auto fileName = getFullFilePathNoExtension(imageAndPaths.at(cameraIndex).second) + ".sift";
writeVisualSFMSiftGPU(fileName, points2DExtrinsic);
auto* points2DExtrinsic = &points2DVectorsExtrinsic[cameraIndex];
auto* matchIndexesCamera = &matchIndexes[cameraIndex];
// Threaded version
threads.emplace_back(estimateAndSaveSiftFileSubThread, points2DExtrinsic,
matchIndexesCamera, cameraIndex, numberCameras,
numberCorners, numberViews, saveImagesWithCorners, imagesFolder,
gridInnerCornersCvSize, imageSize, imageAndPaths);
// // Non-threaded version
// estimateAndSaveSiftFileSubThread(points2DExtrinsic, matchIndexesCamera, cameraIndex, numberCameras,
// numberCorners, numberViews, saveImagesWithCorners, imagesFolder,
// gridInnerCornersCvSize, imageSize, imageAndPaths);
}
// Threaded version
for (auto& thread : threads)
if (thread.joinable())
thread.join();
// Matching file
std::ofstream ofstreamMatches{getFileParentFolderPath(imageAndPaths.at(0).second) + "FeatureMatches.txt"};
for (auto cameraIndex = 0 ; cameraIndex < numberCameras ; cameraIndex++)
......@@ -1146,8 +1240,10 @@ namespace op
matchIndexes[cameraIndex2].begin(), matchIndexes[cameraIndex2].end(),
std::back_inserter(matchIndexesIntersection));
ofstreamMatches << getFileNameAndExtension(imageAndPaths.at(cameraIndex).second)
<< " " << getFileNameAndExtension(imageAndPaths.at(cameraIndex2).second)
ofstreamMatches << getFileNameFromCameraIndex(cameraIndex) << ".jpg"
<< " " << getFileNameFromCameraIndex(cameraIndex2) << ".jpg"
// ofstreamMatches << getFileNameAndExtension(imageAndPaths.at(cameraIndex).second)
// << " " << getFileNameAndExtension(imageAndPaths.at(cameraIndex2).second)
<< " " << matchIndexesIntersection.size() << "\n";
for (auto reps = 0 ; reps < 2 ; reps++)
{
......@@ -1166,28 +1262,6 @@ namespace op
for (auto i = 1 ; i < numberCameras ; i++)
if (points2DVectorsExtrinsic[i].size() != points2DVectorsExtrinsic[0].size())
error("Something went wrong. Notify us.", __LINE__, __FUNCTION__, __FILE__);
// Save images with corners
if (saveImagesWithCorners)
{
const auto folderWhereSavingImages = imagesFolder + "images_with_corners/";
// Create directory in case it did not exist
makeDirectory(folderWhereSavingImages);
// Save new images
const std::string extension{".png"};
auto fileRemoved = true;
for (auto i = 0u ; i < imagesWithCorners.size() || fileRemoved; i++)
{
const auto finalPath = folderWhereSavingImages + std::to_string(i+1) + extension;
// remove leftovers/previous files
// Note: If file is not deleted before cv::imwrite, Windows considers that the file
// was "only" modified at that time, not created
fileRemoved = {remove(finalPath.c_str()) == 0};
// save images on hhd in the desired place
if (i < imagesWithCorners.size())
saveImage(imagesWithCorners.at(i), finalPath);
}
}
}
catch (const std::exception& e)
{
......
......@@ -61,7 +61,17 @@ namespace op
|| !wrapperStructOutput.writeCocoJson.empty() || !wrapperStructOutput.writeHeatMaps.empty()
|| !wrapperStructOutput.writeCocoFootJson.empty()
);
const auto savingCvOutput = (
!wrapperStructOutput.writeImages.empty() || !wrapperStructOutput.writeVideo.empty()
);
const bool guiEnabled = (wrapperStructOutput.displayMode != DisplayMode::NoDisplay);
if (!guiEnabled && !savingCvOutput && renderOutput)
{
const auto message = "GUI is not enabled and you are not saving the output frames. You should then"
" disable rendering for a faster code. I.e., add `--render_pose 0`."
+ additionalMessage;
error(message, __LINE__, __FUNCTION__, __FILE__);
}
if (!guiEnabled && !savingSomething)
{
const auto message = "No output is selected (`--display 0`) and no results are generated (no"
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册