-
Notifications
You must be signed in to change notification settings - Fork 1.5k
/
camera_models.h
executable file
·1519 lines (1286 loc) · 48.2 KB
/
camera_models.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
// COLMAP - Structure-from-Motion and Multi-View Stereo.
// Copyright (C) 2017 Johannes L. Schoenberger <jsch at inf.ethz.ch>
//
// This program is free software: you can redistribute it and/or modify
// it under the terms of the GNU General Public License as published by
// the Free Software Foundation, either version 3 of the License, or
// (at your option) any later version.
//
// This program is distributed in the hope that it will be useful,
// but WITHOUT ANY WARRANTY; without even the implied warranty of
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
// GNU General Public License for more details.
//
// You should have received a copy of the GNU General Public License
// along with this program. If not, see <http://www.gnu.org/licenses/>.
#ifndef COLMAP_SRC_BASE_CAMERA_MODELS_H_
#define COLMAP_SRC_BASE_CAMERA_MODELS_H_
#include <cfloat>
#include <string>
#include <vector>
#include <Eigen/Core>
#include <Eigen/Dense>
#include <ceres/jet.h>
namespace colmap {
// This file defines several different camera models and arbitrary new camera
// models can be added by the following steps:
//
// 1. Add a new struct in this file which implements all the necessary methods.
// 2. Define an unique model_name and model_id for the camera model.
// 3. Add camera model to `CAMERA_MODEL_CASES` macro in this file.
// 4. Add new template specialization of test case for camera model to
// `camera_models_test.cc`.
//
// A camera model can have three different types of camera parameters: focal
// length, principal point, extra parameters (distortion parameters). The
// parameter array is split into different groups, so that we can enable or
// disable the refinement of the individual groups during bundle adjustment. It
// is up to the camera model to access the parameters correctly (it is free to
// do so in an arbitrary manner) - the parameters are not accessed from outside.
//
// A camera model must have the following methods:
//
// - `WorldToImage`: transform normalized camera coordinates to image
// coordinates (the inverse of `ImageToWorld`). Assumes that the world
// coordinates are given as (u, v, 1).
// - `ImageToWorld`: transform image coordinates to normalized camera
// coordinates (the inverse of `WorldToImage`). Produces world coordinates
// as (u, v, 1).
// - `ImageToWorldThreshold`: transform a threshold given in pixels to
// normalized units (e.g. useful for reprojection error thresholds).
//
// Whenever you specify the camera parameters in a list, they must appear
// exactly in the order as they are accessed in the defined model struct.
//
// The camera models follow the convention that the upper left image corner has
// the coordinate (0, 0), the lower right corner (width, height), i.e. that
// the upper left pixel center has coordinate (0.5, 0.5) and the lower right
// pixel center has the coordinate (width - 0.5, height - 0.5).
static const int kInvalidCameraModelId = -1;
#ifndef CAMERA_MODEL_DEFINITIONS
#define CAMERA_MODEL_DEFINITIONS(model_id_value, model_name_value, \
num_params_value) \
static const int kModelId = model_id_value; \
static const size_t kNumParams = num_params_value; \
static const int model_id; \
static const std::string model_name; \
static const size_t num_params; \
static const std::string params_info; \
static const std::vector<size_t> focal_length_idxs; \
static const std::vector<size_t> principal_point_idxs; \
static const std::vector<size_t> extra_params_idxs; \
\
static inline int InitializeModelId() { return model_id_value; }; \
static inline std::string InitializeModelName() { \
return model_name_value; \
}; \
static inline size_t InitializeNumParams() { return num_params_value; }; \
static inline std::string InitializeParamsInfo(); \
static inline std::vector<size_t> InitializeFocalLengthIdxs(); \
static inline std::vector<size_t> InitializePrincipalPointIdxs(); \
static inline std::vector<size_t> InitializeExtraParamsIdxs(); \
static inline std::vector<double> InitializeParams( \
const double focal_length, const size_t width, const size_t height); \
\
template <typename T> \
static void WorldToImage(const T* params, const T u, const T v, T* x, T* y); \
template <typename T> \
static void ImageToWorld(const T* params, const T x, const T y, T* u, T* v); \
template <typename T> \
static void Distortion(const T* extra_params, const T u, const T v, T* du, \
T* dv);
#endif
#ifndef CAMERA_MODEL_CASES
#define CAMERA_MODEL_CASES \
CAMERA_MODEL_CASE(SimplePinholeCameraModel) \
CAMERA_MODEL_CASE(PinholeCameraModel) \
CAMERA_MODEL_CASE(SimpleRadialCameraModel) \
CAMERA_MODEL_CASE(SimpleRadialFisheyeCameraModel) \
CAMERA_MODEL_CASE(RadialCameraModel) \
CAMERA_MODEL_CASE(RadialFisheyeCameraModel) \
CAMERA_MODEL_CASE(OpenCVCameraModel) \
CAMERA_MODEL_CASE(OpenCVFisheyeCameraModel) \
CAMERA_MODEL_CASE(FullOpenCVCameraModel) \
CAMERA_MODEL_CASE(FOVCameraModel) \
CAMERA_MODEL_CASE(ThinPrismFisheyeCameraModel)
#endif
#ifndef CAMERA_MODEL_SWITCH_CASES
#define CAMERA_MODEL_SWITCH_CASES \
CAMERA_MODEL_CASES \
default: \
CAMERA_MODEL_DOES_NOT_EXIST_EXCEPTION \
break;
#endif
#define CAMERA_MODEL_DOES_NOT_EXIST_EXCEPTION \
throw std::domain_error("Camera model does not exist");
// The "Curiously Recurring Template Pattern" (CRTP) is used here, so that we
// can reuse some shared functionality between all camera models -
// defined in the BaseCameraModel.
template <typename CameraModel>
struct BaseCameraModel {
template <typename T>
static inline bool HasBogusParams(const std::vector<T>& params,
const size_t width, const size_t height,
const T min_focal_length_ratio,
const T max_focal_length_ratio,
const T max_extra_param);
template <typename T>
static inline bool HasBogusFocalLength(const std::vector<T>& params,
const size_t width,
const size_t height,
const T min_focal_length_ratio,
const T max_focal_length_ratio);
template <typename T>
static inline bool HasBogusPrincipalPoint(const std::vector<T>& params,
const size_t width,
const size_t height);
template <typename T>
static inline bool HasBogusExtraParams(const std::vector<T>& params,
const T max_extra_param);
template <typename T>
static inline T ImageToWorldThreshold(const T* params, const T threshold);
template <typename T>
static inline void IterativeUndistortion(const T* params, T* u, T* v);
};
// Simple Pinhole camera model.
//
// No Distortion is assumed. Only focal length and principal point is modeled.
//
// Parameter list is expected in the following order:
//
// f, cx, cy
//
// See https://en.wikipedia.org/wiki/Pinhole_camera_model
struct SimplePinholeCameraModel
: public BaseCameraModel<SimplePinholeCameraModel> {
CAMERA_MODEL_DEFINITIONS(0, "SIMPLE_PINHOLE", 3)
};
// Pinhole camera model.
//
// No Distortion is assumed. Only focal length and principal point is modeled.
//
// Parameter list is expected in the following order:
//
// fx, fy, cx, cy
//
// See https://en.wikipedia.org/wiki/Pinhole_camera_model
struct PinholeCameraModel : public BaseCameraModel<PinholeCameraModel> {
CAMERA_MODEL_DEFINITIONS(1, "PINHOLE", 4)
};
// Simple camera model with one focal length and one radial distortion
// parameter.
//
// This model is similar to the camera model that VisualSfM uses with the
// difference that the distortion here is applied to the projections and
// not to the measurements.
//
// Parameter list is expected in the following order:
//
// f, cx, cy, k
//
struct SimpleRadialCameraModel
: public BaseCameraModel<SimpleRadialCameraModel> {
CAMERA_MODEL_DEFINITIONS(2, "SIMPLE_RADIAL", 4)
};
// Simple camera model with one focal length and two radial distortion
// parameters.
//
// This model is equivalent to the camera model that Bundler uses
// (except for an inverse z-axis in the camera coordinate system).
//
// Parameter list is expected in the following order:
//
// f, cx, cy, k1, k2
//
struct RadialCameraModel : public BaseCameraModel<RadialCameraModel> {
CAMERA_MODEL_DEFINITIONS(3, "RADIAL", 5)
};
// OpenCV camera model.
//
// Based on the pinhole camera model. Additionally models radial and
// tangential distortion (up to 2nd degree of coefficients). Not suitable for
// large radial distortions of fish-eye cameras.
//
// Parameter list is expected in the following order:
//
// fx, fy, cx, cy, k1, k2, p1, p2
//
// See
// http://docs.opencv.org/modules/calib3d/doc/camera_calibration_and_3d_reconstruction.html
struct OpenCVCameraModel : public BaseCameraModel<OpenCVCameraModel> {
CAMERA_MODEL_DEFINITIONS(4, "OPENCV", 8)
};
// OpenCV fish-eye camera model.
//
// Based on the pinhole camera model. Additionally models radial and
// tangential Distortion (up to 2nd degree of coefficients). Suitable for
// large radial distortions of fish-eye cameras.
//
// Parameter list is expected in the following order:
//
// fx, fy, cx, cy, k1, k2, k3, k4
//
// See
// http://docs.opencv.org/modules/calib3d/doc/camera_calibration_and_3d_reconstruction.html
struct OpenCVFisheyeCameraModel
: public BaseCameraModel<OpenCVFisheyeCameraModel> {
CAMERA_MODEL_DEFINITIONS(5, "OPENCV_FISHEYE", 8)
};
// Full OpenCV camera model.
//
// Based on the pinhole camera model. Additionally models radial and
// tangential Distortion.
//
// Parameter list is expected in the following order:
//
// fx, fy, cx, cy, k1, k2, p1, p2, k3, k4, k5, k6
//
// See
// http://docs.opencv.org/modules/calib3d/doc/camera_calibration_and_3d_reconstruction.html
struct FullOpenCVCameraModel : public BaseCameraModel<FullOpenCVCameraModel> {
CAMERA_MODEL_DEFINITIONS(6, "FULL_OPENCV", 12)
};
// FOV camera model.
//
// Based on the pinhole camera model. Additionally models radial distortion.
// This model is for example used by Project Tango for its equidistant
// calibration type.
//
// Parameter list is expected in the following order:
//
// fx, fy, cx, cy, omega
//
// See:
// Frederic Devernay, Olivier Faugeras. Straight lines have to be straight:
// Automatic calibration and removal of distortion from scenes of structured
// environments. Machine vision and applications, 2001.
struct FOVCameraModel : public BaseCameraModel<FOVCameraModel> {
CAMERA_MODEL_DEFINITIONS(7, "FOV", 5)
template <typename T>
static void Undistortion(const T* extra_params, const T u, const T v, T* du,
T* dv);
};
// Simple camera model with one focal length and one radial distortion
// parameter, suitable for fish-eye cameras.
//
// This model is equivalent to the OpenCVFisheyeCameraModel but has only one
// radial distortion coefficient.
//
// Parameter list is expected in the following order:
//
// f, cx, cy, k
//
struct SimpleRadialFisheyeCameraModel
: public BaseCameraModel<SimpleRadialFisheyeCameraModel> {
CAMERA_MODEL_DEFINITIONS(8, "SIMPLE_RADIAL_FISHEYE", 4)
};
// Simple camera model with one focal length and two radial distortion
// parameters, suitable for fish-eye cameras.
//
// This model is equivalent to the OpenCVFisheyeCameraModel but has only two
// radial distortion coefficients.
//
// Parameter list is expected in the following order:
//
// f, cx, cy, k1, k2
//
struct RadialFisheyeCameraModel
: public BaseCameraModel<RadialFisheyeCameraModel> {
CAMERA_MODEL_DEFINITIONS(9, "RADIAL_FISHEYE", 5)
};
// Camera model with radial and tangential distortion coefficients and
// additional coefficients accounting for thin-prism distortion.
//
// This camera model is described in
//
// "Camera Calibration with Distortion Models and Accuracy Evaluation",
// J Weng et al., TPAMI, 1992.
//
// Parameter list is expected in the following order:
//
// fx, fy, cx, cy, k1, k2, p1, p2, k3, k4, sx1, sy1
//
struct ThinPrismFisheyeCameraModel
: public BaseCameraModel<ThinPrismFisheyeCameraModel> {
CAMERA_MODEL_DEFINITIONS(10, "THIN_PRISM_FISHEYE", 12)
};
// Check whether camera model with given name or identifier exists.
bool ExistsCameraModelWithName(const std::string& model_name);
bool ExistsCameraModelWithId(const int model_id);
// Convert camera name to unique camera model identifier.
//
// @param name Unique name of camera model.
//
// @return Unique identifier of camera model.
int CameraModelNameToId(const std::string& model_name);
// Convert camera model identifier to unique camera model name.
//
// @param model_id Unique identifier of camera model.
//
// @return Unique name of camera model.
std::string CameraModelIdToName(const int model_id);
// Initialize camera parameters using given image properties.
//
// Initializes all focal length parameters to the same given focal length and
// sets the principal point to the image center.
//
// @param model_id Unique identifier of camera model.
// @param focal_length Focal length, equal for all focal length parameters.
// @param width Sensor width of the camera.
// @param height Sensor height of the camera.
std::vector<double> CameraModelInitializeParams(const int model_id,
const double focal_length,
const size_t width,
const size_t height);
// Get human-readable information about the parameter vector order.
//
// @param model_id Unique identifier of camera model.
std::string CameraModelParamsInfo(const int model_id);
// Get the indices of the parameter groups in the parameter vector.
//
// @param model_id Unique identifier of camera model.
const std::vector<size_t>& CameraModelFocalLengthIdxs(const int model_id);
const std::vector<size_t>& CameraModelPrincipalPointIdxs(const int model_id);
const std::vector<size_t>& CameraModelExtraParamsIdxs(const int model_id);
// Get the total number of parameters of a camera model.
size_t CameraModelNumParams(const int model_id);
// Check whether parameters are valid, i.e. the parameter vector has
// the correct dimensions that match the specified camera model.
//
// @param model_id Unique identifier of camera model.
// @param params Array of camera parameters.
bool CameraModelVerifyParams(const int model_id,
const std::vector<double>& params);
// Check whether camera has bogus parameters.
//
// @param model_id Unique identifier of camera model.
// @param params Array of camera parameters.
// @param width Sensor width of the camera.
// @param height Sensor height of the camera.
// @param min_focal_length_ratio Minimum ratio of focal length over
// maximum sensor dimension.
// @param min_focal_length_ratio Maximum ratio of focal length over
// maximum sensor dimension.
// @param max_extra_param Maximum magnitude of each extra parameter.
bool CameraModelHasBogusParams(const int model_id,
const std::vector<double>& params,
const size_t width, const size_t height,
const double min_focal_length_ratio,
const double max_focal_length_ratio,
const double max_extra_param);
// Transform world coordinates in camera coordinate system to image coordinates.
//
// This is the inverse of `CameraModelImageToWorld`.
//
// @param model_id Unique model_id of camera model as defined in
// `CAMERA_MODEL_NAME_TO_CODE`.
// @param params Array of camera parameters.
// @param u, v Coordinates in camera system as (u, v, 1).
// @param x, y Output image coordinates in pixels.
inline void CameraModelWorldToImage(const int model_id,
const std::vector<double>& params,
const double u, const double v, double* x,
double* y);
// Transform image coordinates to world coordinates in camera coordinate system.
//
// This is the inverse of `CameraModelWorldToImage`.
//
// @param model_id Unique identifier of camera model.
// @param params Array of camera parameters.
// @param x, y Image coordinates in pixels.
// @param v, u Output Coordinates in camera system as (u, v, 1).
inline void CameraModelImageToWorld(const int model_id,
const std::vector<double>& params,
const double x, const double y, double* u,
double* v);
// Convert pixel threshold in image plane to world space by dividing
// the threshold through the mean focal length.
//
// @param model_id Unique identifier of camera model.
// @param params Array of camera parameters.
// @param threshold Image space threshold in pixels.
//
// @ return World space threshold.
inline double CameraModelImageToWorldThreshold(
const int model_id, const std::vector<double>& params,
const double threshold);
////////////////////////////////////////////////////////////////////////////////
// Implementation
////////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////////////////
// BaseCameraModel
template <typename CameraModel>
template <typename T>
bool BaseCameraModel<CameraModel>::HasBogusParams(
const std::vector<T>& params, const size_t width, const size_t height,
const T min_focal_length_ratio, const T max_focal_length_ratio,
const T max_extra_param) {
if (HasBogusPrincipalPoint(params, width, height)) {
return true;
}
if (HasBogusFocalLength(params, width, height, min_focal_length_ratio,
max_focal_length_ratio)) {
return true;
}
if (HasBogusExtraParams(params, max_extra_param)) {
return true;
}
return false;
}
template <typename CameraModel>
template <typename T>
bool BaseCameraModel<CameraModel>::HasBogusFocalLength(
const std::vector<T>& params, const size_t width, const size_t height,
const T min_focal_length_ratio, const T max_focal_length_ratio) {
const size_t max_size = std::max(width, height);
for (const auto& idx : CameraModel::focal_length_idxs) {
const T focal_length_ratio = params[idx] / max_size;
if (focal_length_ratio < min_focal_length_ratio ||
focal_length_ratio > max_focal_length_ratio) {
return true;
}
}
return false;
}
template <typename CameraModel>
template <typename T>
bool BaseCameraModel<CameraModel>::HasBogusPrincipalPoint(
const std::vector<T>& params, const size_t width, const size_t height) {
const T cx = params[CameraModel::principal_point_idxs[0]];
const T cy = params[CameraModel::principal_point_idxs[1]];
return cx < 0 || cx > width || cy < 0 || cy > height;
}
template <typename CameraModel>
template <typename T>
bool BaseCameraModel<CameraModel>::HasBogusExtraParams(
const std::vector<T>& params, const T max_extra_param) {
for (const auto& idx : CameraModel::extra_params_idxs) {
if (std::abs(params[idx]) > max_extra_param) {
return true;
}
}
return false;
}
template <typename CameraModel>
template <typename T>
T BaseCameraModel<CameraModel>::ImageToWorldThreshold(const T* params,
const T threshold) {
T mean_focal_length = 0;
for (const auto& idx : CameraModel::focal_length_idxs) {
mean_focal_length += params[idx];
}
mean_focal_length /= CameraModel::focal_length_idxs.size();
return threshold / mean_focal_length;
}
template <typename CameraModel>
template <typename T>
void BaseCameraModel<CameraModel>::IterativeUndistortion(const T* params, T* u,
T* v) {
// Parameters for Newton iteration using numerical differentiation with
// central differences, 100 iterations should be enough even for complex
// camera models with higher order terms.
const size_t kNumIterations = 100;
const double kMaxStepNorm = 1e-10;
const double kRelStepSize = 1e-6;
Eigen::Matrix2d J;
const Eigen::Vector2d x0(*u, *v);
Eigen::Vector2d x(*u, *v);
Eigen::Vector2d dx;
Eigen::Vector2d dx_0b;
Eigen::Vector2d dx_0f;
Eigen::Vector2d dx_1b;
Eigen::Vector2d dx_1f;
for (size_t i = 0; i < kNumIterations; ++i) {
const double step0 = std::max(std::numeric_limits<double>::epsilon(),
std::abs(kRelStepSize * x(0)));
const double step1 = std::max(std::numeric_limits<double>::epsilon(),
std::abs(kRelStepSize * x(1)));
CameraModel::Distortion(params, x(0), x(1), &dx(0), &dx(1));
CameraModel::Distortion(params, x(0) - step0, x(1), &dx_0b(0), &dx_0b(1));
CameraModel::Distortion(params, x(0) + step0, x(1), &dx_0f(0), &dx_0f(1));
CameraModel::Distortion(params, x(0), x(1) - step1, &dx_1b(0), &dx_1b(1));
CameraModel::Distortion(params, x(0), x(1) + step1, &dx_1f(0), &dx_1f(1));
J(0, 0) = 1 + (dx_0f(0) - dx_0b(0)) / (2 * step0);
J(0, 1) = (dx_1f(0) - dx_1b(0)) / (2 * step1);
J(1, 0) = (dx_0f(1) - dx_0b(1)) / (2 * step0);
J(1, 1) = 1 + (dx_1f(1) - dx_1b(1)) / (2 * step1);
const Eigen::Vector2d step_x = J.inverse() * (x + dx - x0);
x -= step_x;
if (step_x.squaredNorm() < kMaxStepNorm) {
break;
}
}
*u = x(0);
*v = x(1);
}
////////////////////////////////////////////////////////////////////////////////
// SimplePinholeCameraModel
std::string SimplePinholeCameraModel::InitializeParamsInfo() {
return "f, cx, cy";
}
std::vector<size_t> SimplePinholeCameraModel::InitializeFocalLengthIdxs() {
return {0};
}
std::vector<size_t> SimplePinholeCameraModel::InitializePrincipalPointIdxs() {
return {1, 2};
}
std::vector<size_t> SimplePinholeCameraModel::InitializeExtraParamsIdxs() {
return {};
}
std::vector<double> SimplePinholeCameraModel::InitializeParams(
const double focal_length, const size_t width, const size_t height) {
return {focal_length, width / 2.0, height / 2.0};
}
template <typename T>
void SimplePinholeCameraModel::WorldToImage(const T* params, const T u,
const T v, T* x, T* y) {
const T f = params[0];
const T c1 = params[1];
const T c2 = params[2];
// No Distortion
// Transform to image coordinates
*x = f * u + c1;
*y = f * v + c2;
}
template <typename T>
void SimplePinholeCameraModel::ImageToWorld(const T* params, const T x,
const T y, T* u, T* v) {
const T f = params[0];
const T c1 = params[1];
const T c2 = params[2];
*u = (x - c1) / f;
*v = (y - c2) / f;
}
////////////////////////////////////////////////////////////////////////////////
// PinholeCameraModel
std::string PinholeCameraModel::InitializeParamsInfo() {
return "fx, fy, cx, cy";
}
std::vector<size_t> PinholeCameraModel::InitializeFocalLengthIdxs() {
return {0, 1};
}
std::vector<size_t> PinholeCameraModel::InitializePrincipalPointIdxs() {
return {2, 3};
}
std::vector<size_t> PinholeCameraModel::InitializeExtraParamsIdxs() {
return {};
}
std::vector<double> PinholeCameraModel::InitializeParams(
const double focal_length, const size_t width, const size_t height) {
return {focal_length, focal_length, width / 2.0, height / 2.0};
}
template <typename T>
void PinholeCameraModel::WorldToImage(const T* params, const T u, const T v,
T* x, T* y) {
const T f1 = params[0];
const T f2 = params[1];
const T c1 = params[2];
const T c2 = params[3];
// No Distortion
// Transform to image coordinates
*x = f1 * u + c1;
*y = f2 * v + c2;
}
template <typename T>
void PinholeCameraModel::ImageToWorld(const T* params, const T x, const T y,
T* u, T* v) {
const T f1 = params[0];
const T f2 = params[1];
const T c1 = params[2];
const T c2 = params[3];
*u = (x - c1) / f1;
*v = (y - c2) / f2;
}
////////////////////////////////////////////////////////////////////////////////
// SimpleRadialCameraModel
std::string SimpleRadialCameraModel::InitializeParamsInfo() {
return "f, cx, cy, k";
}
std::vector<size_t> SimpleRadialCameraModel::InitializeFocalLengthIdxs() {
return {0};
}
std::vector<size_t> SimpleRadialCameraModel::InitializePrincipalPointIdxs() {
return {1, 2};
}
std::vector<size_t> SimpleRadialCameraModel::InitializeExtraParamsIdxs() {
return {3};
}
std::vector<double> SimpleRadialCameraModel::InitializeParams(
const double focal_length, const size_t width, const size_t height) {
return {focal_length, width / 2.0, height / 2.0, 0};
}
template <typename T>
void SimpleRadialCameraModel::WorldToImage(const T* params, const T u,
const T v, T* x, T* y) {
const T f = params[0];
const T c1 = params[1];
const T c2 = params[2];
// Distortion
T du, dv;
Distortion(¶ms[3], u, v, &du, &dv);
*x = u + du;
*y = v + dv;
// Transform to image coordinates
*x = f * *x + c1;
*y = f * *y + c2;
}
template <typename T>
void SimpleRadialCameraModel::ImageToWorld(const T* params, const T x,
const T y, T* u, T* v) {
const T f = params[0];
const T c1 = params[1];
const T c2 = params[2];
// Lift points to normalized plane
*u = (x - c1) / f;
*v = (y - c2) / f;
IterativeUndistortion(¶ms[3], u, v);
}
template <typename T>
void SimpleRadialCameraModel::Distortion(const T* extra_params, const T u,
const T v, T* du, T* dv) {
const T k = extra_params[0];
const T u2 = u * u;
const T v2 = v * v;
const T r2 = u2 + v2;
const T radial = k * r2;
*du = u * radial;
*dv = v * radial;
}
////////////////////////////////////////////////////////////////////////////////
// RadialCameraModel
std::string RadialCameraModel::InitializeParamsInfo() {
return "f, cx, cy, k1, k2";
}
std::vector<size_t> RadialCameraModel::InitializeFocalLengthIdxs() {
return {0};
}
std::vector<size_t> RadialCameraModel::InitializePrincipalPointIdxs() {
return {1, 2};
}
std::vector<size_t> RadialCameraModel::InitializeExtraParamsIdxs() {
return {3, 4};
}
std::vector<double> RadialCameraModel::InitializeParams(
const double focal_length, const size_t width, const size_t height) {
return {focal_length, width / 2.0, height / 2.0, 0, 0};
}
template <typename T>
void RadialCameraModel::WorldToImage(const T* params, const T u, const T v,
T* x, T* y) {
const T f = params[0];
const T c1 = params[1];
const T c2 = params[2];
// Distortion
T du, dv;
Distortion(¶ms[3], u, v, &du, &dv);
*x = u + du;
*y = v + dv;
// Transform to image coordinates
*x = f * *x + c1;
*y = f * *y + c2;
}
template <typename T>
void RadialCameraModel::ImageToWorld(const T* params, const T x, const T y,
T* u, T* v) {
const T f = params[0];
const T c1 = params[1];
const T c2 = params[2];
// Lift points to normalized plane
*u = (x - c1) / f;
*v = (y - c2) / f;
IterativeUndistortion(¶ms[3], u, v);
}
template <typename T>
void RadialCameraModel::Distortion(const T* extra_params, const T u, const T v,
T* du, T* dv) {
const T k1 = extra_params[0];
const T k2 = extra_params[1];
const T u2 = u * u;
const T v2 = v * v;
const T r2 = u2 + v2;
const T radial = k1 * r2 + k2 * r2 * r2;
*du = u * radial;
*dv = v * radial;
}
////////////////////////////////////////////////////////////////////////////////
// OpenCVCameraModel
std::string OpenCVCameraModel::InitializeParamsInfo() {
return "fx, fy, cx, cy, k1, k2, p1, p2";
}
std::vector<size_t> OpenCVCameraModel::InitializeFocalLengthIdxs() {
return {0, 1};
}
std::vector<size_t> OpenCVCameraModel::InitializePrincipalPointIdxs() {
return {2, 3};
}
std::vector<size_t> OpenCVCameraModel::InitializeExtraParamsIdxs() {
return {4, 5, 6, 7};
}
std::vector<double> OpenCVCameraModel::InitializeParams(
const double focal_length, const size_t width, const size_t height) {
return {focal_length, focal_length, width / 2.0, height / 2.0, 0, 0, 0, 0};
}
template <typename T>
void OpenCVCameraModel::WorldToImage(const T* params, const T u, const T v,
T* x, T* y) {
const T f1 = params[0];
const T f2 = params[1];
const T c1 = params[2];
const T c2 = params[3];
// Distortion
T du, dv;
Distortion(¶ms[4], u, v, &du, &dv);
*x = u + du;
*y = v + dv;
// Transform to image coordinates
*x = f1 * *x + c1;
*y = f2 * *y + c2;
}
template <typename T>
void OpenCVCameraModel::ImageToWorld(const T* params, const T x, const T y,
T* u, T* v) {
const T f1 = params[0];
const T f2 = params[1];
const T c1 = params[2];
const T c2 = params[3];
// Lift points to normalized plane
*u = (x - c1) / f1;
*v = (y - c2) / f2;
IterativeUndistortion(¶ms[4], u, v);
}
template <typename T>
void OpenCVCameraModel::Distortion(const T* extra_params, const T u, const T v,
T* du, T* dv) {
const T k1 = extra_params[0];
const T k2 = extra_params[1];
const T p1 = extra_params[2];
const T p2 = extra_params[3];
const T u2 = u * u;
const T uv = u * v;
const T v2 = v * v;
const T r2 = u2 + v2;
const T radial = k1 * r2 + k2 * r2 * r2;
*du = u * radial + T(2) * p1 * uv + p2 * (r2 + T(2) * u2);
*dv = v * radial + T(2) * p2 * uv + p1 * (r2 + T(2) * v2);
}
////////////////////////////////////////////////////////////////////////////////
// OpenCVFisheyeCameraModel
std::string OpenCVFisheyeCameraModel::InitializeParamsInfo() {
return "fx, fy, cx, cy, k1, k2, k3, k4";
}
std::vector<size_t> OpenCVFisheyeCameraModel::InitializeFocalLengthIdxs() {
return {0, 1};
}
std::vector<size_t> OpenCVFisheyeCameraModel::InitializePrincipalPointIdxs() {
return {2, 3};
}
std::vector<size_t> OpenCVFisheyeCameraModel::InitializeExtraParamsIdxs() {
return {4, 5, 6, 7};
}
std::vector<double> OpenCVFisheyeCameraModel::InitializeParams(
const double focal_length, const size_t width, const size_t height) {
return {focal_length, focal_length, width / 2.0, height / 2.0, 0, 0, 0, 0};
}
template <typename T>
void OpenCVFisheyeCameraModel::WorldToImage(const T* params, const T u,
const T v, T* x, T* y) {
const T f1 = params[0];
const T f2 = params[1];
const T c1 = params[2];
const T c2 = params[3];
// Distortion
T du, dv;
Distortion(¶ms[4], u, v, &du, &dv);
*x = u + du;
*y = v + dv;
// Transform to image coordinates
*x = f1 * *x + c1;
*y = f2 * *y + c2;
}
template <typename T>
void OpenCVFisheyeCameraModel::ImageToWorld(const T* params, const T x,
const T y, T* u, T* v) {
const T f1 = params[0];
const T f2 = params[1];
const T c1 = params[2];
const T c2 = params[3];
// Lift points to normalized plane
*u = (x - c1) / f1;
*v = (y - c2) / f2;
IterativeUndistortion(¶ms[4], u, v);
}
template <typename T>
void OpenCVFisheyeCameraModel::Distortion(const T* extra_params, const T u,
const T v, T* du, T* dv) {
const T k1 = extra_params[0];
const T k2 = extra_params[1];
const T k3 = extra_params[2];
const T k4 = extra_params[3];
const T r = ceres::sqrt(u * u + v * v);
if (r > T(std::numeric_limits<double>::epsilon())) {
const T theta = ceres::atan(r);
const T theta2 = theta * theta;
const T theta4 = theta2 * theta2;
const T theta6 = theta4 * theta2;
const T theta8 = theta4 * theta4;
const T thetad =
theta * (T(1) + k1 * theta2 + k2 * theta4 + k3 * theta6 + k4 * theta8);
*du = u * thetad / r - u;
*dv = v * thetad / r - v;
} else {
*du = T(0);
*dv = T(0);
}
}
////////////////////////////////////////////////////////////////////////////////
// FullOpenCVCameraModel
std::string FullOpenCVCameraModel::InitializeParamsInfo() {
return "fx, fy, cx, cy, k1, k2, p1, p2, k3, k4, k5, k6";
}
std::vector<size_t> FullOpenCVCameraModel::InitializeFocalLengthIdxs() {
return {0, 1};
}
std::vector<size_t> FullOpenCVCameraModel::InitializePrincipalPointIdxs() {
return {2, 3};
}
std::vector<size_t> FullOpenCVCameraModel::InitializeExtraParamsIdxs() {
return {4, 5, 6, 7, 8, 9, 10, 11};
}
std::vector<double> FullOpenCVCameraModel::InitializeParams(
const double focal_length, const size_t width, const size_t height) {
return {focal_length,
focal_length,
width / 2.0,
height / 2.0,
0,
0,
0,