Theory of Bouguet s MatLab Camera Calibration Toolbox

Similar documents
Sparse Levenberg-Marquardt algorithm.

Pose Tracking II! Gordon Wetzstein! Stanford University! EE 267 Virtual Reality! Lecture 12! stanford.edu/class/ee267/!

3D from Photographs: Camera Calibration. Dr Francesco Banterle

Camera calibration by Zhang

Augmented Reality VU Camera Registration. Prof. Vincent Lepetit

Camera calibration. Outline. Pinhole camera. Camera projection models. Nonlinear least square methods A camera calibration tool

Visual SLAM Tutorial: Bundle Adjustment

Camera Calibration The purpose of camera calibration is to determine the intrinsic camera parameters (c 0,r 0 ), f, s x, s y, skew parameter (s =

Pose estimation from point and line correspondences

Homographies and Estimating Extrinsics

nonrobust estimation The n measurement vectors taken together give the vector X R N. The unknown parameter vector is P R M.

OPPA European Social Fund Prague & EU: We invest in your future.

Linear and Nonlinear Optimization

Camera calibration Triangulation

EE Camera & Image Formation

13. Nonlinear least squares

Chapter 4 Systems of Linear Equations; Matrices

Numerical computation II. Reprojection error Bundle adjustment Family of Newtonʼs methods Statistical background Maximum likelihood estimation

Lecture 3: QR-Factorization

Augmented Reality VU numerical optimization algorithms. Prof. Vincent Lepetit

Applied Mathematics 205. Unit I: Data Fitting. Lecturer: Dr. David Knezevic

16. Analysis and Computation of the Intrinsic Camera Parameters

Quality Report Generated with Pix4Dmapper Pro version

Method 1: Geometric Error Optimization

ANALYTICAL IMAGE FEATURES

Lecture 4.3 Estimating homographies from feature correspondences. Thomas Opsahl

Camera Calibration. (Trucco, Chapter 6) -Toproduce an estimate of the extrinsic and intrinsic camera parameters.

A Stellar Gyroscope for CubeSat Attitude Determination

Nonlinear Least Squares

Structure from Motion. CS4670/CS Kevin Matzen - April 15, 2016

A Study of Kruppa s Equation for Camera Self-calibration

Practical rotation angle measurement method by monocular vision

Deuxième examen partiel A 2013

CS181 Midterm 2 Practice Solutions

Principal Component Analysis (PCA) for Sparse High-Dimensional Data

A Theory of Multi-Layer Flat Refractive Geometry Supplementary Materials

Introduction to pinhole cameras

CS4495/6495 Introduction to Computer Vision. 3D-L3 Fundamental matrix

Self-Calibration of a Moving Camera by Pre-Calibration

EPIPOLAR GEOMETRY WITH MANY DETAILS

CS 231A Computer Vision (Fall 2011) Problem Set 2

Optimisation on Manifolds

Least squares problems

Uncertainty Models in Quasiconvex Optimization for Geometric Reconstruction

3D Computer Vision - WT 2004

L3: Review of linear algebra and MATLAB

Vision par ordinateur

Linear Algebra: Matrix Eigenvalue Problems

The Multibody Trifocal Tensor: Motion Segmentation from 3 Perspective Views

Math 273a: Optimization Netwon s methods

TRACKING and DETECTION in COMPUTER VISION

Least-Squares Performance of Analog Product Codes

Least-Squares Fitting of Model Parameters to Experimental Data

Finite Element Methods with Linear B-Splines

Visual Object Recognition

CSE 160 Lecture 13. Numerical Linear Algebra

Numerical Programming I (for CSE)

Non-polynomial Least-squares fitting

Homogeneous Coordinates

Bundle Adjustment for 3-D Reconstruction: Implementation and Evaluation

1 EM algorithm: updating the mixing proportions {π k } ik are the posterior probabilities at the qth iteration of EM.

Linear algebra for computational statistics

Geometric Image Manipulation

1 Curvature of submanifolds of Euclidean space

Position & motion in 2D and 3D

CSE 252B: Computer Vision II

Structure from Motion. Read Chapter 7 in Szeliski s book

Probabilistic & Unsupervised Learning

Linear Algebra & Geometry why is linear algebra useful in computer vision?

Vision 3D articielle Session 2: Essential and fundamental matrices, their computation, RANSAC algorithm

Kadath: a spectral solver and its application to black hole spacetimes

Inverse Theory. COST WaVaCS Winterschool Venice, February Stefan Buehler Luleå University of Technology Kiruna

Matrix Derivatives and Descent Optimization Methods

Class Averaging in Cryo-Electron Microscopy

Feature Tracking. 2/27/12 ECEn 631

Trust-region methods for rectangular systems of nonlinear equations

A geometric interpretation of the homogeneous coordinates is given in the following Figure.

Basic Math for

Single view metrology

Computational Methods. Least Squares Approximation/Optimization

Lecture 2: Linear Algebra Review

Parallel Scientific Computing

April 26, Applied mathematics PhD candidate, physics MA UC Berkeley. Lecture 4/26/2013. Jed Duersch. Spd matrices. Cholesky decomposition

Lecture 8: Interest Point Detection. Saad J Bedros

Finite Difference Methods (FDMs) 1

Advanced Machine Learning & Perception

Convex Optimization Algorithms for Machine Learning in 10 Slides

Inverse Problems, Information Content and Stratospheric Aerosols

Programming, numerics and optimization

Solving Linear Systems of Equations

Chapter 2: Matrix Algebra

Multivariate Statistical Analysis

Introduction to Machine Learning

Numerical Linear Algebra. Computer Labs

Learning strategies for neuronal nets - the backpropagation algorithm

Optimization 2. CS5240 Theoretical Foundations in Multimedia. Leow Wee Kheng

Affine invariant Fourier descriptors

Chapter 3 Numerical Methods

Vasil Khalidov & Miles Hansard. C.M. Bishop s PRML: Chapter 5; Neural Networks

SUPPLEMENTARY INFORMATION

Transcription:

Theory of Bouguet s MatLab Camera Calibration Toolbox Yuji Oyamada 1 HVRL, University 2 Chair for Computer Aided Medical Procedure (CAMP) Technische Universität München June 26, 2012

MatLab Camera Calibration Toolbox Calibration using a planar calibration object. Points correspondence requires manual click on object s corners. Core calibration part is fully automatic. C implementation is included in OpenCV. Web

Functions Extract grid corners: Points correspondence Calibration: Core calibration Show Extrinsic: Visualization of estimated extrinsic parameters Reproject on images: Visualization of reprojection error Analyse error: Recomp. corners: Recompute the corners using estimated parameters

Input: Extract grid corners n sq {x,y}: Number of square along {x,y} axis d{x,y}: Size of square in m unit. I: Input image Output: {x i}, i = 1,..., N: Set of detected 2D points. {X i}, i = 1,..., N: Set of known 3D points. where x i and X i have M i elements as [ ] x i(1) x i(j) x i(mi ) x i = and y i(1) y i(j) y i(m i ) X i(1) X i(j) X i(m i ) X i = Y i(1) Y i(j) Y i(m i ) Z i(1) Z i(j) Z i(m i )

Calibration Input: {x i}: Set of detected 2D points. {X i}: Set of known 3D points. Output: Intrinsic parameters Extrinsic parameters Method: 1. Initialize intrinsic and extrinsic params. 2. Non-linear optimization to refine all parameters.

Camera parameters Intrinsic parameters: fc R 2 : Camera focal length cc R 2 : Principal point coordinates alpha c R 1 : Skew coefficient kc R 5 : Distortion coefficients KK R 3 3 : The camera matrix (containing fc, cc, alpha c) Extrinsic parameters for i-th image: omc i R 3 : Rotation angles Tc i R 3 : Translation vectors Rc i R 3 3 : Rotation matrix computed as Rc i = rodrigues(omc i)

Initialization 1/2: Intrinsic parameters Input {x i}: Set of detected 2D points. {X i}: Set of known 3D points. Output Initialized intrinsic parameters Initialized extrinsic parameters

Initialization 1/2: Intrinsic parameters 1. Roughly compute intrinsic params. 2. Refine intrinsic params. 3. Compute extrinsic params. Step1: fc: Computed based on all the vanishing points. cc: Center of image. alpha c = 0. kc = 0.

Initialization 1/2: Intrinsic parameters Step2: Given N sets of corresponding points {x k, X k }, 1. Compute Homography {H k }. 2. Build linear equations Vb = 0 and solve the equations Detail. 3. Compute A from estimated b. v 1,12 (v 1,11 v 1,22 ) v k,12 V (v k,11 v k,22 ) v N,12 (v N,11 v N,22 ) v k,ij = [h k,i1 h k,j1, h k,i1 h k,j2 + h k,i2 h k,j1, h k,i2 h k,j2, h k,i3 h k,j1 + h k,i1 h k,j3, h k,i3 h k,j2 + h k,i2 h k,j3, h k,i3 h k,j3 ]

Initialization 2/2: Extrinsic parameters Step3: Compute each extrinsic parameters from estimated A and pre-computed H k as where λ k = r k,1 = λ k A 1 h k,1 r k,2 = λ k A 1 h k,2 r k,3 = r k,1 r k,2 t k = λ k A 1 h k,3 1 A 1 h k,1 = 1 A 1 h k,2

Solves the following equations: Non-linear optimization ˆp = arg min p x f (p) 2 2 where p = {fc, cc, alpha c, kc, {omc i}, {Tc i}} and the function f projects the known 3D points X onto 2D image plane with the argument p. Sparse Levenberg-Marquardt algorithm iteratively updates ˆp with an initial estimate ˆp 0 as while( x f (ˆp i 1 ) 2 2 > ɛ) ˆp i = ˆp i 1 + p i ; i = i + 1;

Given Image projection x p = (x p, y p, 1) : Pixel coordinate of a point on the image plane. x d = (x d, y d, 1) : Normalized coordinate distorted by lens. x n = (x n, y n, 1) : Normalized pinhole image projection. k R 5 : Lens distortion parameters. KK R 3 3 : Camera calibration matrix. where fc(1) alpha c(1) cc(1) KK = 0 fc(2) cc(2) 0 0 1 x p = KKx d = KK(cdistx n + delta x)

Given Lens distortion x n = x: Normalized pinhole image projection. k R 5 : Lens distortion parameters. Compute x d = xd: Normalized coordinate distorted by lens. cdist: Radial distortion delta x: Tangential distortion xd = cdist x + delta x [ ] cdist x + delta x(1) = cdist y + delta x(2)

Radial distortion where xd1 = [ ] x cdist y cdist cdist = 1 + k(1) r2 + k(2) r4 + k(5) r6 r2 = x 2 i + y 2 i, r4 = r2 2, r6 = r2 3

Tangential distortion where delta x = [ ] k(3) a1 + k(4) a2 k(3) a3 + k(4) a1 a1 = 2x i y i a2 = r2 + 2x 2 i a3 = r2 + 2y 2 i

Closed form solution for initialization X u s v = A [ r 1 r 2 r 3 t ] Y 0 = A [ r 1 r 2 t ] X Y 1 1 1 X = H Y 1 Since r 1 and r 2 are orthonormal, we have following two constraints: h 1 A A 1 h 2 = 0 h 1 A A 1 h 1 = h 2 A A 1 h 2, where A A 1 describes the image of the absolute conic.

Closed form solution for initialization Let B 11 B 21 B 31 B = A A 1 B 12 B 22 B 32 B 13 B 23 B 33 = 1 α 2 γ α 2 β γ α 2 β v 0 γ u 0 β α 2 β γ 2 + 1 γ(v 0γ u 0 β) v α 2 β 2 β 2 α 2 β 2 0 β 2 v 0 γ u 0 β α 2 β γ(v 0γ u 0 β) α 2 β 2 v 0 β 2 (v 0 γ u 0 β) 2 α 2 β 2 + v 2 0 β 2 + 1 Note that B is symmetric, defined by a 6D vector b [ B 11, B 12, B 22, B 13, B 23, B 3 ]

Closed form solution for initialization Let the i-th column vector of H be h i = [ h i1, h i2, h i3 ]. Then, we have following linear equation where h i Bh j = v ij b v ij = [h i1 h j1, h i1 h j2 + h i2 h j1, h i2 h j2 h i3 h j1 + h i1 h j3, h i3 h j2 + h i2 h j3, h i3 h j3 ]

Closed form solution for initialization The above two constraints can be rewritten as two homogeneous equation w.r.t. unknown b as [ v ] 12 (v 11 v 22 ) b = 0 Given n images, we have Vb = 0, where V R 2n 6.

Least Squares Let f ( ) a function projecting 3D points X onto 2D points x with projection parameters p as bmx = f (p) = px. Our task is to find an optimal p such that minimizes x px 2 2. In the case of non-linear function f ( ), we iteratively update the estimate ˆp with an initial estimate ˆp 0 as while( x px 2 2 > ɛ) ˆp i = ˆp i 1 + p i ; i = i + 1;

Least Squares: Newton s method Given a previous estimate ˆp i, estimate an update i s.t. i = arg min f (ˆp i + ) X 2 2 = arg min f (ˆp i) + J X 2 2 = arg min ɛ i + J 2 2 where J = f p. Then, solve the normal equations J J = J ɛ i

Levenberg-Marquardt (LM) iteration The normal equation is replaced by the augmented normal equations as J J = J ɛ i (J J + λi) = J ɛ i where I denotes the identity matrix. An initial value of λ is 10 3 times the average of the diagonal elements of N = J J.

Sparse LM LM is suitable for minimization w.r.t. a small number of parameters. The central step of LM, solving the normal equations, has complexity N 3 in the number of parameters and is repeated many times. The normal equation matrix has a certain sparse block structure.

Sparse LM Let p R M be the parameter vector that is able to be partitioned into parameter vectors as p = (a, b ). Given a measurement vector x R N Let x be the covariance matrix for the measurement vector. A general function f : R M R N takes p to the estimated measurement vector ˆx = f (p). ɛ denotes the difference x ˆx between the measured and the estimated vectors.

Sparse LM The set of equations Jδ = ɛ solved as the central step in the LM has the form ( ) δa Jδ = [A B] = ɛ. Then, the normal equations J 1 x at each step of LM are of the form [ A 1 x A A ] 1 ( ) ( x B B 1 x A B δa 1 = x B δ b δ b Jδ = J 1 x ɛ to be solved A 1 x B 1 x ) ɛ ɛ

Let Sparse LM U = A 1 x A W = A 1 x B V = B 1 x B and denotes augmented matrix by λ. The normal equations are rewritten as [ U ] ( ) ( ) W δa ɛa = W V δ b ɛ B [ U WV 1 W ] ( ) ( 0 δa ɛa WV 1 ) ɛ = B W This results in the elimination of the top right hand block. V δ b ɛ B

Sparse LM The top half of this set of equations is (U WV 1 W )δ a = ɛ A WV 1 ɛ B Subsequently, the value of δ a may be found by back-substitution, giving V δ b = ɛ B W δ a

Sparse LM p = (a, b ), where a = (fc, cc, alpha c, kc ) and b = ({omc i Tc i }) The Jacobian matrix is where [ ˆx ˆx a = ˆx b = [ fc, ˆx cc, ˆx omc 1, J = ˆx p = ˆx alpha c, ˆx ] kc ˆx Tc 1,, [ ˆx a, ˆx ] = [A, B] b ˆx omc i ˆx Tc i, ˆx omc N ] ˆx Tc N

Sparse LM The normal equation is rewritten as ([ ] ) [ ] A [A ] A B + λi p = ɛ x B N A i A i i=1 N B i A i i=1 N i=1 N i=1 B A i B i [ B + λi A ] ɛ p = x B ɛ x i B i

Sparse LM J J = N A i A i A 1 B 1 A i B i A N B N i=1 B 1 A 1 B 1 B 1. B i A i. B N A N... B i B i... B N B N

Sparse LM J ɛ x = N A i ɛ x i=1 B 1 ɛ x. B i ɛ x. B N ɛ x

Sparse LM When each image has different number of corresponding points (M i M j, if i j), each A i and B i have different size as

Sparse LM However, the difference does not matter because A A R d int d int A B R d int d ex B A R dex d int B B R dex dex where d int denotes dimension of intrinsic params and d ex denotes dimension of extrinsic params.