22 #include <Eigen/Dense> 30 #ifdef USE_NUMERIC_JACOBIANS 52 ASSERT_(
p.check_squares_length_X_meters > 0);
53 ASSERT_(
p.check_squares_length_Y_meters > 0);
54 const bool user_wants_use_robust =
p.use_robust_kernel;
56 if (images.size() < 1)
58 std::cout <<
"ERROR: No input images." << std::endl;
62 const unsigned CORNERS_COUNT =
p.check_size_x *
p.check_size_y;
72 vector<size_t> valid_image_pair_indices;
76 for (
size_t i = 0; i < images.size(); i++)
80 bool corners_found[2] = {
false,
false};
82 for (
int lr = 0; lr < 2; lr++)
93 imgSize[lr] = img_gray.
getSize();
107 if (imgSize[lr].
y != (
int)img_gray.
getHeight() ||
108 imgSize[lr].
x != (int)img_gray.
getWidth())
110 std::cout <<
"ERROR: All the images in each left/right " 111 "channel must have the same size." 125 if (corners_found[lr] &&
127 corners_found[lr] =
false;
131 "%s img #%u: %s\n", lr == 0 ?
"LEFT" :
"RIGHT",
132 static_cast<unsigned int>(i),
133 corners_found[lr] ?
"DETECTED" :
"NOT DETECTED");
142 (*
p.callback)(cbPars,
p.callback_user_param);
145 if (corners_found[lr])
162 if (corners_found[0] && corners_found[1])
164 valid_image_pair_indices.push_back(i);
176 bool has_to_redraw_corners =
false;
178 const TPixelCoordf pt_l0 = images[i].left.detected_corners[0],
179 pt_l1 = images[i].left.detected_corners[1],
180 pt_r0 = images[i].right.detected_corners[0],
181 pt_r1 = images[i].right.detected_corners[1];
189 if (Al.x * Ar.x + Al.y * Ar.y < 0)
191 has_to_redraw_corners =
true;
194 images[i].right.detected_corners.begin(),
195 images[i].right.detected_corners.end());
198 if (has_to_redraw_corners)
201 images[i].right.img_original.colorImage(
202 images[i].right.img_checkboard);
203 images[i].right.img_checkboard.drawChessboardCorners(
204 images[i].right.detected_corners, check_size.
x,
212 std::cout << valid_image_pair_indices.size()
213 <<
" valid image pairs." << std::endl;
214 if (valid_image_pair_indices.empty())
216 std::cout <<
"ERROR: No valid images. Perhaps the checkerboard " 225 vector<TPoint3D> obj_points;
226 obj_points.reserve(CORNERS_COUNT);
227 for (
unsigned int y = 0;
y <
p.check_size_y;
y++)
228 for (
unsigned int x = 0;
x <
p.check_size_x;
x++)
229 obj_points.emplace_back(
230 p.check_squares_length_X_meters *
x,
231 p.check_squares_length_Y_meters *
y, 0);
242 const size_t N = valid_image_pair_indices.size();
243 const size_t nObs = 2 * N * CORNERS_COUNT;
248 const double tau = 0.3;
249 const double t1 = 1e-8;
250 const double t2 = 1e-8;
251 const double MAX_LAMBDA = 1e20;
256 lm_stat_t lm_stat(images, valid_image_pair_indices, obj_points);
280 size_t nUnknownsCamParams = 0;
283 std::vector<size_t> vars_to_optimize;
288 for (
int calibRound = 0; calibRound < 2; calibRound++)
293 << ((calibRound == 0) ?
"LM calibration round #0: WITHOUT " 294 "distortion ----------\n" 295 :
"LM calibration round #1: ALL " 296 "parameters --------------\n");
302 vars_to_optimize.clear();
303 vars_to_optimize.push_back(0);
304 vars_to_optimize.push_back(1);
305 vars_to_optimize.push_back(2);
306 vars_to_optimize.push_back(3);
309 if (
p.optimize_k1) vars_to_optimize.push_back(4);
310 if (
p.optimize_k2) vars_to_optimize.push_back(5);
311 if (
p.optimize_t1) vars_to_optimize.push_back(6);
312 if (
p.optimize_t2) vars_to_optimize.push_back(7);
313 if (
p.optimize_k3) vars_to_optimize.push_back(8);
316 nUnknownsCamParams = vars_to_optimize.size();
322 const size_t nUnknowns = N * 6 + 6 + 2 * nUnknownsCamParams;
327 lm_stat, res_jacob,
false ,
328 p.robust_kernel_param);
337 double lambda = tau * H.
asEigen().diagonal().array().maxCoeff();
338 bool done = (minus_g.
array().abs().maxCoeff() < t1);
339 int numItersImproving = 0;
340 bool use_robust =
false;
344 while (iter <
p.maxIters && !done)
351 (*
p.callback)(cbPars,
p.callback_user_param);
356 for (
size_t i = 0; i < nUnknowns; i++) HH(i, i) += lambda;
359 Eigen::LLT<Eigen::MatrixXd> llt(
360 HH.asEigen().selfadjointView<Eigen::Lower>());
361 if (llt.info() != Eigen::Success)
365 done = (lambda > MAX_LAMBDA);
367 if (
p.verbose && !done)
368 cout <<
"LM iter#" << iter
369 <<
": Couldn't solve LLt, retrying with larger " 375 llt.solve(minus_g.
asEigen()).eval());
377 const double eps_norm =
eps.norm();
378 if (eps_norm < t2 * (eps_norm + t2))
381 cout <<
"Termination criterion: eps_norm < " 383 << eps_norm <<
" < " << t2 * (eps_norm + t2)
398 new_lm_stat, new_res_jacob, use_robust,
399 p.robust_kernel_param);
406 if (numItersImproving++ > 5)
407 use_robust = user_wants_use_robust;
411 cout <<
"LM iter#" << iter
412 <<
": Avr.err(px):" << std::sqrt(err / nObs)
413 <<
"->" << std::sqrt(err_new / nObs)
414 <<
" lambda:" << lambda << endl;
417 lm_stat.
swap(new_lm_stat);
418 res_jacob.swap(new_res_jacob);
422 res_jacob, vars_to_optimize, minus_g, H);
425 done = (minus_g.
array().abs().maxCoeff() < t1);
428 lambda = std::max(lambda, 1e-100);
437 cout <<
"LM iter#" << iter <<
": No update: err=" << err
438 <<
" -> err_new=" << err_new
439 <<
" retrying with larger lambda=" << lambda
442 done = (lambda > MAX_LAMBDA);
486 for (
unsigned long valid_image_pair_indice : valid_image_pair_indices)
497 const size_t base_idx_H_CPs = H.
cols() - 2 * nUnknownsCamParams;
498 for (
size_t i = 0; i < nUnknownsCamParams; i++)
501 H(base_idx_H_CPs + i, base_idx_H_CPs + i);
503 H(base_idx_H_CPs + nUnknownsCamParams + i,
504 base_idx_H_CPs + nUnknownsCamParams + i);
508 for (
unsigned long idx : valid_image_pair_indices)
553 catch (
const std::exception& e)
555 std::cout << e.what() << std::endl;
577 const double pz_ = 1 /
p.z;
578 const double pz_2 = pz_ * pz_;
582 G(0, 2) = -
p.x * pz_2;
586 G(1, 2) = -
p.y * pz_2;
638 const double x = nP.
x / nP.
z;
639 const double y = nP.
y / nP.
z;
641 const double r2 =
x *
x +
y *
y;
642 const double r = std::sqrt(r2);
643 const double r6 = r2 * r2 * r2;
646 const double fx =
c[0], fy =
c[1];
648 const double k1 =
c[4], k2 =
c[5], k3 =
c[6];
649 const double t1 =
c[7], t2 =
c[8];
653 fx * (k2 * r2 + k3 * r6 + 6 * t2 *
x + 2 * t1 *
y +
654 x * (2 * k1 *
x + 4 * k2 *
x *
r + 6 * k3 *
x * r2) + k1 *
r + 1);
655 Hb(0, 1) = fx * (2 * t1 *
x + 2 * t2 *
y +
656 x * (2 * k1 *
y + 4 * k2 *
y *
r + 6 * k3 *
y * r2));
658 Hb(1, 0) = fy * (2 * t1 *
x + 2 * t2 *
y +
659 y * (2 * k1 *
x + 4 * k2 *
x *
r + 6 * k3 *
x * r2));
661 fy * (k2 * r2 + k3 * r6 + 2 * t2 *
x + 6 * t1 *
y +
662 y * (2 * k1 *
y + 4 * k2 *
y *
r + 6 * k3 *
y * r2) + k1 *
r + 1);
665 Hc(0, 0) = t2 * (3 *
x *
x +
y *
y) +
x * (k2 * r2 + k3 * r6 + k1 *
r + 1) +
670 Hc(0, 4) = fx *
x *
r;
671 Hc(0, 5) = fx *
x * r2;
672 Hc(0, 6) = fx *
x * r6;
673 Hc(0, 7) = 2 * fx *
x *
y;
674 Hc(0, 8) = fx * (3 *
x *
x +
y *
y);
677 Hc(1, 1) = t1 * (
x *
x + 3 *
y *
y) +
y * (k2 * r2 + k3 * r6 + k1 *
r + 1) +
681 Hc(1, 4) = fy *
y *
r;
682 Hc(1, 5) = fy *
y * r2;
683 Hc(1, 6) = fy *
y * r6;
684 Hc(1, 7) = fy * (
x *
x + 3 *
y *
y);
685 Hc(1, 8) = 2 * fy *
x *
y;
694 dpl_del.
block<3, 3>(0, 0).setIdentity();
710 P.dot(dr1) + D.
x(), P.dot(dr2) + D.
y(), P.dot(dr3) + D.z());
713 H.block<3, 3>(0, 0).setIdentity();
716 dp_deps =
A.getRotationMatrix().asEigen() * H;
728 const double x = nP.
x / nP.
z;
729 const double y = nP.
y / nP.
z;
733 const double r4 =
square(r2);
734 const double r6 = r2 * r4;
737 const double B = 2 *
x *
y;
755 const size_t N = res_jac.size();
756 const size_t nMaxUnknowns = N * 6 + 6 + 9 + 9;
764 for (
size_t i = 0; i < N; i++)
766 const size_t nObs = res_jac[i].size();
767 for (
size_t j = 0; j < nObs; j++)
778 minus_g_tot.block<6, 1>(i * 6, 0) -= gij.block<6, 1>(0, 0);
779 minus_g_tot.block<6 + 9 + 9, 1>(N * 6, 0) -=
780 gij.block<6 + 9 + 9, 1>(6, 0);
782 H_tot.block<6, 6>(i * 6, i * 6) += Hij.block<6, 6>(0, 0);
784 H_tot.block<6 + 9 + 9, 6 + 9 + 9>(N * 6, N * 6) +=
785 Hij.block<6 + 9 + 9, 6 + 9 + 9>(6, 6);
786 H_tot.block<6, 6 + 9 + 9>(i * 6, N * 6) +=
787 Hij.block<6, 6 + 9 + 9>(0, 6);
788 H_tot.block<6 + 9 + 9, 6>(N * 6, i * 6) +=
789 Hij.block<6 + 9 + 9, 6>(6, 0);
797 const double cost_lr_angular = 1e10;
804 const size_t N_Cs = var_indxs.size();
805 const size_t nUnknowns = N * 6 + 6 + 2 * N_Cs;
806 const size_t nUnkPoses = N * 6 + 6;
809 H.
setZero(nUnknowns, nUnknowns);
811 minus_g.
asEigen().block(0, 0, nUnkPoses, 1) =
812 minus_g_tot.asEigen().block(0, 0, nUnkPoses, 1);
813 H.
asEigen().block(0, 0, nUnkPoses, nUnkPoses) =
814 H_tot.asEigen().block(0, 0, nUnkPoses, nUnkPoses);
817 for (
size_t i = 0; i < N_Cs; i++)
819 minus_g[nUnkPoses + i] = minus_g_tot[nUnkPoses + var_indxs[i]];
820 minus_g[nUnkPoses + N_Cs + i] =
821 minus_g_tot[nUnkPoses + 9 + var_indxs[i]];
824 for (
size_t k = 0; k < nUnkPoses; k++)
826 for (
size_t i = 0; i < N_Cs; i++)
828 H(nUnkPoses + i, k) = H(k, nUnkPoses + i) =
829 H_tot(k, nUnkPoses + var_indxs[i]);
830 H(nUnkPoses + i + N_Cs, k) = H(k, nUnkPoses + i + N_Cs) =
831 H_tot(k, nUnkPoses + 9 + var_indxs[i]);
835 for (
size_t i = 0; i < N_Cs; i++)
837 for (
size_t j = 0; j < N_Cs; j++)
839 H(nUnkPoses + i, nUnkPoses + j) =
840 H_tot(nUnkPoses + var_indxs[i], nUnkPoses + var_indxs[j]);
841 H(nUnkPoses + N_Cs + i, nUnkPoses + N_Cs + j) = H_tot(
842 nUnkPoses + 9 + var_indxs[i], nUnkPoses + 9 + var_indxs[j]);
869 const std::vector<size_t>& var_indxs,
lm_stat_t& lm_stat)
873 for (
size_t i = 0; i < N; i++)
899 const size_t idx = 6 * N + 6;
902 for (
size_t i = 0; i < nPC; i++)
910 #ifdef USE_NUMERIC_JACOBIANS 927 obj_point(_obj_point),
929 right2left(_right2left),
935 void numeric_jacob_eval_function(
972 dat.obj_point, cam_params.
leftCamera, incrPose_l + dat.left_cam, px_l);
976 incrPose_rl + dat.right2left + incrPose_l + dat.left_cam, px_r);
979 px_l.
x, px_l.
y, px_r.
x, px_r.
y);
990 const double x = X[0],
y = X[1];
992 const double r4 =
square(r2);
993 const double r6 = r2 * r4;
996 const double B = 2 *
x *
y;
1022 for (
int i = 0; i < 3; i++) out[i] = D_p_out[i];
1025 struct TEvalData_A_eps_D_p
1031 void eval_dA_eps_D_p(
1037 const CPose3D A_eps_D = dat.A + (incrPose + dat.D);
1040 for (
int i = 0; i < 3; i++) out[i] = pt[i];
1051 bool use_robust_kernel,
double kernel_param)
1053 double total_err = 0;
1081 for (
size_t k = 0; k < N; k++)
1084 const size_t nPts = lm_stat.
obj_points.size();
1085 res_jac[k].resize(nPts);
1087 for (
size_t i = 0; i < nPts; i++)
1091 lm_stat.
images[k_idx].left.detected_corners[i];
1093 lm_stat.
images[k_idx].right.detected_corners[i];
1095 px_obs_l.
x, px_obs_l.
y, px_obs_r.
x, px_obs_r.
y);
1115 const double err_sqr_norm = rje.
residual.squaredNorm();
1116 if (use_robust_kernel)
1119 rk.param_sq = kernel_param;
1121 double kernel_1st_deriv, kernel_2nd_deriv;
1122 const double scaled_err =
1123 rk.eval(err_sqr_norm, kernel_1st_deriv, kernel_2nd_deriv);
1126 total_err += scaled_err;
1129 total_err += err_sqr_norm;
1136 #if !defined(USE_NUMERIC_JACOBIANS) || defined(COMPARE_NUMERIC_JACOBIANS) 1142 TPoint3D pt_wrt_left, pt_wrt_right;
1146 .composePoint(lm_stat.
obj_points[i], pt_wrt_right);
1174 rje.
J.setZero(4, 30);
1175 rje.
J.block<2, 6>(0, 0) = dhl_del.
asEigen();
1176 rje.
J.block<2, 6>(2, 0) = dhr_del.
asEigen();
1177 rje.
J.block<2, 6>(2, 6) = dhr_der.
asEigen();
1178 rje.
J.block<2, 9>(0, 12) = dhl_dcl.
asEigen();
1179 rje.
J.block<2, 9>(2, 21) = dhr_dcr.
asEigen();
1181 #if defined(COMPARE_NUMERIC_JACOBIANS) 1187 #if defined(USE_NUMERIC_JACOBIANS) || defined(COMPARE_NUMERIC_JACOBIANS) 1197 const double x_incrs_val[30] = {
1198 1e-6, 1e-6, 1e-6, 1e-7, 1e-7, 1e-7,
1199 1e-6, 1e-6, 1e-6, 1e-7, 1e-7, 1e-7,
1200 1e-3, 1e-3, 1e-3, 1e-3, 1e-8, 1e-8, 1e-8, 1e-8, 1e-4,
1201 1e-3, 1e-3, 1e-3, 1e-3, 1e-8, 1e-8, 1e-8, 1e-8, 1e-4
1209 x0, &numeric_jacob_eval_function, x_incrs, dat, rje.
J);
1211 #if defined(COMPARE_NUMERIC_JACOBIANS) 1214 #endif // ---- end of numeric Jacobians ---- 1217 #if defined(COMPARE_NUMERIC_JACOBIANS) 1221 f.open(
"dbg.txt", ios_base::out | ios_base::app);
1227 << J_num - J_theor << endl
1228 <<
"diff (ratio):\n" 1229 << (J_num - J_theor).cwiseQuotient(J_num) << endl
double k3() const
Get the value of the k3 distortion parameter.
double final_rmse
Final reprojection square Root Mean Square Error (in pixels).
A compile-time fixed-size numeric matrix container.
double x
X,Y,Z coordinates.
bool drawChessboardCorners(std::vector< TPixelCoordf > &cornerCoords, unsigned int check_size_x, unsigned int check_size_y, unsigned int lines_width=1, unsigned int circles_radius=4)
Draw onto this image the detected corners of a chessboard.
std::vector< std::vector< TResidJacobElement > > TResidualJacobianList
void composePoint(double lx, double ly, double lz, double &gx, double &gy, double &gz, mrpt::math::CMatrixFixed< double, 3, 3 > *out_jacobian_df_dpoint=nullptr, mrpt::math::CMatrixFixed< double, 3, 6 > *out_jacobian_df_dpose=nullptr, mrpt::math::CMatrixFixed< double, 3, 6 > *out_jacobian_df_dse3=nullptr, bool use_small_rot_approx=false) const
An alternative, slightly more efficient way of doing with G and L being 3D points and P this 6D pose...
double fx() const
Get the value of the focal length x-value (in pixels).
std::vector< bool > image_pair_was_used
true if a checkerboard was correctly detected in both left/right images.
unsigned int nImgsToProcess
size_t final_number_good_image_pairs
Number of image pairs in which valid checkerboards were correctly detected.
double fy() const
Get the value of the focal length y-value (in pixels).
void jacob_deps_D_p_deps(const TPoint3D &p_D, mrpt::math::CMatrixFixed< double, 3, 6 > &dpl_del)
size_t getHeight() const override
Returns the height of the image in pixels.
size_t final_iters
Final number of optimization iterations executed.
A pair (x,y) of pixel coordinates (subpixel resolution).
Eigen::Matrix< double, 4, 1 > predicted_obs
[u_l v_l u_r v_r]: left/right camera pixels
bool isExternallyStored() const noexcept
See setExternalStorage().
const TCalibrationStereoImageList & images
Data associated to each observation in the Lev-Marq.
void saveToTextFile(const std::string &file, mrpt::math::TMatrixTextFileFormat fileFormat=mrpt::math::MATRIX_FORMAT_ENG, bool appendMRPTHeader=false, const std::string &userHeader=std::string()) const
Saves the vector/matrix to a file compatible with MATLAB/Octave text format.
void jacob_dh_db_and_dh_dc(const TPoint3D &nP, const mrpt::math::CVectorFixedDouble< 9 > &c, mrpt::math::CMatrixFixed< double, 2, 2 > &Hb, mrpt::math::CMatrixFixed< double, 2, 9 > &Hc)
mrpt::poses::CPose3D right2left_pose
void getSize(TImageSize &s) const
Return the size of the image.
mrpt::img::TStereoCamera cam_params
Recovered parameters of the stereo camera.
double k2() const
Get the value of the k2 distortion parameter.
T square(const T x)
Inline function for the square of a number.
CImage colorImage() const
Returns a color (RGB) version of the grayscale image, or a shallow copy of itself if it is already a ...
#define ASSERT_(f)
Defines an assertion mechanism.
void skew_symmetric3_neg(const VECTOR &v, MATRIX &M)
Computes the negative version of a 3x3 skew symmetric matrix from a 3-vector or 3-array: ...
mrpt::img::CImage img_checkboard
At output, this will contain the detected checkerboard overprinted to the image.
Data associated to each image in the calibration process mrpt::vision::checkerBoardCameraCalibration ...
This base provides a set of functions for maths stuff.
size_t getWidth() const override
Returns the width of the image in pixels.
double cy() const
Get the value of the principal point y-coordinate (in pixels).
Input parameters for mrpt::vision::checkerBoardStereoCalibration.
Params of the optional callback provided by the user.
void composeFrom(const CPose3D &A, const CPose3D &B)
Makes "this = A (+) B"; this method is slightly more efficient than "this= A + B;" since it avoids th...
#define ASSERT_EQUAL_(__A, __B)
Assert comparing two values, reporting their actual values upon failure.
auto block(int start_row, int start_col)
non-const block(): Returns an Eigen::Block reference to the block
void add_lm_increment(const mrpt::math::CVectorDynamic< double > &eps, const std::vector< size_t > &var_indxs, lm_stat_t &new_lm_stat)
bool findChessboardCorners(const mrpt::img::CImage &img, std::vector< mrpt::img::TPixelCoordf > &cornerCoords, unsigned int check_size_x, unsigned int check_size_y, bool normalize_image=true, bool useScaramuzzaMethod=false)
Look for the corners of a chessboard in the image using one of two different methods.
std::vector< mrpt::poses::CPose3D > left_cam_poses
A pair (x,y) of pixel coordinates (integer resolution).
std::vector< mrpt::img::TPixelCoordf > detected_corners
At output, the detected corners (x,y) in pixel units.
Classes for computer vision, detectors, features, etc.
Structure to hold the parameters of a pinhole camera model.
const std::vector< mrpt::math::TPoint3D > & obj_points
double x() const
Common members of all points & poses classes.
A class used to store a 3D pose as a translation (x,y,z) and a quaternion (qr,qx,qy,qz).
std::array< double, 9 > right_params_inv_variance
size_type cols() const
Number of columns in the matrix.
double p1() const
Get the value of the p1 distortion parameter.
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
void estimateJacobian(const VECTORLIKE &x, const std::function< void(const VECTORLIKE &x, const USERPARAM &y, VECTORLIKE3 &out)> &functor, const VECTORLIKE2 &increments, const USERPARAM &userParam, MATRIXLIKE &out_Jacobian)
Estimate the Jacobian of a multi-dimensional function around a point "x", using finite differences of...
double recompute_errors_and_Jacobians(const lm_stat_t &lm_stat, TResidualJacobianList &res_jac, bool use_robust_kernel, double kernel_param)
const std::vector< size_t > & valid_image_pair_indices
void projectPoints_with_distortion(const std::vector< mrpt::math::TPoint3D > &in_points_3D, const mrpt::poses::CPose3D &cameraPose, const mrpt::math::CMatrixDouble33 &intrinsicParams, const std::vector< double > &distortionParams, std::vector< mrpt::img::TPixelCoordf > &projectedPoints, bool accept_points_behind=false)
Project a set of 3D points into a camera at an arbitrary 6D pose using its calibration matrix and dis...
void pause(const std::string &msg=std::string("Press any key to continue...")) noexcept
Shows the message "Press any key to continue" (or other custom message) to the current standard outpu...
Traits for SE(n), rigid-body transformations in R^n space.
Eigen::Matrix< double, 4, 1 > residual
= predicted_obs - observations
Eigen::Matrix< double, 4, 30 > J
Jacobian.
double cx() const
Get the value of the principal point x-coordinate (in pixels).
bool checkerBoardStereoCalibration(TCalibrationStereoImageList &images, const TStereoCalibParams ¶ms, TStereoCalibResults &out_results)
Optimize the calibration parameters of a stereo camera or a RGB+D (Kinect) camera.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
void jacob_dA_eps_D_p_deps(const CPose3D &A, const CPose3D &D, const TPoint3D &p, mrpt::math::CMatrixFixed< double, 3, 6 > &dp_deps)
double current_rmse
Current root-mean square reprojection error (in pixels)
mrpt::math::CVectorFixedDouble< 9 > right_cam_params
GLdouble GLdouble GLdouble r
unsigned int nImgsProcessed
Info for calibRound==-1.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
std::array< double, 9 > left_params_inv_variance
The inverse variance (information/precision) of each of the 9 left/right camera parameters [fx fy cx ...
std::string format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
TPixelCoord TImageSize
A type for image sizes.
TCamera leftCamera
Intrinsic and distortion parameters of the left and right cameras.
EIGEN_MAP asEigen()
Get as an Eigen-compatible Eigen::Map object.
mrpt::poses::CPose3D right2left_camera_pose
The pose of the left camera as seen from the right camera.
static CVectorDynamic< T > Zero()
std::vector< mrpt::poses::CPose3D > left_cam_poses
Poses of the origin of coordinates of the pattern wrt the left camera (i.e.
double p2() const
Get the value of the p2 distortion parameter.
double k1() const
Get the value of the k1 distortion parameter.
EIGEN_MAP asEigen()
Get as an Eigen-compatible Eigen::Map object.
void project_point(const mrpt::math::TPoint3D &P, const mrpt::img::TCamera ¶ms, const CPose3D &cameraPose, mrpt::img::TPixelCoordf &px)
Output results for mrpt::vision::checkerBoardStereoCalibration.
void getRotationMatrix(mrpt::math::CMatrixDouble33 &ROT) const
Get the 3x3 rotation matrix.
EIGEN_MAP asEigen()
Get as an Eigen-compatible Eigen::Map object.
mrpt::poses::CPose3D reconstructed_camera_pose
At output, the reconstructed pose of the camera.
int calibRound
=-1:Processing images; =0: Initial calib without distortion, =1: Calib of all parameters ...
std::vector< mrpt::img::TPixelCoordf > projectedPoints_distorted
At output, only will have an empty vector if the checkerboard was not found in this image...
GLenum const GLfloat * params
void jacob_db_dp(const TPoint3D &p, mrpt::math::CMatrixFixed< double, 2, 3 > &G)
uint32_t ncols
Camera resolution.
mrpt::img::CImage img_original
This image will be automatically loaded from the file name passed to checkerBoardCameraCalibration.
Structure to hold the parameters of a pinhole stereo camera model.
std::vector< TImageStereoCalibData > TCalibrationStereoImageList
A list of images, used in checkerBoardStereoCalibration.
mrpt::math::CVectorFixedDouble< 9 > left_cam_params
[fx fy cx cy k1 k2 k3 t1 t2]
mrpt::img::CImage img_rectified
At output, this will be the rectified image.
A class for storing images as grayscale or RGB bitmaps.
void build_linear_system(const TResidualJacobianList &res_jac, const std::vector< size_t > &var_indxs, mrpt::math::CVectorDynamic< double > &minus_g, mrpt::math::CMatrixDouble &H)