Commit 9011368a authored by Vadim Pisarevsky's avatar Vadim Pisarevsky

Merge pull request #266 from jiuerbujie:omnidir_camera_calib

parents cdbe3352 bf9dd72f
Custom Calibration Pattern for 3D reconstruction
================================================
1. Custom calibration pattern for 3D reconstruction
2. Omnidirectional camera calibration
3. random pattern calibration object
4. multi-camera calibration
\ No newline at end of file
/*M///////////////////////////////////////////////////////////////////////////////////////
//
// IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING.
//
// By downloading, copying, installing or using the software you agree to this license.
// If you do not agree to this license, do not download, install,
// copy or use the software.
//
//
// License Agreement
// For Open Source Computer Vision Library
//
// Copyright (C) 2015, Baisheng Lai (laibaisheng@gmail.com), Zhejiang University,
// all rights reserved.
//
// Redistribution and use in source and binary forms, with or without modification,
// are permitted provided that the following conditions are met:
//
// * Redistribution's of source code must retain the above copyright notice,
// this list of conditions and the following disclaimer.
//
// * Redistribution's in binary form must reproduce the above copyright notice,
// this list of conditions and the following disclaimer in the documentation
// and/or other materials provided with the distribution.
//
// * The name of the copyright holders may not be used to endorse or promote products
// derived from this software without specific prior written permission.
//
// This software is provided by the copyright holders and contributors "as is" and
// any express or implied warranties, including, but not limited to, the implied
// warranties of merchantability and fitness for a particular purpose are disclaimed.
// In no event shall the Intel Corporation or contributors be liable for any direct,
// indirect, incidental, special, exemplary, or consequential damages
// (including, but not limited to, procurement of substitute goods or services;
// loss of use, data, or profits; or business interruption) however caused
// and on any theory of liability, whether in contract, strict liability,
// or tort (including negligence or otherwise) arising in any way out of
// the use of this software, even if advised of the possibility of such damage.
//
//M*/
#ifndef __OPENCV_MULTICAMERACALIBRATION_HPP__
#define __OPENCV_MULTICAMERACALIBRATION_HPP__
#include "opencv2/ccalib/randpattern.hpp"
#include "opencv2/ccalib/omnidir.hpp"
#include <string>
#include <iostream>
namespace cv { namespace multicalib {
//! @addtogroup ccalib
//! @{
#define HEAD -1
#define INVALID -2
/** @brief Class for multiple camera calibration that supports pinhole camera and omnidirection camera.
For omnidirectional camera model, please refer to omnidir.hpp in ccalib module.
It first calibrate each camera individually, then a bundle adjustment like optimization is applied to
refine extrinsic parameters. So far, it only support "random" pattern for calibration,
see randomPattern.hpp in ccalib module for details.
Images that are used should be named by "cameraIdx-timestamp.*", several images with the same timestamp
means that they are the same pattern that are photographed. cameraIdx should start from 0.
For more details, please refer to paper
B. Li, L. Heng, K. Kevin and M. Pollefeys, "A Multiple-Camera System
Calibration Toolbox Using A Feature Descriptor-Based Calibration
Pattern", in IROS 2013.
*/
class CV_EXPORTS MultiCameraCalibration
{
public:
enum {
PINHOLE,
OMNIDIRECTIONAL
//FISHEYE
};
// an edge connects a camera and pattern
struct edge
{
int cameraVertex; // vertex index for camera in this edge
int photoVertex; // vertex index for pattern in this edge
int photoIndex; // photo index among photos for this camera
Mat transform; // transform from pattern to camera
edge(int cv, int pv, int pi, Mat trans)
{
cameraVertex = cv;
photoVertex = pv;
photoIndex = pi;
transform = trans;
}
};
struct vertex
{
Mat pose; // relative pose to the first camera. For camera vertex, it is the
// transform from the first camera to this camera, for pattern vertex,
// it is the transform from pattern to the first camera
int timestamp; // timestamp of photo, only available for photo vertex
vertex(Mat po, int ts)
{
pose = po;
timestamp = ts;
}
vertex()
{
pose = Mat::eye(4, 4, CV_32F);
timestamp = -1;
}
};
/* @brief Constructor
@param cameraType camera type, PINHOLE or OMNIDIRECTIONAL
@param nCameras number of cameras
@fileName filename of string list that are used for calibration, the file is generated
by imagelist_creator from OpenCv samples. The first one in the list is the pattern filename.
@patternWidth the physical width of pattern, in user defined unit.
@patternHeight the physical height of pattern, in user defined unit.
@showExtration whether show extracted features and feature filtering.
@nMiniMatches minimal number of matched features for a frame.
@flags Calibration flags
@criteria optimization stopping criteria.
@detector feature detector that detect feature points in pattern and images.
@descriptor feature descriptor.
@matcher feature matcher.
*/
MultiCameraCalibration(int cameraType, int nCameras, const std::string& fileName, float patternWidth,
float patternHeight, int verbose = 0, int showExtration = 0, int nMiniMatches = 20, int flags = 0,
TermCriteria criteria = TermCriteria(TermCriteria::COUNT + TermCriteria::EPS, 200, 1e-7),
Ptr<FeatureDetector> detector = AKAZE::create(AKAZE::DESCRIPTOR_MLDB, 0, 3, 0.006f),
Ptr<DescriptorExtractor> descriptor = AKAZE::create(AKAZE::DESCRIPTOR_MLDB,0, 3, 0.006f),
Ptr<DescriptorMatcher> matcher = DescriptorMatcher::create("BruteForce-L1"));
/* @brief load images
*/
void loadImages();
/* @brief initialize multiple camera calibration. It calibrates each camera individually.
*/
void initialize();
/* @brief optimization extrinsic parameters
*/
double optimizeExtrinsics();
/* @brief run multi-camera camera calibration, it runs loadImage(), initialize() and optimizeExtrinsics()
*/
double run();
/* @brief write camera parameters to file.
*/
void writeParameters(const std::string& filename);
private:
std::vector<std::string> readStringList();
int getPhotoVertex(int timestamp);
void graphTraverse(const Mat& G, int begin, std::vector<int>& order, std::vector<int>& pre);
void findRowNonZero(const Mat& row, Mat& idx);
void computeJacobianExtrinsic(const Mat& extrinsicParams, Mat& JTJ_inv, Mat& JTE);
void computePhotoCameraJacobian(const Mat& rvecPhoto, const Mat& tvecPhoto, const Mat& rvecCamera,
const Mat& tvecCamera, Mat& rvecTran, Mat& tvecTran, const Mat& objectPoints, const Mat& imagePoints, const Mat& K,
const Mat& distort, const Mat& xi, Mat& jacobianPhoto, Mat& jacobianCamera, Mat& E);
void compose_motion(InputArray _om1, InputArray _T1, InputArray _om2, InputArray _T2, Mat& om3, Mat& T3, Mat& dom3dom1,
Mat& dom3dT1, Mat& dom3dom2, Mat& dom3dT2, Mat& dT3dom1, Mat& dT3dT1, Mat& dT3dom2, Mat& dT3dT2);
void JRodriguesMatlab(const Mat& src, Mat& dst);
void dAB(InputArray A, InputArray B, OutputArray dABdA, OutputArray dABdB);
double computeProjectError(Mat& parameters);
void vector2parameters(const Mat& parameters, std::vector<Vec3f>& rvecVertex, std::vector<Vec3f>& tvecVertexs);
void parameters2vector(const std::vector<Vec3f>& rvecVertex, const std::vector<Vec3f>& tvecVertex, Mat& parameters);
int _camType; //PINHOLE, FISHEYE or OMNIDIRECTIONAL
int _nCamera;
int _nMiniMatches;
int _flags;
int _verbose;
double _error;
float _patternWidth, _patternHeight;
TermCriteria _criteria;
std::string _filename;
int _showExtraction;
Ptr<FeatureDetector> _detector;
Ptr<DescriptorExtractor> _descriptor;
Ptr<DescriptorMatcher> _matcher;
std::vector<edge> _edgeList;
std::vector<vertex> _vertexList;
std::vector<std::vector<cv::Mat> > _objectPointsForEachCamera;
std::vector<std::vector<cv::Mat> > _imagePointsForEachCamera;
std::vector<cv::Mat> _cameraMatrix;
std::vector<cv::Mat> _distortCoeffs;
std::vector<cv::Mat> _xi;
std::vector<std::vector<Mat> > _omEachCamera, _tEachCamera;
};
//! @}
}} // namespace multicalib, cv
#endif
\ No newline at end of file
This diff is collapsed.
/*M///////////////////////////////////////////////////////////////////////////////////////
//
// IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING.
//
// By downloading, copying, installing or using the software you agree to this license.
// If you do not agree to this license, do not download, install,
// copy or use the software.
//
//
// License Agreement
// For Open Source Computer Vision Library
//
// Copyright (C) 2015, Baisheng Lai (laibaisheng@gmail.com), Zhejiang University,
// all rights reserved.
//
// Redistribution and use in source and binary forms, with or without modification,
// are permitted provided that the following conditions are met:
//
// * Redistribution's of source code must retain the above copyright notice,
// this list of conditions and the following disclaimer.
//
// * Redistribution's in binary form must reproduce the above copyright notice,
// this list of conditions and the following disclaimer in the documentation
// and/or other materials provided with the distribution.
//
// * The name of the copyright holders may not be used to endorse or promote products
// derived from this software without specific prior written permission.
//
// This software is provided by the copyright holders and contributors "as is" and
// any express or implied warranties, including, but not limited to, the implied
// warranties of merchantability and fitness for a particular purpose are disclaimed.
// In no event shall the Intel Corporation or contributors be liable for any direct,
// indirect, incidental, special, exemplary, or consequential damages
// (including, but not limited to, procurement of substitute goods or services;
// loss of use, data, or profits; or business interruption) however caused
// and on any theory of liability, whether in contract, strict liability,
// or tort (including negligence or otherwise) arising in any way out of
// the use of this software, even if advised of the possibility of such damage.
//
//M*/
#ifndef __OPENCV_RANDOMPATTERN_HPP__
#define __OPENCV_RANDOMPATTERN_HPP__
#include "opencv2/features2d.hpp"
#include "opencv2/highgui.hpp"
namespace cv { namespace randpattern {
//! @addtogroup ccalib
//! @{
/** @brief Class for finding features points and corresponding 3D in world coordinate of
a "random" pattern, which can be to be used in calibration. It is useful when pattern is
partly occluded or only a part of pattern can be observed in multiple cameras calibration.
The pattern can be generated by RandomPatternGenerator class described in this file.
Please refer to paper
B. Li, L. Heng, K. Kevin and M. Pollefeys, "A Multiple-Camera System
Calibration Toolbox Using A Feature Descriptor-Based Calibration
Pattern", in IROS 2013.
*/
class CV_EXPORTS RandomPatternCornerFinder
{
public:
/* @brief Construct RandomPatternCornerFinder object
@param patternWidth the real width of "random" pattern in a user defined unit.
@param patternHeight the real height of "random" pattern in a user defined unit.
@param nMiniMatch number of minimal matches, otherwise that image is abandoned
@depth depth of output objectPoints and imagePoints, set it to be CV_32F or CV_64F.
@showExtraction whether show feature extraction, 0 for no and 1 for yes.
@detector feature detector to detect feature points in pattern and images.
@descriptor feature descriptor.
@matcher feature matcher.
*/
RandomPatternCornerFinder(float patternWidth, float patternHeight,
int nminiMatch = 20, int depth = CV_32F, int verbose = 0, int showExtraction = 0,
Ptr<FeatureDetector> detector = AKAZE::create(AKAZE::DESCRIPTOR_MLDB, 0, 3, 0.005f),
Ptr<DescriptorExtractor> descriptor = AKAZE::create(AKAZE::DESCRIPTOR_MLDB,0, 3, 0.005f),
Ptr<DescriptorMatcher> matcher = DescriptorMatcher::create("BruteForce-L1"));
/* @brief Load pattern image and compute features for pattern
@param patternImage image for "random" pattern generated by RandomPatternGenerator, run it first.
*/
void loadPattern(cv::Mat patternImage);
/* @brief Compute matched object points and image points which are used for calibration
The objectPoints (3D) and imagePoints (2D) are stored inside the class. Run getObjectPoints()
and getImagePoints() to get them.
@param inputImages vector of 8-bit grayscale images containing "random" pattern
that are used for calibration.
*/
void computeObjectImagePoints(std::vector<cv::Mat> inputImages);
//void computeObjectImagePoints2(std::vector<cv::Mat> inputImages);
/* @brief Compute object and image points for a single image. It returns a vector<Mat> that
the first element stores the imagePoints and the second one stores the objectPoints.
@param inputImage single input image for calibration
*/
std::vector<cv::Mat> computeObjectImagePointsForSingle(cv::Mat inputImage);
/* @brief Get object(3D) points
*/
std::vector<cv::Mat> getObjectPoints();
/* @brief and image(2D) points
*/
std::vector<cv::Mat> getImagePoints();
private:
std::vector<cv::Mat> _objectPonits, _imagePoints;
float _patternWidth, _patternHeight;
cv::Size _patternImageSize;
int _nminiMatch;
int _depth;
int _verbose;
Ptr<FeatureDetector> _detector;
Ptr<DescriptorExtractor> _descriptor;
Ptr<DescriptorMatcher> _matcher;
Mat _descriptorPattern;
std::vector<cv::KeyPoint> _keypointsPattern;
Mat _patternImage;
int _showExtraction;
void keyPoints2MatchedLocation(const std::vector<cv::KeyPoint>& imageKeypoints,
const std::vector<cv::KeyPoint>& patternKeypoints, const std::vector<cv::DMatch> matchces,
cv::Mat& matchedImagelocation, cv::Mat& matchedPatternLocation);
void getFilteredLocation(cv::Mat& imageKeypoints, cv::Mat& patternKeypoints, const cv::Mat mask);
void getObjectImagePoints(const cv::Mat& imageKeypoints, const cv::Mat& patternKeypoints);
void crossCheckMatching( cv::Ptr<DescriptorMatcher>& descriptorMatcher,
const Mat& descriptors1, const Mat& descriptors2,
std::vector<DMatch>& filteredMatches12, int knn=1 );
void drawCorrespondence(const Mat& image1, const std::vector<cv::KeyPoint> keypoint1,
const Mat& image2, const std::vector<cv::KeyPoint> keypoint2, const std::vector<cv::DMatch> matchces,
const Mat& mask1, const Mat& mask2, const int step);
};
/* @brief Class to generate "random" pattern image that are used for RandomPatternCornerFinder
Please refer to paper
B. Li, L. Heng, K. Kevin and M. Pollefeys, "A Multiple-Camera System
Calibration Toolbox Using A Feature Descriptor-Based Calibration
Pattern", in IROS 2013.
*/
class CV_EXPORTS RandomPatternGenerator
{
public:
/* @brief Construct RandomPatternGenerator
@param imageWidth image width of the generated pattern image
@param imageHeight image height of the generated pattern image
*/
RandomPatternGenerator(int imageWidth, int imageHeight);
/* @brief Generate pattern
*/
void generatePattern();
/* @brief Get pattern
*/
cv::Mat getPattern();
private:
cv::Mat _pattern;
int _imageWidth, _imageHeight;
};
//! @}
}} //namespace randpattern, cv
#endif
\ No newline at end of file
#include "opencv2/ccalib/omnidir.hpp"
#include "opencv2/ccalib/multicalib.hpp"
#include "opencv2/ccalib/randpattern.hpp"
using namespace std;
using namespace cv;
const char * usage =
"\n example command line for multi-camera calibration by using random pattern \n"
" multi_cameras_calibration -nc 5 -pw 800 -ph 600 -ct 1 -fe 0 -nm 25 -v 0 multi_camera_omnidir.xml \n"
"\n"
" the file multi_camera_omnidir.xml is generated by imagelist_creator as \n"
" imagelist_creator multi_camera_omnidir.xml *.* \n"
" note the first filename in multi_camera_omnidir.xml is the pattern, the rest are photo names,\n"
" photo names should be in form of cameraIdx-timestamp.*, and cameraIdx starts from 0";
static void help()
{
printf("\n This is a sample for multi-camera calibration, so far it only support random pattern,\n"
"see randomPattern.hpp for detail. Pinhole and omnidirectional cameras are both supported, \n"
"for omnidirectional camera, see omnidir.hpp for detail.\n"
"Usage: mutiCamCalib \n"
" -nc <num_camera> # number of cameras \n"
" -pw <pattern_width> # physical width of random pattern \n"
" -ph <pattern_height> # physical height of random pattern \n"
" -ct <camera_type> # camera type, 0 for pinhole and 1 for omnidirectional \n"
" -fe # whether show feature extraction\n"
" -nm # number of minimal matches of an image \n"
" -v # whether show verbose information \n"
" input_data # text file with pattern file names and a list of photo names, the file is generated by imagelist_creator \n");
printf("\n %s", usage);
}
int main(int argc, char** argv)
{
float patternWidth = 0.0f, patternHeight = 0.0f;
int nCamera = 0, nMiniMatches = 0, cameraType = 0;
const char* outputFilename = "multi-camera-results.xml";
const char* inputFilename = 0;
int showFeatureExtraction = 0, verbose = 0;
if (argc < 2)
{
help();
return 1;
}
for (int i = 1; i < argc; ++i)
{
const char* s = argv[i];
if (strcmp( s, "-nc") == 0)
{
if (sscanf( argv[++i], "%u", &nCamera) != 1 || nCamera <= 0)
{
return fprintf(stderr, "Invalid number of cameras \n"), -1;
}
}
else if ( strcmp( s, "-pw" ) == 0 )
{
if (sscanf( argv[++i], "%f", &patternWidth) != 1 || patternWidth <=0 )
{
return fprintf(stderr, "Invalid pattern width \n"), -1;
}
}
else if ( strcmp( s, "-ph" ) == 0 )
{
if (sscanf( argv[++i], "%f", &patternHeight) != 1 || patternHeight <=0 )
{
return fprintf(stderr, "Invalid pattern height \n"), -1;
}
}
else if ( strcmp( s, "-ct" ) == 0 )
{
if (sscanf( argv[++i], "%u", &cameraType) != 1 || (cameraType !=0 && cameraType !=1 && cameraType !=2) )
{
return fprintf(stderr, "Invalid camera type, 0 for pinhole and 1 for omnidirectional \n"), -1;
}
}
else if ( strcmp( s, "-fe" ) == 0 )
{
if (sscanf( argv[++i], "%u", &showFeatureExtraction) != 1 || (showFeatureExtraction !=1 && showFeatureExtraction !=0) )
{
return fprintf(stderr, "Not bool value, set to 0 or 1 \n"), -1;
}
}
else if ( strcmp( s, "-nm" ) == 0 )
{
if (sscanf( argv[++i], "%u", &nMiniMatches) != 1 || nMiniMatches <=0 )
{
return fprintf(stderr, "Invalid number of minimal matches \n"), -1;
}
}
else if ( strcmp( s, "-v" ) == 0 )
{
if (sscanf( argv[++i], "%u", &verbose) != 1 || (verbose !=1 && verbose !=0) )
{
return fprintf(stderr, "verbose is not bool value, set to 0 or 1 \n"), -1;
}
}
else if( s[0] != '-')
{
inputFilename = s;
}
else
{
return fprintf( stderr, "Unknown option %s\n", s ), -1;
}
}
// do multi-camera calibration
multicalib::MultiCameraCalibration multiCalib(cameraType, nCamera, inputFilename, patternWidth, patternHeight, verbose, showFeatureExtraction, nMiniMatches);
multiCalib.loadImages();
multiCalib.initialize();
multiCalib.optimizeExtrinsics();
// the above three lines can be replaced by multiCalib.run();
multiCalib.writeParameters(outputFilename);
}
\ No newline at end of file
#include "opencv2/ccalib/omnidir.hpp"
#include "opencv2/core.hpp"
#include "opencv2/imgproc.hpp"
#include "opencv2/calib3d.hpp"
#include "opencv2/highgui.hpp"
#include <vector>
#include <iostream>
#include <string>
#include <time.h>
using namespace cv;
using namespace std;
const char * usage =
"\n example command line for omnidirectional camera calibration.\n"
" omni_calibration -w 6 -h 9 -sw 80 -sh 80 imagelist.xml \n"
" \n"
" the file imagelist.xml is generated by imagelist_creator as\n"
"imagelist_creator imagelist.xml *.*";
static void help()
{
printf("\n This is a sample for omnidirectional camera calibration.\n"
"Usage: omni_calibration\n"
" -w <board_width> # the number of inner corners per one of board dimension\n"
" -h <board_height> # the number of inner corners per another board dimension\n"
" [-sw <square_width>] # the width of square in some user-defined units (1 by default)\n"
" [-sh <square_height>] # the height of square in some user-defined units (1 by default)\n"
" [-o <out_camera_params>] # the output filename for intrinsic [and extrinsic] parameters\n"
" [-fs <fix_skew>] # fix skew\n"
" [-fp ] # fix the principal point at the center\n"
" input_data # input data - text file with a list of the images of the board, which is generated by imagelist_creator"
);
printf("\n %s", usage);
}
static void calcChessboardCorners(Size boardSize, double square_width, double square_height,
Mat& corners)
{
// corners has type of CV_64FC3
corners.release();
int n = boardSize.width * boardSize.height;
corners.create(n, 1, CV_64FC3);
Vec3d *ptr = corners.ptr<Vec3d>();
for (int i = 0; i < boardSize.height; ++i)
{
for (int j = 0; j < boardSize.width; ++j)
{
ptr[i*boardSize.width + j] = Vec3d(double(j * square_width), double(i * square_height), 0.0);
}
}
}
static bool detecChessboardCorners(const vector<string>& list, vector<string>& list_detected,
vector<Mat>& imagePoints, Size boardSize, Size& imageSize)
{
imagePoints.resize(0);
list_detected.resize(0);
int n_img = (int)list.size();
Mat img;
for(int i = 0; i < n_img; ++i)
{
Mat points;
img = imread(list[i], IMREAD_GRAYSCALE);
bool found = findChessboardCorners( img, boardSize, points);
if (found)
{
if (points.type() != CV_64FC2)
points.convertTo(points, CV_64FC2);
imagePoints.push_back(points);
list_detected.push_back(list[i]);
}
}
if (!img.empty())
imageSize = img.size();
if (imagePoints.size() < 3)
return false;
else
return true;
}
static bool readStringList( const string& filename, vector<string>& l )
{
l.resize(0);
FileStorage fs(filename, FileStorage::READ);
if( !fs.isOpened() )
return false;
FileNode n = fs.getFirstTopLevelNode();
if( n.type() != FileNode::SEQ )
return false;
FileNodeIterator it = n.begin(), it_end = n.end();
for( ; it != it_end; ++it )
l.push_back((string)*it);
return true;
}
static void saveCameraParams( const string & filename, int flags, const Mat& cameraMatrix,
const Mat& distCoeffs, const double xi, const vector<Vec3d>& rvecs, const vector<Vec3d>& tvecs,
vector<string> detec_list, const Mat& idx, const double rms, const vector<Mat>& imagePoints)
{
FileStorage fs( filename, FileStorage::WRITE );
time_t tt;
time( &tt );
struct tm *t2 = localtime( &tt );
char buf[1024];
strftime( buf, sizeof(buf)-1, "%c", t2 );
fs << "calibration_time" << buf;
if ( !rvecs.empty())
fs << "nFrames" << (int)rvecs.size();
if ( flags != 0)
{
sprintf( buf, "flags: %s%s%s%s%s%s%s%s%s",
flags & omnidir::CALIB_USE_GUESS ? "+use_intrinsic_guess" : "",
flags & omnidir::CALIB_FIX_SKEW ? "+fix_skew" : "",
flags & omnidir::CALIB_FIX_K1 ? "+fix_k1" : "",
flags & omnidir::CALIB_FIX_K2 ? "+fix_k2" : "",
flags & omnidir::CALIB_FIX_P1 ? "+fix_p1" : "",
flags & omnidir::CALIB_FIX_P2 ? "+fix_p2" : "",
flags & omnidir::CALIB_FIX_XI ? "+fix_xi" : "",
flags & omnidir::CALIB_FIX_GAMMA ? "+fix_gamma" : "",
flags & omnidir::CALIB_FIX_CENTER ? "+fix_center" : "");
//cvWriteComment( *fs, buf, 0 );
}
fs << "flags" << flags;
fs << "camera_matrix" << cameraMatrix;
fs << "distortion_coefficients" << distCoeffs;
fs << "xi" << xi;
//cvWriteComment( *fs, "names of images that are acturally used in calibration", 0 );
fs << "used_imgs" << "[";
for (int i = 0; i < (int)idx.total(); ++i)
{
fs << detec_list[(int)idx.at<int>(i)];
}
fs << "]";
if ( !rvecs.empty() && !tvecs.empty() )
{
Mat rvec_tvec((int)rvecs.size(), 6, CV_64F);
for (int i = 0; i < (int)rvecs.size(); ++i)
{
Mat(rvecs[i]).reshape(1, 1).copyTo(rvec_tvec(Rect(0, i, 3, 1)));
Mat(tvecs[i]).reshape(1, 1).copyTo(rvec_tvec(Rect(3, i, 3, 1)));
}
//cvWriteComment( *fs, "a set of 6-tuples (rotation vector + translation vector) for each view", 0 );
fs << "extrinsic_parameters" << rvec_tvec;
}
fs << "rms" << rms;
if ( !imagePoints.empty() )
{
Mat imageMat((int)imagePoints.size(), (int)imagePoints[0].total(), CV_64FC2);
for (int i = 0; i < (int)imagePoints.size(); ++i)
{
Mat r = imageMat.row(i).reshape(2, imageMat.cols);
Mat imagei(imagePoints[i]);
imagei.copyTo(r);
}
fs << "image_points" << imageMat;
}
}
int main(int argc, char** argv)
{
Size boardSize, imageSize;
int flags = 0;
double square_width = 0.0, square_height = 0.0;
const char* outputFilename = "out_camera_params.xml";
const char* inputFilename = 0;
vector<Mat> objectPoints;
vector<Mat> imagePoints;
if(argc < 2)
{
help();
return 1;
}
for(int i = 1; i < argc; i++)
{
const char* s = argv[i];
if( strcmp( s, "-w") == 0)
{
if( sscanf( argv[++i], "%u", &boardSize.width ) != 1 || boardSize.width <= 0 )
return fprintf( stderr, "Invalid board width\n" ), -1;
}
else if( strcmp( s, "-h" ) == 0 )
{
if( sscanf( argv[++i], "%u", &boardSize.height ) != 1 || boardSize.height <= 0 )
return fprintf( stderr, "Invalid board height\n" ), -1;
}
else if( strcmp( s, "-sw" ) == 0 )
{
if( sscanf( argv[++i], "%lf", &square_width ) != 1 || square_width <= 0 )
return fprintf(stderr, "Invalid square width\n"), -1;
}
else if( strcmp( s, "-sh" ) == 0 )
{
if( sscanf( argv[++i], "%lf", &square_height) != 1 || square_height <= 0 )
return fprintf(stderr, "Invalid square height\n"), -1;
}
else if( strcmp( s, "-o" ) == 0 )
{
outputFilename = argv[++i];
}
else if( strcmp( s, "-fs" ) == 0 )
{
flags |= omnidir::CALIB_FIX_SKEW;
}
else if( strcmp( s, "-fp" ) == 0 )
{
flags |= omnidir::CALIB_FIX_CENTER;
}
else if( s[0] != '-')
{
inputFilename = s;
}
else
{
return fprintf( stderr, "Unknown option %s\n", s ), -1;
}
}
// get image name list
vector<string> image_list, detec_list;
if(!readStringList(inputFilename, image_list))
return fprintf( stderr, "Failed to read image list\n"), -1;
// find corners in images
// some images may be failed in automatic corner detection, passed cases are in detec_list
if(!detecChessboardCorners(image_list, detec_list, imagePoints, boardSize, imageSize))
return fprintf(stderr, "Not enough corner detected images\n"), -1;
// calculate object coordinates
Mat object;
calcChessboardCorners(boardSize, square_width, square_height, object);
for(int i = 0; i < (int)detec_list.size(); ++i)
objectPoints.push_back(object);
// run calibration, some images are discarded in calibration process because they are failed
// in initialization. Retained image indexes are in idx variable.
Mat K, D, xi, idx;
vector<Vec3d> rvecs, tvecs;
double _xi, rms;
TermCriteria criteria(3, 200, 1e-8);
rms = omnidir::calibrate(objectPoints, imagePoints, imageSize, K, xi, D, rvecs, tvecs, flags, criteria, idx);
_xi = xi.at<double>(0);
saveCameraParams(outputFilename, flags, K, D, _xi,
rvecs, tvecs, detec_list, idx, rms, imagePoints);
}
This diff is collapsed.
#include "opencv2/ccalib/randpattern.hpp"
#include "opencv2/highgui.hpp"
#include "opencv2/imgproc.hpp"
#include "opencv2/calib3d.hpp"
#include <vector>
#include <iostream>
#include <time.h>
using namespace std;
using namespace cv;
const char * usage =
"\n example command line for calibrate a camera by random pattern. \n"
" random_pattern_calibration -pw 600 -ph 850 -mm 20 image_list.xml \n"
"\n"
" the file image_list.xml is generated by imagelist_creator as\n"
"imagelist_creator image_list.xml *.*";
static void help()
{
printf("\n This is a sample for camera calibration by a random pattern.\n"
"Usage: random_pattern_calibration\n"
" -pw <pattern_width> # the physical width of random pattern\n"
" -ph <pattern_height> # the physical height of random pattern\n"
" -mm <minimal_match> # minimal number of matches\n"
" [-fp ] # fix the principal point at the center \n"
" input_data # input data - text file with a list of the images of the board, which is generated by imagelist_creator"
);
printf("\n %s", usage);
}
static bool readStringList( const string& filename, vector<string>& l )
{
l.resize(0);
FileStorage fs(filename, FileStorage::READ);
if( !fs.isOpened() )
return false;
FileNode n = fs.getFirstTopLevelNode();
if( n.type() != FileNode::SEQ )
return false;
FileNodeIterator it = n.begin(), it_end = n.end();
for( ; it != it_end; ++it )
l.push_back((string)*it);
return true;
}
static void saveCameraParams(const string& filename, Size imageSize, float patternWidth,
float patternHeight, int flags, const Mat& cameraMatrix, const Mat& distCoeffs,
const vector<Mat>& rvecs, const vector<Mat>& tvecs, double rms)
{
FileStorage fs (filename, FileStorage::WRITE );
time_t tt;
time( &tt );
struct tm *t2 = localtime( &tt );
char buf[1024];
strftime( buf, sizeof(buf)-1, "%c", t2 );
fs << "calibration_time" << buf;
if( !rvecs.empty())
fs << "nframes" << (int)rvecs.size();
fs << "image_width" << imageSize.width;
fs << "image_height" << imageSize.height;
fs << "pattern_width" << patternWidth;
fs << "pattern_height" << patternHeight;
fs << "flags" <<flags;
fs << "camera_matrix" << cameraMatrix;
fs << "distortion_coefficients" << distCoeffs;
fs << "rms" << rms;
if( !rvecs.empty() && !tvecs.empty() )
{
CV_Assert(rvecs[0].type() == tvecs[0].type());
Mat bigmat((int)rvecs.size(), 6, rvecs[0].type());
for( int i = 0; i < (int)rvecs.size(); i++ )
{
Mat r = bigmat(Range(i, i+1), Range(0,3));
Mat t = bigmat(Range(i, i+1), Range(3,6));
CV_Assert(rvecs[i].rows == 3 && rvecs[i].cols == 1);
CV_Assert(tvecs[i].rows == 3 && tvecs[i].cols == 1);
//*.t() is MatExpr (not Mat) so we can use assignment operator
r = rvecs[i].t();
t = tvecs[i].t();
}
//cvWriteComment( *fs, "a set of 6-tuples (rotation vector + translation vector) for each view", 0 );
fs << "extrinsic_parameters" << bigmat;
}
}
int main(int argc, char** argv)
{
const char* inputFilename = 0;
const char* outputFilename = "out_camera_params.xml";
vector<string> imglist;
vector<Mat> vecImg;
int flags = 0;
float patternWidth = 0.0f, patternHeight = 0.0f;
int nMiniMatches = 0;
if(argc < 2)
{
help();
return 1;
}
for (int i = 1; i < argc; ++i)
{
const char* s = argv[i];
if(strcmp(s, "-pw") == 0)
{
if(sscanf(argv[++i], "%f", &patternWidth) != 1 || patternWidth <= 0)
return fprintf( stderr, "Invalid pattern width\n"), -1;
}
else if(strcmp(s, "-ph") == 0)
{
if(sscanf(argv[++i], "%f", &patternHeight) != 1 || patternHeight <= 0)
return fprintf( stderr, "Invalid pattern height\n"), -1;
}
else if (strcmp(s, "-mm") == 0)
{
if (sscanf(argv[++i], "%d", &nMiniMatches) != 1 || nMiniMatches < 15)
return fprintf( stderr, "Invalid number of minimal matches or number is too small"), -1;
}
else if( strcmp( s, "-fp" ) == 0 )
{
flags |= CALIB_FIX_PRINCIPAL_POINT;
}
else if( s[0] != '-')
{
inputFilename = s;
}
else
{
return fprintf( stderr, "Unknown option %s\n", s ), -1;
}
}
readStringList(inputFilename, imglist);
// the first image is the pattern
Mat pattern = cv::imread(imglist[0], cv::IMREAD_GRAYSCALE);
for (int i = 1; i < (int)imglist.size(); ++i)
{
Mat img;
img = cv::imread(imglist[i], cv::IMREAD_GRAYSCALE);
vecImg.push_back(img);
}
randpattern::RandomPatternCornerFinder finder(patternWidth, patternHeight, nMiniMatches);
finder.loadPattern(pattern);
finder.computeObjectImagePoints(vecImg);
vector<Mat> objectPoints = finder.getObjectPoints();
vector<Mat> imagePoints = finder.getImagePoints();
Mat K;
Mat D;
vector<Mat> rvec, tvec;
double rms = calibrateCamera(objectPoints, imagePoints, vecImg[0].size(), K, D, rvec, tvec);
saveCameraParams(outputFilename, vecImg[0].size(), patternWidth, patternHeight, flags, K, D, rvec, tvec, rms);
}
#include "opencv2/ccalib/randpattern.hpp"
using namespace cv;
const char * usage =
"\n example command line for generating a random pattern. \n"
" random_patterng_generator -iw 600 -ih 850 pattern.png\n"
"\n";
static void help()
{
printf("\n This is a sample for generating a random pattern that can be used for calibration.\n"
"Usage: random_patterng_generator\n"
" -iw <image_width> # the width of pattern image\n"
" -ih <image_height> # the height of pattern image\n"
" filename # the filename for pattern image \n"
);
printf("\n %s", usage);
}
int main(int argc, char** argv)
{
const char* filename = 0;
Mat pattern;
int width = 0, height = 0;
if(argc < 2)
{
help();
return 1;
}
for (int i = 1; i < argc; ++i)
{
const char* s = argv[i];
if(strcmp(s, "-iw") == 0)
{
if(sscanf(argv[++i], "%d", &width) != 1 || width <= 0)
return fprintf( stderr, "Invalid pattern image width\n"), -1;
}
else if(strcmp(s, "-ih") == 0)
{
if(sscanf(argv[++i], "%d", &height) != 1 || height <= 0)
return fprintf( stderr, "Invalid pattern image height\n"), -1;
}
else if( s[0] != '-')
{
filename = s;
}
else
{
return fprintf( stderr, "Unknown option %s\n", s ), -1;
}
}
randpattern::RandomPatternGenerator generator(width, height);
generator.generatePattern();
pattern = generator.getPattern();
imwrite(filename, pattern);
}
\ No newline at end of file
This diff is collapsed.
This diff is collapsed.
/*M///////////////////////////////////////////////////////////////////////////////////////
//
// IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING.
//
// By downloading, copying, installing or using the software you agree to this license.
// If you do not agree to this license, do not download, install,
// copy or use the software.
//
//
// License Agreement
// For Open Source Computer Vision Library
//
// Copyright (C) 2014, OpenCV Foundation, all rights reserved.
// Third party copyrights are property of their respective owners.
//
// Redistribution and use in source and binary forms, with or without modification,
// are permitted provided that the following conditions are met:
//
// * Redistribution's of source code must retain the above copyright notice,
// this list of conditions and the following disclaimer.
//
// * Redistribution's in binary form must reproduce the above copyright notice,
// this list of conditions and the following disclaimer in the documentation
// and/or other materials provided with the distribution.
//
// * The name of the copyright holders may not be used to endorse or promote products
// derived from this software without specific prior written permission.
//
// This software is provided by the copyright holders and contributors "as is" and
// any express or implied warranties, including, but not limited to, the implied
// warranties of merchantability and fitness for a particular purpose are disclaimed.
// In no event shall the Intel Corporation or contributors be liable for any direct,
// indirect, incidental, special, exemplary, or consequential damages
// (including, but not limited to, procurement of substitute goods or services;
// loss of use, data, or profits; or business interruption) however caused
// and on any theory of liability, whether in contract, strict liability,
// or tort (including negligence or otherwise) arising in any way out of
// the use of this software, even if advised of the possibility of such damage.
//
//M*/
//
// IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING.
//
// By downloading, copying, installing or using the software you agree to this license.
// If you do not agree to this license, do not download, install,
// copy or use the software.
//
//
// License Agreement
// For Open Source Computer Vision Library
//
// Copyright (C) 2000-2008, Intel Corporation, all rights reserved.
// Copyright (C) 2009, Willow Garage Inc., all rights reserved.
// Third party copyrights are property of their respective owners.
//
// Redistribution and use in source and binary forms, with or without modification,
// are permitted provided that the following conditions are met:
//
// * Redistribution's of source code must retain the above copyright notice,
// this list of conditions and the following disclaimer.
//
// * Redistribution's in binary form must reproduce the above copyright notice,
// this list of conditions and the following disclaimer in the documentation
// and/or other materials provided with the distribution.
//
// * The name of the copyright holders may not be used to endorse or promote products
// derived from this software without specific prior written permission.
//
// This software is provided by the copyright holders and contributors "as is" and
// any express or implied warranties, including, but not limited to, the implied
// warranties of merchantability and fitness for a particular purpose are disclaimed.
// In no event shall the Intel Corporation or contributors be liable for any direct,
// indirect, incidental, special, exemplary, or consequential damages
// (including, but not limited to, procurement of substitute goods or services;
// loss of use, data, or profits; or business interruption) however caused
// and on any theory of liability, whether in contract, strict liability,
// or tort (including negligence or otherwise) arising in any way out of
// the use of this software, even if advised of the possibility of such damage.
//
//M*/
#ifndef __OPENCV_CCALIB_PRECOMP__
#define __OPENCV_CCALIB_PRECOMP__
#ifndef __OPENCV_PRECOMP_H__
#define __OPENCV_PRECOMP_H__
#include <opencv2/core.hpp>
#include <opencv2/calib3d.hpp>
#include <opencv2/features2d.hpp>
#include "opencv2/imgproc.hpp"
#include "opencv2/highgui.hpp"
#include <vector>
#endif
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
Multi-camera Calibration {#tutorial_multi_camera_main}
====================================
This tutorial will show how to use the multiple camera calibration toolbox. This toolbox is based on the usage of "random" pattern calibration object, so the tutorial is mainly two parts: an introduction to "random" pattern and multiple camera calibration.
Random Pattern Calibration Object
-------------------------------
The random pattern is an image that is randomly generated. It is "random" so that it has many feature points. After generating it, one print it out and use it as a calibration object. The following two images are random pattern and a photo taken for it.
![image](img/random_pattern.jpg)
![image](img/pattern_img.jpg)
To generate a random pattern, use the class ```cv::randpattern::RandomPatternGenerator``` in ```ccalib``` module. Run it as
```
cv::randpattern::RandomPatternGenerator generator(width, height);
generator.generatePattern();
pattern = generator.getPattern();
```
Here ```width``` and ```height``` are width and height of pattern image. After getting the pattern, print it out and take some photos of it.
Now we can use these images to calibrate camera. First, ```objectPoints``` and ```imagePoints``` need to be detected. Use class ```cv::randpattern::RandomPatternCornerFinder``` to detect them. A sample code can be
```
cv::randpattern::RandomPatternCornerFinder finder(patternWidth, patternHeight, nMiniMatches);
finder.loadPattern(pattern);
finder.computeObjectImagePoints(vecImg);
vector<Mat> objectPoints = finder.getObjectPoints();
vector<Mat> imagePoints = finder.getImagePoints();
```
Here variable ```patternWidth``` and ```patternHeight``` are physical pattern width and height with some user defined unit. ```vecImg``` is a vector of images that stores calibration images.
Second, use calibration functions like ```cv::calibrateCamera``` or ```cv::omnidir::calibrate``` to calibrate camera.
Multiple Cameras Calibration
-------------------------------
Now we move to multiple camera calibration, so far this toolbox must use random pattern object.
To calibrate multiple cameras, we first need to take some photos of random pattern. Of cause, to calibrate the extrinsic parameters, one pattern need to be viewed by multiple cameras (at least two) at the same time. Another thing is that to help the program know which camera and which pattern the photo is taken, the image file should be named as "cameraIdx-timestamp.*". Photos with same timestamp means that they are the same object taken by several cameras. In addition, cameraIdx should start from 0. Some examples of files names are "0-129.png", "0-187.png", "1-187", "2-129".
Then, we can run multiple cameras calibration as
```
cv::multicalib::MultiCameraCalibration multiCalib(cameraType, nCamera, inputFilename,patternWidth, patternHeight, showFeatureExtraction, nMiniMatches);
multiCalib.run();
multiCalib.writeParameters(outputFilename);
```
Here ```cameraType``` indicates the camera type, ```multicalib::MultiCameraCalibration::PINHOLE``` and ```multicalib::MultiCameraCalibration::OMNIDIRECTIONAL``` are supported. For omnidirectional camera, you can refer to ```cv::omnidir``` module for detail. ```nCamera``` is the number of camers. ```inputFilename``` is the name of a file generated by ```imagelist_creator``` from ```opencv/sample```. It stores names of random pattern and calibration images, the first file name is the name of random pattern. ```patternWidth``` and ```patternHeight``` are physical width and height of pattern. ```showFeatureExtraction``` is a flags to indicate whether show feature extraction process. ```nMiniMatches``` is a minimal points that should be detected in each frame, otherwise this frame will be abandoned. ```outputFilename``` is a xml file name to store parameters.
This diff is collapsed.
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment