40#include <visp3/core/vpConfig.h>
42#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC) && defined(VISP_HAVE_PUGIXML) \
43 && (((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_CALIB3D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_3D)))
47#if defined(HAVE_OPENCV_CALIB3D)
48#include <opencv2/calib3d/calib3d.hpp>
49#elif defined(HAVE_OPENCV_CALIB)
50#include <opencv2/calib.hpp>
53#if defined(HAVE_OPENCV_CONTRIB)
54#include <opencv2/contrib/contrib.hpp>
57#include <opencv2/core/core.hpp>
58#include <opencv2/highgui/highgui.hpp>
59#include <opencv2/imgproc/imgproc.hpp>
61#include <visp3/vision/vpCalibration.h>
63#include <visp3/core/vpImageTools.h>
64#include <visp3/core/vpIoTools.h>
65#include <visp3/core/vpMeterPixelConversion.h>
66#include <visp3/core/vpPixelMeterConversion.h>
67#include <visp3/core/vpPoint.h>
68#include <visp3/core/vpXmlParserCamera.h>
69#include <visp3/gui/vpDisplayFactory.h>
70#include <visp3/io/vpVideoReader.h>
72#include "calibration-helper.hpp"
74using namespace calib_helper;
76void usage(
const char *argv[],
int error)
78 std::cout <<
"Synopsis" << std::endl
80 <<
" <configuration file>.cfg"
81 <<
" [--init-from-xml <camera-init.xml>]"
82 <<
" [--camera-name <name>]"
83 <<
" [--aspect-ratio <ratio>]"
84 <<
" [--output <file.xml>]"
85 <<
" [--help, -h]" << std::endl
87 std::cout <<
"Description" << std::endl
88 <<
" <configuration file>.cfg" << std::endl
89 <<
" Configuration file. See example in \"default-chessboard.cfg\" or in \"default-circles.cfg\"." << std::endl
90 <<
" Default: \"default.cfg\"." << std::endl
92 <<
" --init-from-xml <camera-init.xml>" << std::endl
93 <<
" XML file that contains camera parameters used to initialize the calibration process." << std::endl
95 <<
" --camera-name <name>" << std::endl
96 <<
" Camera name in the XML file set using \"--init-from-xml\" option." << std::endl
97 <<
" Default: \"Camera\"." << std::endl
99 <<
" --aspect-ratio <ratio>" << std::endl
100 <<
" Pixel aspect ratio. To estimate px = py, use \"--aspect-ratio 1\" option. Set to -1" << std::endl
101 <<
" to unset any constraint for px and py parameters. " << std::endl
102 <<
" Default: -1." << std::endl
104 <<
" --output <file.xml>" << std::endl
105 <<
" XML file containing estimated camera parameters." << std::endl
106 <<
" Default: \"camera.xml\"." << std::endl
108 <<
" --help, -h" << std::endl
109 <<
" Print this helper message." << std::endl
112 std::cout <<
"Error" << std::endl
114 <<
"Unsupported parameter " << argv[
error] << std::endl;
118int main(
int argc,
const char *argv[])
120#if defined(ENABLE_VISP_NAMESPACE)
124#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
133 std::string opt_output_file_name =
"camera.xml";
135 const std::string opt_inputSettingsFile = argc > 1 ? argv[1] :
"default.cfg";
136 std::string opt_init_camera_xml_file;
137 std::string opt_camera_name =
"Camera";
138 double opt_aspect_ratio = -1;
140 for (
int i = 2;
i < argc;
i++) {
141 if (std::string(argv[i]) ==
"--init-from-xml" && i + 1 < argc) {
142 opt_init_camera_xml_file = std::string(argv[++i]);
144 else if (std::string(argv[i]) ==
"--camera-name" && i + 1 < argc) {
145 opt_camera_name = std::string(argv[++i]);
147 else if (std::string(argv[i]) ==
"--output" && i + 1 < argc) {
148 opt_output_file_name = std::string(argv[++i]);
150 else if (std::string(argv[i]) ==
"--aspect-ratio" && i + 1 < argc) {
151 opt_aspect_ratio = std::atof(argv[++i]);
153 else if (std::string(argv[i]) ==
"--help" || std::string(argv[i]) ==
"-h") {
163 std::cout <<
"Settings from config file: " << argv[1] << std::endl;
164 if (!
s.read(opt_inputSettingsFile)) {
165 std::cout <<
"Could not open the configuration file: \"" << opt_inputSettingsFile <<
"\"" << std::endl;
171 std::cout <<
"Invalid input detected. Application stopping. " << std::endl;
175 std::cout <<
"\nSettings from command line options: " << std::endl;
176 if (!opt_init_camera_xml_file.empty()) {
177 std::cout <<
"Init parameters: " << opt_init_camera_xml_file << std::endl;
179 std::cout <<
"Ouput xml file : " << opt_output_file_name << std::endl;
180 std::cout <<
"Camera name : " << opt_camera_name << std::endl;
184 std::cout <<
"\nOutput file name " << opt_output_file_name <<
" already exists." << std::endl;
185 std::cout <<
"Remove this file or change output file name using [--output <file.xml>] command line option."
198 std::cout <<
"Catch an exception: " <<
e.getStringMessage() << std::endl;
199 std::cout <<
"Check if input images name \"" <<
s.input <<
"\" set in " << opt_inputSettingsFile
200 <<
" config file is correct..." << std::endl;
204#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
211 bool init_from_xml =
false;
212 if (!opt_init_camera_xml_file.empty()) {
214 std::cout <<
"Input camera file \"" << opt_init_camera_xml_file <<
"\" doesn't exist!" << std::endl;
215 std::cout <<
"Modify [--init-from-xml <camera-init.xml>] option value" << std::endl;
216#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
217 if (display !=
nullptr) {
223 init_from_xml =
true;
226 std::cout <<
"Initialize camera parameters from xml file: " << opt_init_camera_xml_file << std::endl;
228 if (
parser.parse(cam_init, opt_init_camera_xml_file, opt_camera_name,
230 std::cout <<
"Unable to find camera with name \"" << opt_camera_name
231 <<
"\" in file: " << opt_init_camera_xml_file << std::endl;
232 std::cout <<
"Modify [--camera-name <name>] option value" << std::endl;
233#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
234 if (display !=
nullptr) {
242 std::cout <<
"Initialize camera parameters with default values " << std::endl;
244 double px = cam_init.
get_px();
245 double py = cam_init.
get_py();
247 double u0 = I.getWidth() / 2;
248 double v0 = I.getHeight() / 2;
252 std::cout <<
"Camera parameters used for initialization:\n" << cam_init << std::endl;
254 std::vector<vpPoint> model;
255 std::vector<vpCalibration> calibrator;
257 for (
int i = 0;
i <
s.boardSize.height;
i++) {
258 for (
int j = 0;
j <
s.boardSize.width;
j++) {
259 model.push_back(
vpPoint(j *
s.squareSize, i *
s.squareSize, 0));
263 std::vector<CalibInfo> calib_info;
264 std::multimap<double, vpCameraParameters, std::less<double> > map_cam_sorted;
266 map_cam_sorted.insert(std::make_pair(1000, cam_init));
277 std::vector<cv::Point2f> pointBuf;
280 std::cout <<
"Process frame: " << frame_name << std::flush;
281 bool found = extractCalibrationPoints(s, cvI, pointBuf);
283 std::cout <<
", grid detection status: " << found;
285 std::cout <<
", image rejected" << std::endl;
287 std::cout <<
", image used as input data" << std::endl;
292 std::vector<vpImagePoint>
data;
293 for (
unsigned int i = 0;
i < pointBuf.size();
i++) {
300 std::vector<vpPoint> calib_points;
304 for (
unsigned int i = 0;
i < model.size();
i++) {
305 calib.
addPoint(model[i].get_oX(), model[i].get_oY(), model[i].get_oZ(), data[i]);
306 calib_points.push_back(
vpPoint(model[i].get_oX(), model[i].get_oY(), model[i].get_oZ()));
307 calib_points.back().set_x(data[i].get_u());
308 calib_points.back().set_y(data[i].get_v());
312 bool calib_status =
false;
313 std::multimap<double, vpCameraParameters>::const_iterator it_cam;
314 for (it_cam = map_cam_sorted.begin(); it_cam != map_cam_sorted.end(); ++it_cam) {
317 calibrator.push_back(calib);
319 calib_info.push_back(CalibInfo(I, calib_points, data, frame_name));
322 map_cam_sorted.insert(std::make_pair(residual, cam));
327 std::cout <<
"frame: " << frame_name <<
", unable to calibrate from single image, image rejected"
340 if (
s.tempo > 10.f) {
350 }
while (!reader.
end());
354 if (calibrator.empty()) {
355 std::cerr <<
"Unable to calibrate. Image processing failed !" << std::endl;
356#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
357 if (display !=
nullptr) {
365 drawCalibrationOccupancy(I, calib_info,
s.boardSize.width);
367 cv::Mat1b img(I.getHeight(), I.getWidth());
369 cv::Mat3b imgColor(I.getHeight(), I.getWidth());
370 cv::applyColorMap(img, imgColor, cv::COLORMAP_JET);
373 for (
size_t idx1 = 0; idx1 < calib_info.size(); idx1++) {
374 const CalibInfo &calib = calib_info[idx1];
376 for (
size_t idx2 = 0; idx2 < calib.m_imPts.size(); idx2++) {
378 cv::rectangle(imgColor,
379 cv::Rect(
static_cast<int>(imPt.
get_u() - 2),
static_cast<int>(imPt.
get_v() - 2),
381 cv::Scalar(0, 0, 0), -1);
388 d->init(I_color, 0, 0,
"Calibration pattern occupancy");
395 if (
s.tempo > 10.f) {
408 std::stringstream ss_additional_info;
410 ss_additional_info <<
"<nb_calibration_images>" << calibrator.size() <<
"</nb_calibration_images>";
411 ss_additional_info <<
"<calibration_pattern_type>";
413 switch (
s.calibrationPattern) {
414 case Settings::CHESSBOARD:
415 ss_additional_info <<
"Chessboard";
418 case Settings::CIRCLES_GRID:
419 ss_additional_info <<
"Circles grid";
422 case Settings::UNDEFINED:
424 ss_additional_info <<
"Undefined";
427 ss_additional_info <<
"</calibration_pattern_type>";
428 ss_additional_info <<
"<board_size>" <<
s.boardSize.width <<
"x" <<
s.boardSize.height <<
"</board_size>";
429 ss_additional_info <<
"<square_size>" <<
s.squareSize <<
"</square_size>";
434 std::cout <<
"\nCalibration without distortion in progress on " << calibrator.size() <<
" images..." << std::endl;
437 std::cout <<
cam << std::endl;
441 ss_additional_info <<
"<reprojection_error><without_distortion>";
442 for (
size_t i = 0;
i < calibrator.size();
i++) {
443 double reproj_error = sqrt(calibrator[i].getResidual() / calibrator[i].get_npt());
445 const CalibInfo &calib = calib_info[
i];
446 std::cout <<
"Image " << calib.m_frame_name <<
" reprojection error: " << reproj_error << std::endl;
448 ss_additional_info <<
"<image>" << reproj_error <<
"</image>";
452 std::ostringstream ss;
453 ss <<
"Reprojection error: " << reproj_error;
463 for (
size_t idx = 0;
idx < calib.m_points.size();
idx++) {
473 if (
s.tempo > 10.f) {
485 std::cout <<
"\nGlobal reprojection error: " <<
error << std::endl;
486 ss_additional_info <<
"<global_reprojection_error>" <<
error <<
"</global_reprojection_error>";
488 ss_additional_info <<
"</without_distortion>";
491 if (xml.
save(cam, opt_output_file_name.c_str(), opt_camera_name, I.getWidth(), I.getHeight()) ==
493 std::cout <<
"Camera parameters without distortion successfully saved in \"" << opt_output_file_name <<
"\""
496 std::cout <<
"Failed to save the camera parameters without distortion in \"" << opt_output_file_name <<
"\""
498 std::cout <<
"A file with the same name exists. Remove it to be able "
499 "to save the parameters..."
504 std::cout <<
"Calibration without distortion failed." << std::endl;
505#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
506 if (display !=
nullptr) {
513 std::vector<vpCalibration> calibrator_without_dist = calibrator;
515 std::cout <<
"\n\nCalibration with distortion in progress on " << calibrator.size() <<
" images..." << std::endl;
518 std::cout <<
cam << std::endl;
521 ss_additional_info <<
"<with_distortion>";
522 for (
size_t i = 0;
i < calibrator.size();
i++) {
523 double reproj_error = sqrt(calibrator[i].getResidual_dist() / calibrator[i].get_npt());
525 const CalibInfo &calib = calib_info[
i];
526 std::cout <<
"Image " << calib.m_frame_name <<
" reprojection error: " << reproj_error << std::endl;
527 ss_additional_info <<
"<image>" << reproj_error <<
"</image>";
531 std::ostringstream ss;
532 ss <<
"Reprojection error: " << reproj_error;
542 for (
size_t idx = 0;
idx < calib.m_points.size();
idx++) {
546 pt.
project(calibrator[i].cMo_dist);
552 if (
s.tempo > 10.f) {
563 std::cout <<
"\nGlobal reprojection error: " <<
error << std::endl;
564 ss_additional_info <<
"<global_reprojection_error>" <<
error <<
"</global_reprojection_error>";
566 ss_additional_info <<
"</with_distortion></reprojection_error>";
571 d->init(I_dist_undist, 0, 0,
"Straight lines have to be straight - distorted image / undistorted image");
573 for (
size_t idx = 0;
idx < calib_info.size();
idx++) {
574 std::cout <<
"\nThis tool computes the line fitting error (mean distance error) on image points extracted from "
575 "the raw distorted image."
578 I = calib_info[
idx].m_img;
582 I_dist_undist.insert(I_undist,
vpImagePoint(0, I.getWidth()));
587 calib_info[idx].m_frame_name + std::string(
" distorted"),
vpColor::red);
591 std::vector<vpImagePoint> grid_points = calib_info[
idx].m_imPts;
592 for (
int i = 0;
i <
s.boardSize.height;
i++) {
593 std::vector<vpImagePoint> current_line(grid_points.begin() + i *
s.boardSize.width,
594 grid_points.begin() + (i + 1) *
s.boardSize.width);
596 std::vector<vpImagePoint> current_line_undist = undistort(cam, current_line);
597 double a = 0, b = 0, c = 0;
600 std::cout << calib_info[
idx].m_frame_name <<
" line " <<
i + 1
601 <<
" fitting error on distorted points: " << line_fitting_error
602 <<
" ; on undistorted points: " << line_fitting_error_undist << std::endl;
609 std::cout <<
"\nThis tool computes the line fitting error (mean distance error) on image points extracted from "
610 "the undistorted image"
611 <<
" (vpImageTools::undistort())." << std::endl;
613 std::vector<cv::Point2f> pointBuf;
616 bool found = extractCalibrationPoints(s, cvI, pointBuf);
618 std::vector<vpImagePoint> grid_points;
619 for (
unsigned int i = 0;
i < pointBuf.size();
i++) {
621 grid_points.push_back(ip);
626 calib_info[idx].m_frame_name + std::string(
" undistorted"),
vpColor::red);
627 for (
int i = 0;
i <
s.boardSize.height;
i++) {
628 std::vector<vpImagePoint> current_line(grid_points.begin() + i *
s.boardSize.width,
629 grid_points.begin() + (i + 1) *
s.boardSize.width);
631 double a = 0, b = 0, c = 0;
633 std::cout << calib_info[
idx].m_frame_name <<
" undistorted image, line " <<
i + 1
634 <<
" fitting error: " << line_fitting_error << std::endl;
642 std::string msg(
"Unable to detect grid on undistorted image");
643 std::cout << msg << std::endl;
644 std::cout <<
"Check that the grid is not too close to the image edges" << std::endl;
647 calib_info[idx].m_frame_name + std::string(
" undistorted"),
vpColor::red);
652 if (
s.tempo > 10.f) {
665 std::cout << std::endl;
669 ss_additional_info <<
"<camera_poses>";
670 for (
size_t i = 0;
i < calibrator.size();
i++) {
672 ss_additional_info <<
"<cMo>" << pose.t() <<
"</cMo>";
674 for (
size_t i = 0;
i < calibrator.size();
i++) {
676 ss_additional_info <<
"<cMo_dist>" << pose.t() <<
"</cMo_dist>";
678 ss_additional_info <<
"</camera_poses>";
680 if (xml.
save(cam, opt_output_file_name.c_str(), opt_camera_name, I.getWidth(), I.getHeight(),
682 std::cout <<
"Camera parameters without distortion successfully saved in \"" << opt_output_file_name <<
"\""
685 std::cout <<
"Failed to save the camera parameters without distortion in \"" << opt_output_file_name <<
"\""
687 std::cout <<
"A file with the same name exists. Remove it to be able "
688 "to save the parameters..."
691 std::cout << std::endl;
692 std::cout <<
"Estimated pose using vpPoseVector format: [tx ty tz tux tuy tuz] with translation in meter and "
695 for (
unsigned int i = 0;
i < calibrator.size();
i++)
696 std::cout <<
"Estimated pose on input data extracted from " << calib_info[i].m_frame_name <<
": "
700 std::cout <<
"Calibration with distortion failed." << std::endl;
701#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
702 if (display !=
nullptr) {
709 std::cout <<
"\nCamera calibration succeeded. Results are saved in " <<
"\"" << opt_output_file_name <<
"\"" << std::endl;
710#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
711 if (display !=
nullptr) {
718 std::cout <<
"Catch an exception: " <<
e << std::endl;
719#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
720 if (display !=
nullptr) {
730#if !defined(HAVE_OPENCV_IMGPROC)
731 std::cout <<
"This example requires OpenCV imgproc module." << std::endl;
733#if !defined(HAVE_OPENCV_HIGHGUI)
734 std::cout <<
"This example requires OpenCV highgui module." << std::endl;
736#if defined(VISP_HAVE_OPENCV) && (VISP_HAVE_OPENCV_VERSION < 0x050000) && !defined(HAVE_OPENCV_CALIB3D)
737 std::cout <<
"This example requires OpenCV calib3d module." << std::endl;
739#if defined(VISP_HAVE_OPENCV) && (VISP_HAVE_OPENCV_VERSION >= 0x050000) && !defined(HAVE_OPENCV_3D)
740 std::cout <<
"This example requires OpenCV 3d module." << std::endl;
742#if !defined(VISP_HAVE_PUGIXML)
743 std::cout <<
"pugixml built-in 3rdparty is requested to run the calibration." << std::endl;
Tools for perspective camera intrinsic parameters calibration.
static void setLambda(const double &lambda)
int computeCalibration(vpCalibrationMethodType method, vpHomogeneousMatrix &cMo_est, vpCameraParameters &cam_est, bool verbose=false)
double getResidual(void) const
int addPoint(double X, double Y, double Z, vpImagePoint &ip)
static int computeCalibrationMulti(vpCalibrationMethodType method, std::vector< vpCalibration > &table_cal, vpCameraParameters &cam_est, double &globalReprojectionError, bool verbose=false)
void setAspectRatio(double aspect_ratio)
Generic class defining intrinsic camera parameters.
void initPersProjWithoutDistortion(double px, double py, double u0, double v0)
@ perspectiveProjWithoutDistortion
Perspective projection without distortion model.
static const vpColor green
Class that defines generic functionalities for display.
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
static void display(const vpImage< unsigned char > &I)
static void displayLine(const vpImage< unsigned char > &I, const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color, unsigned int thickness=1, bool segment=true)
static void displayCross(const vpImage< unsigned char > &I, const vpImagePoint &ip, unsigned int size, const vpColor &color, unsigned int thickness=1)
static void setTitle(const vpImage< unsigned char > &I, const std::string &windowtitle)
static void flush(const vpImage< unsigned char > &I)
unsigned int getDownScalingFactor()
static void displayText(const vpImage< unsigned char > &I, const vpImagePoint &ip, const std::string &s, const vpColor &color)
error that can be emitted by ViSP classes.
Implementation of an homogeneous matrix and operations on such kind of matrices.
static void convert(const vpImage< unsigned char > &src, vpImage< vpRGBa > &dest)
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
Definition of the vpImage class member functions.
unsigned int getHeight() const
static double lineFitting(const std::vector< vpImagePoint > &imPts, double &a, double &b, double &c)
static void convertPoint(const vpCameraParameters &cam, const double &x, const double &y, double &u, double &v)
Class that defines a 3D point in the object frame and allows forward projection of a 3D point in the ...
double get_y() const
Get the point y coordinate in the image plane.
double get_x() const
Get the point x coordinate in the image plane.
Implementation of a pose vector and operations on poses.
Class that enables to manipulate easily a video file or a sequence of images. As it inherits from the...
void open(vpImage< vpRGBa > &I) VP_OVERRIDE
void setFileName(const std::string &filename)
long getFrameIndex() const
void acquire(vpImage< vpRGBa > &I) VP_OVERRIDE
XML parser to load and save intrinsic camera parameters.
int save(const vpCameraParameters &cam, const std::string &filename, const std::string &camera_name, unsigned int image_width=0, unsigned int image_height=0, const std::string &additionalInfo="", bool verbose=true)
std::shared_ptr< vpDisplay > createDisplay()
Return a smart pointer vpDisplay specialization if a GUI library is available or nullptr otherwise.
vpDisplay * allocateDisplay()
Return a newly allocated vpDisplay specialization if a GUI library is available or nullptr otherwise.
VISP_EXPORT int wait(double t0, double t)
VISP_EXPORT std::string getDateTime(const std::string &format="%Y/%m/%d %H:%M:%S")