-
Notifications
You must be signed in to change notification settings - Fork 16
/
mrcal.c
6885 lines (6053 loc) · 296 KB
/
mrcal.c
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
// Copyright (c) 2017-2023 California Institute of Technology ("Caltech"). U.S.
// Government sponsorship acknowledged. All rights reserved.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
// Apparently I need this in MSVC to get constants
#define _USE_MATH_DEFINES
#include <stdio.h>
#include <stdlib.h>
#include <inttypes.h>
#include <dogleg.h>
#include <assert.h>
#include <stdbool.h>
#include <math.h>
#include <string.h>
#include "mrcal.h"
#include "minimath/minimath.h"
#include "cahvore.h"
#include "minimath/minimath-extra.h"
#include "util.h"
#include "scales.h"
#define MSG_IF_VERBOSE(...) do { if(verbose) MSG( __VA_ARGS__ ); } while(0)
// Returns a static string, using "..." as a placeholder for any configuration
// values
#define LENSMODEL_PRINT_CFG_ELEMENT_TEMPLATE(name, type, pybuildvaluecode, PRIcode,SCNcode, bitfield, cookie) \
"_" #name "=..."
#define LENSMODEL_PRINT_CFG_ELEMENT_FMT(name, type, pybuildvaluecode, PRIcode,SCNcode, bitfield, cookie) \
"_" #name "=%" PRIcode
#define LENSMODEL_PRINT_CFG_ELEMENT_VAR(name, type, pybuildvaluecode, PRIcode,SCNcode, bitfield, cookie) \
,config->name
#define LENSMODEL_SCAN_CFG_ELEMENT_FMT(name, type, pybuildvaluecode, PRIcode,SCNcode, bitfield, cookie) \
"_" #name "=%" SCNcode
#define LENSMODEL_SCAN_CFG_ELEMENT_VAR(name, type, pybuildvaluecode, PRIcode,SCNcode, bitfield, cookie) \
,&config->name
#define LENSMODEL_SCAN_CFG_ELEMENT_PLUS1(name, type, pybuildvaluecode, PRIcode,SCNcode, bitfield, cookie) \
+1
const char* mrcal_lensmodel_name_unconfigured( const mrcal_lensmodel_t* lensmodel )
{
switch(lensmodel->type)
{
#define CASE_STRING_NOCONFIG(s,n) case MRCAL_##s: ; \
return #s;
#define _CASE_STRING_WITHCONFIG(s,n,s_CONFIG_LIST) case MRCAL_##s: ; \
return #s s_CONFIG_LIST(LENSMODEL_PRINT_CFG_ELEMENT_TEMPLATE, );
#define CASE_STRING_WITHCONFIG(s,n) _CASE_STRING_WITHCONFIG(s,n,MRCAL_ ## s ## _CONFIG_LIST)
MRCAL_LENSMODEL_NOCONFIG_LIST( CASE_STRING_NOCONFIG )
MRCAL_LENSMODEL_WITHCONFIG_STATIC_NPARAMS_LIST( CASE_STRING_WITHCONFIG )
MRCAL_LENSMODEL_WITHCONFIG_DYNAMIC_NPARAMS_LIST( CASE_STRING_WITHCONFIG )
default:
return NULL;
#undef CASE_STRING_NOCONFIG
#undef CASE_STRING_WITHCONFIG
}
return NULL;
}
// Write the model name WITH the full config into the given buffer. Identical to
// mrcal_lensmodel_name_unconfigured() for configuration-free models
static int LENSMODEL_CAHVORE__snprintf_model
(char* out, int size,
const mrcal_LENSMODEL_CAHVORE__config_t* config)
{
return
snprintf( out, size, "LENSMODEL_CAHVORE"
MRCAL_LENSMODEL_CAHVORE_CONFIG_LIST(LENSMODEL_PRINT_CFG_ELEMENT_FMT, )
MRCAL_LENSMODEL_CAHVORE_CONFIG_LIST(LENSMODEL_PRINT_CFG_ELEMENT_VAR, ));
}
static int LENSMODEL_SPLINED_STEREOGRAPHIC__snprintf_model
(char* out, int size,
const mrcal_LENSMODEL_SPLINED_STEREOGRAPHIC__config_t* config)
{
return
snprintf( out, size, "LENSMODEL_SPLINED_STEREOGRAPHIC"
MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC_CONFIG_LIST(LENSMODEL_PRINT_CFG_ELEMENT_FMT, )
MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC_CONFIG_LIST(LENSMODEL_PRINT_CFG_ELEMENT_VAR, ));
}
bool mrcal_lensmodel_name( char* out, int size, const mrcal_lensmodel_t* lensmodel )
{
switch(lensmodel->type)
{
#define CASE_STRING_NOCONFIG(s,n) case MRCAL_##s: \
return size > snprintf(out,size, #s);
#define CASE_STRING_WITHCONFIG(s,n) case MRCAL_##s: \
return size > s##__snprintf_model(out, size, &lensmodel->s##__config);
MRCAL_LENSMODEL_NOCONFIG_LIST( CASE_STRING_NOCONFIG )
MRCAL_LENSMODEL_WITHCONFIG_STATIC_NPARAMS_LIST( CASE_STRING_WITHCONFIG )
MRCAL_LENSMODEL_WITHCONFIG_DYNAMIC_NPARAMS_LIST( CASE_STRING_WITHCONFIG )
default:
return NULL;
#undef CASE_STRING_NOCONFIG
#undef CASE_STRING_WITHCONFIG
}
return NULL;
}
static bool LENSMODEL_CAHVORE__scan_model_config( mrcal_LENSMODEL_CAHVORE__config_t* config, const char* config_str)
{
int pos;
int Nelements = 0 MRCAL_LENSMODEL_CAHVORE_CONFIG_LIST(LENSMODEL_SCAN_CFG_ELEMENT_PLUS1, );
return
Nelements ==
sscanf( config_str,
MRCAL_LENSMODEL_CAHVORE_CONFIG_LIST(LENSMODEL_SCAN_CFG_ELEMENT_FMT, )"%n"
MRCAL_LENSMODEL_CAHVORE_CONFIG_LIST(LENSMODEL_SCAN_CFG_ELEMENT_VAR, ),
&pos) &&
config_str[pos] == '\0';
}
static bool LENSMODEL_SPLINED_STEREOGRAPHIC__scan_model_config( mrcal_LENSMODEL_SPLINED_STEREOGRAPHIC__config_t* config, const char* config_str)
{
int pos;
int Nelements = 0 MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC_CONFIG_LIST(LENSMODEL_SCAN_CFG_ELEMENT_PLUS1, );
return
Nelements ==
sscanf( config_str,
MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC_CONFIG_LIST(LENSMODEL_SCAN_CFG_ELEMENT_FMT, )"%n"
MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC_CONFIG_LIST(LENSMODEL_SCAN_CFG_ELEMENT_VAR, ),
&pos) &&
config_str[pos] == '\0';
}
const char* const* mrcal_supported_lensmodel_names( void )
{
#define NAMESTRING_NOCONFIG(s,n) #s,
#define _NAMESTRING_WITHCONFIG(s,n,s_CONFIG_LIST) #s s_CONFIG_LIST(LENSMODEL_PRINT_CFG_ELEMENT_TEMPLATE, ),
#define NAMESTRING_WITHCONFIG(s,n) _NAMESTRING_WITHCONFIG(s,n,MRCAL_ ## s ## _CONFIG_LIST)
static const char* names[] = {
MRCAL_LENSMODEL_NOCONFIG_LIST( NAMESTRING_NOCONFIG)
MRCAL_LENSMODEL_WITHCONFIG_STATIC_NPARAMS_LIST( NAMESTRING_WITHCONFIG)
MRCAL_LENSMODEL_WITHCONFIG_DYNAMIC_NPARAMS_LIST(NAMESTRING_WITHCONFIG)
NULL };
return names;
}
#undef LENSMODEL_PRINT_CFG_ELEMENT_TEMPLATE
#undef LENSMODEL_PRINT_CFG_ELEMENT_FMT
#undef LENSMODEL_PRINT_CFG_ELEMENT_VAR
#undef LENSMODEL_SCAN_CFG_ELEMENT_FMT
#undef LENSMODEL_SCAN_CFG_ELEMENT_VAR
#undef LENSMODEL_SCAN_CFG_ELEMENT_PLUS1
// parses the model name AND the configuration into a mrcal_lensmodel_t structure.
// On error returns false with lensmodel->type set to MRCAL_LENSMODEL_INVALID_...
bool mrcal_lensmodel_from_name( // output
mrcal_lensmodel_t* lensmodel,
// input
const char* name )
{
#define CHECK_AND_RETURN_NOCONFIG(s,n) \
if( 0 == strcmp( name, #s) ) \
{ \
*lensmodel = (mrcal_lensmodel_t){.type = MRCAL_##s}; \
return true; \
}
#define CHECK_AND_RETURN_WITHCONFIG(s,n) \
/* Configured model. I need to extract the config from the string. */ \
/* The string format is NAME_cfg1=var1_cfg2=var2... */ \
{ \
const int len_s = strlen(#s); \
if( 0 == strncmp( name, #s, len_s ) ) \
{ \
if(name[len_s] == '\0') \
{ \
*lensmodel = (mrcal_lensmodel_t){.type = MRCAL_LENSMODEL_INVALID_MISSINGCONFIG}; \
return false; \
} \
if(name[len_s] == '_') \
{ \
/* found name. Now extract the config */ \
*lensmodel = (mrcal_lensmodel_t){.type = MRCAL_##s}; \
mrcal_##s##__config_t* config = &lensmodel->s##__config; \
\
const char* config_str = &name[len_s]; \
\
if(s##__scan_model_config(config, config_str)) \
return true; \
\
*lensmodel = (mrcal_lensmodel_t){.type = MRCAL_LENSMODEL_INVALID_BADCONFIG}; \
return false; \
} \
} \
}
if(name == NULL)
{
*lensmodel = (mrcal_lensmodel_t){.type = MRCAL_LENSMODEL_INVALID_TYPE};
return false;
}
MRCAL_LENSMODEL_NOCONFIG_LIST( CHECK_AND_RETURN_NOCONFIG );
MRCAL_LENSMODEL_WITHCONFIG_STATIC_NPARAMS_LIST( CHECK_AND_RETURN_WITHCONFIG );
MRCAL_LENSMODEL_WITHCONFIG_DYNAMIC_NPARAMS_LIST( CHECK_AND_RETURN_WITHCONFIG );
*lensmodel = (mrcal_lensmodel_t){.type = MRCAL_LENSMODEL_INVALID_TYPE};
return false;
#undef CHECK_AND_RETURN_NOCONFIG
#undef CHECK_AND_RETURN_WITHCONFIG
}
// parses the model name only. The configuration is ignored. Even if it's
// missing or unparseable. Unknown model names return
// MRCAL_LENSMODEL_INVALID_TYPE
mrcal_lensmodel_type_t mrcal_lensmodel_type_from_name( const char* name )
{
#define CHECK_AND_RETURN_NOCONFIG(s,n) \
if( 0 == strcmp( name, #s) ) return MRCAL_##s;
#define CHECK_AND_RETURN_WITHCONFIG(s,n) \
/* Configured model. If the name is followed by _ or nothing, I */ \
/* accept this model */ \
{ \
const int len_s = strlen(#s); \
if( 0 == strncmp( name, #s, len_s) && \
( name[len_s] == '\0' || \
name[len_s] == '_' ) ) \
return MRCAL_##s; \
}
if(name == NULL)
return MRCAL_LENSMODEL_INVALID_TYPE;
MRCAL_LENSMODEL_NOCONFIG_LIST( CHECK_AND_RETURN_NOCONFIG );
MRCAL_LENSMODEL_WITHCONFIG_STATIC_NPARAMS_LIST( CHECK_AND_RETURN_WITHCONFIG );
MRCAL_LENSMODEL_WITHCONFIG_DYNAMIC_NPARAMS_LIST( CHECK_AND_RETURN_WITHCONFIG );
return MRCAL_LENSMODEL_INVALID_TYPE;
#undef CHECK_AND_RETURN_NOCONFIG
#undef CHECK_AND_RETURN_WITHCONFIG
}
mrcal_lensmodel_metadata_t mrcal_lensmodel_metadata( const mrcal_lensmodel_t* lensmodel )
{
switch(lensmodel->type)
{
case MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC:
case MRCAL_LENSMODEL_STEREOGRAPHIC:
case MRCAL_LENSMODEL_LONLAT:
case MRCAL_LENSMODEL_LATLON:
return (mrcal_lensmodel_metadata_t) { .has_core = true,
.can_project_behind_camera = true,
.has_gradients = true,
.noncentral = false};
case MRCAL_LENSMODEL_PINHOLE:
case MRCAL_LENSMODEL_OPENCV4:
case MRCAL_LENSMODEL_OPENCV5:
case MRCAL_LENSMODEL_OPENCV8:
case MRCAL_LENSMODEL_OPENCV12:
case MRCAL_LENSMODEL_CAHVOR:
return (mrcal_lensmodel_metadata_t) { .has_core = true,
.can_project_behind_camera = false,
.has_gradients = true,
.noncentral = false };
case MRCAL_LENSMODEL_CAHVORE:
return (mrcal_lensmodel_metadata_t) { .has_core = true,
.can_project_behind_camera = false,
.has_gradients = true,
.noncentral = true };
default: ;
}
MSG("Unknown lens model %d. Barfing out", lensmodel->type);
assert(0);
}
static
bool modelHasCore_fxfycxcy( const mrcal_lensmodel_t* lensmodel )
{
mrcal_lensmodel_metadata_t meta = mrcal_lensmodel_metadata(lensmodel);
return meta.has_core;
}
static
bool model_supports_projection_behind_camera( const mrcal_lensmodel_t* lensmodel )
{
mrcal_lensmodel_metadata_t meta = mrcal_lensmodel_metadata(lensmodel);
return meta.can_project_behind_camera;
}
static int LENSMODEL_SPLINED_STEREOGRAPHIC__lensmodel_num_params(const mrcal_LENSMODEL_SPLINED_STEREOGRAPHIC__config_t* config)
{
return
// I have two surfaces: one for x and another for y
(int)config->Nx * (int)config->Ny * 2 +
// and I have a core
4;
}
int mrcal_lensmodel_num_params(const mrcal_lensmodel_t* lensmodel)
{
#define CHECK_CONFIG_NPARAM_NOCONFIG(s,n) \
_Static_assert(n >= 0, "no-config implies known-at-compile-time param count");
switch(lensmodel->type)
{
#define CASE_NUM_STATIC(s,n) \
case MRCAL_##s: return n;
#define CASE_NUM_DYNAMIC(s,n) \
case MRCAL_##s: return s##__lensmodel_num_params(&lensmodel->s##__config);
MRCAL_LENSMODEL_NOCONFIG_LIST( CASE_NUM_STATIC )
MRCAL_LENSMODEL_WITHCONFIG_STATIC_NPARAMS_LIST( CASE_NUM_STATIC )
MRCAL_LENSMODEL_WITHCONFIG_DYNAMIC_NPARAMS_LIST( CASE_NUM_DYNAMIC )
default: ;
}
return -1;
#undef CASE_NUM_NOCONFIG
#undef CASE_NUM_WITHCONFIG
}
static
int get_num_distortions_optimization_params(mrcal_problem_selections_t problem_selections,
const mrcal_lensmodel_t* lensmodel)
{
if( !problem_selections.do_optimize_intrinsics_distortions )
return 0;
int N = mrcal_lensmodel_num_params(lensmodel);
if(modelHasCore_fxfycxcy(lensmodel))
N -= 4; // ignoring fx,fy,cx,cy
return N;
}
int mrcal_num_intrinsics_optimization_params(mrcal_problem_selections_t problem_selections,
const mrcal_lensmodel_t* lensmodel)
{
int N = get_num_distortions_optimization_params(problem_selections, lensmodel);
if( problem_selections.do_optimize_intrinsics_core &&
modelHasCore_fxfycxcy(lensmodel) )
N += 4; // fx,fy,cx,cy
return N;
}
int mrcal_num_states(int Ncameras_intrinsics, int Ncameras_extrinsics,
int Nframes,
int Npoints, int Npoints_fixed, int Nobservations_board,
mrcal_problem_selections_t problem_selections,
const mrcal_lensmodel_t* lensmodel)
{
return
mrcal_num_states_intrinsics(Ncameras_intrinsics,
problem_selections,
lensmodel) +
mrcal_num_states_extrinsics(Ncameras_extrinsics,
problem_selections) +
mrcal_num_states_frames(Nframes,
problem_selections) +
mrcal_num_states_points(Npoints, Npoints_fixed,
problem_selections) +
mrcal_num_states_calobject_warp( problem_selections,
Nobservations_board);
}
static int num_regularization_terms_percamera(mrcal_problem_selections_t problem_selections,
const mrcal_lensmodel_t* lensmodel)
{
if(!problem_selections.do_apply_regularization)
return 0;
// distortions
int N = get_num_distortions_optimization_params(problem_selections, lensmodel);
// optical center
if(problem_selections.do_optimize_intrinsics_core)
N += 2;
return N;
}
int mrcal_measurement_index_boards(int i_observation_board,
int Nobservations_board,
int Nobservations_point,
int calibration_object_width_n,
int calibration_object_height_n)
{
if(Nobservations_board <= 0)
return -1;
// *2 because I have separate x and y measurements
return
0 +
mrcal_num_measurements_boards(i_observation_board,
calibration_object_width_n,
calibration_object_height_n);
}
int mrcal_num_measurements_boards(int Nobservations_board,
int calibration_object_width_n,
int calibration_object_height_n)
{
if(Nobservations_board <= 0)
return 0;
// *2 because I have separate x and y measurements
return
Nobservations_board *
calibration_object_width_n*calibration_object_height_n *
2;
return mrcal_measurement_index_boards( Nobservations_board,
0,0,
calibration_object_width_n,
calibration_object_height_n);
}
int mrcal_measurement_index_points(int i_observation_point,
int Nobservations_board,
int Nobservations_point,
int calibration_object_width_n,
int calibration_object_height_n)
{
if(Nobservations_point <= 0)
return -1;
// 2: x,y measurements
return
mrcal_num_measurements_boards(Nobservations_board,
calibration_object_width_n,
calibration_object_height_n) +
i_observation_point * 2;
}
#if defined ENABLE_TRIANGULATED_WARNINGS && ENABLE_TRIANGULATED_WARNINGS
#warning "triangulated-solve: need known-range points, at-infinity points"
#endif
int mrcal_num_measurements_points(int Nobservations_point)
{
// 2: x,y measurements
return Nobservations_point * 2;
}
#if defined ENABLE_TRIANGULATED_WARNINGS && ENABLE_TRIANGULATED_WARNINGS
#warning "triangulated-solve: Add a test for mrcal_measurement_index_points_triangulated()"
#endif
int mrcal_measurement_index_points_triangulated(int i_point_triangulated,
int Nobservations_board,
int Nobservations_point,
// May be NULL if we don't have any of these
const mrcal_observation_point_triangulated_t* observations_point_triangulated,
int Nobservations_point_triangulated,
int calibration_object_width_n,
int calibration_object_height_n)
{
if(observations_point_triangulated == NULL ||
Nobservations_point_triangulated <= 0)
return -1;
return
mrcal_num_measurements_boards(Nobservations_board,
calibration_object_width_n,
calibration_object_height_n) +
mrcal_num_measurements_points(Nobservations_point) +
mrcal_num_measurements_points_triangulated_initial_Npoints(observations_point_triangulated,
Nobservations_point_triangulated,
i_point_triangulated);
}
#if defined ENABLE_TRIANGULATED_WARNINGS && ENABLE_TRIANGULATED_WARNINGS
#warning "triangulated-solve: python-wrap this function"
#endif
int mrcal_num_measurements_points_triangulated_initial_Npoints(// May be NULL if we don't have any of these
const mrcal_observation_point_triangulated_t* observations_point_triangulated,
int Nobservations_point_triangulated,
// Only consider the leading Npoints. If Npoints < 0: take ALL the points
int Npoints)
{
if(observations_point_triangulated == NULL ||
Nobservations_point_triangulated <= 0)
return 0;
// Similar loop as in _mrcal_num_j_nonzero(). If the data layout changes,
// update this and that
int Nmeas = 0;
int ipoint = 0;
int iobservation = 0;
while( iobservation < Nobservations_point_triangulated &&
(Npoints < 0 || ipoint < Npoints))
{
int Nset = 1;
while(!observations_point_triangulated[iobservation].last_in_set)
{
Nmeas += Nset++;
iobservation++;
}
ipoint++;
iobservation++;
}
return Nmeas;
}
int mrcal_num_measurements_points_triangulated(// May be NULL if we don't have any of these
const mrcal_observation_point_triangulated_t* observations_point_triangulated,
int Nobservations_point_triangulated)
{
return
mrcal_num_measurements_points_triangulated_initial_Npoints( observations_point_triangulated,
Nobservations_point_triangulated,
-1 );
}
#if defined ENABLE_TRIANGULATED_WARNINGS && ENABLE_TRIANGULATED_WARNINGS
#warning "triangulated-solve: python-wrap this function"
#endif
bool mrcal_decode_observation_indices_points_triangulated(
// output
int* iobservation0,
int* iobservation1,
int* iobservation_point0,
int* Nobservations_this_point,
int* Nmeasurements_this_point,
int* ipoint,
// input
const int imeasurement,
const mrcal_observation_point_triangulated_t* observations_point_triangulated,
int Nobservations_point_triangulated)
{
if(observations_point_triangulated == NULL ||
Nobservations_point_triangulated <= 0)
return false;
// Similar loop as in
// mrcal_num_measurements_points_triangulated_initial_Npoints(). If the data
// layout changes, update this and that
int Nmeas = 0;
int iobservation = 0;
*ipoint = 0;
while( iobservation < Nobservations_point_triangulated )
{
int Nset = 1;
while(!observations_point_triangulated[iobservation].last_in_set)
{
Nset++;
iobservation++;
}
// This point has Nset observations. Each pair of observations produces
// a measurement, so:
const int Nmeas_thispoint = Nset*(Nset-1) / 2;
// Done with this point. It is described by Nmeas_thispoint
// measurements, with the first one at Nmeas. The last observation is at
// iobservation
if(imeasurement < Nmeas+Nmeas_thispoint)
{
// The measurement I care about observes THIS point. I find the
// specific observations.
//
// I simplify the notation: "m" is "imeasurement", "o" is
// "iobservation".
const int No = Nset;
const int Nm = Nmeas_thispoint;
const int m = imeasurement - Nmeas;
// Within this point o is in range(No) and m is in range(Nm). A pair
// (o0,o1) describes one measurement. Both o0 and o1 are in
// range(No) and o1>o0. A sample table of measurement indices m for
// No = 5:
//
// o1
// 0 1 2 3 4
// ---------
// 0| 0 1 2 3
// o0 1| 4 5 6
// 2| 7 8
// 3| 9
// 4|
//
// For a given o0, the maximum m =
//
// m_max = (No-1) + (No-2) + (No-3) ... - 1
//
// for a total of o0+1 (No...) terms so
//
// m_max = ((No-1) + (No-o0-1))/2 * (o0+1) - 1
// = (2*No - 2 - o0)/2 * (o0+1) - 1
//
// m_min = m_max(o0-1) + 1
// = (2*No - 2 - o0 + 1)/2 * o0
// = (2*No - 1 - o0) * o0 / 2
// = (-o0^2 + (2*No - 1)*o0 ) / 2
//
// -> (-1/2) o0^2 + (2*No - 1)/2 o0 - m_min = 0
// -> o0 = (2*No - 1)/2 +- sqrt( (2*No - 1)^2/4 - 2*m_min)
// = (2*No - 1)/2 - sqrt( (2*No - 1)^2/4 - 2*m_min)
// = (2*No - 1 - sqrt( (2*No - 1)^2 - 8*m_min))/2
//
// o0(m) = floor(o0(m))
//
// Now that I have o0 I compute
//
// o1 = m - m_min(o0) + o0 + 1
// = m - (-o0^2 + (2*No - 1)*o0 ) / 2 + o0 + 1
// = m + (o0^2 + (3- 2*No)*o0 + 2) / 2
// = m + o0*(o0 + 3 - 2*No)/2 + 1
const double x = 2.*(double)No - 1.;
*iobservation0 = (int)((x - sqrt( x*x - 8.*(double)m))/2.);
*iobservation1 = m + (*iobservation0)*((*iobservation0) + 3 - 2*No)/2 + 1;
// Reference the observations from the first
*iobservation_point0 = iobservation-Nset+1;
*iobservation0 += *iobservation_point0;
*iobservation1 += *iobservation_point0;
*Nobservations_this_point = No;
*Nmeasurements_this_point = Nm;
return true;
}
Nmeas += Nmeas_thispoint;
iobservation++;
(*ipoint)++;
}
return false;
}
int mrcal_measurement_index_regularization(
#if defined ENABLE_TRIANGULATED_WARNINGS && ENABLE_TRIANGULATED_WARNINGS
#warning "triangulated-solve: this argument order is weird. Put then triangulated stuff at the end?"
#endif
// May be NULL if we don't have any of these
const mrcal_observation_point_triangulated_t* observations_point_triangulated,
int Nobservations_point_triangulated,
int calibration_object_width_n,
int calibration_object_height_n,
int Ncameras_intrinsics, int Ncameras_extrinsics,
int Nframes,
int Npoints, int Npoints_fixed, int Nobservations_board, int Nobservations_point,
mrcal_problem_selections_t problem_selections,
const mrcal_lensmodel_t* lensmodel)
{
if(mrcal_num_measurements_regularization(Ncameras_intrinsics, Ncameras_extrinsics,
Nframes,
Npoints, Npoints_fixed, Nobservations_board,
problem_selections,
lensmodel) <= 0)
return -1;
return
mrcal_num_measurements_boards(Nobservations_board,
calibration_object_width_n,
calibration_object_height_n) +
mrcal_num_measurements_points(Nobservations_point) +
mrcal_num_measurements_points_triangulated(observations_point_triangulated,
Nobservations_point_triangulated);
}
int mrcal_num_measurements_regularization(int Ncameras_intrinsics, int Ncameras_extrinsics,
int Nframes,
int Npoints, int Npoints_fixed, int Nobservations_board,
mrcal_problem_selections_t problem_selections,
const mrcal_lensmodel_t* lensmodel)
{
return
Ncameras_intrinsics *
num_regularization_terms_percamera(problem_selections, lensmodel) +
((problem_selections.do_apply_regularization_unity_cam01 &&
problem_selections.do_optimize_extrinsics &&
Ncameras_extrinsics > 0) ? 1 : 0);
}
int mrcal_num_measurements(int Nobservations_board,
int Nobservations_point,
// May be NULL if we don't have any of these
const mrcal_observation_point_triangulated_t* observations_point_triangulated,
int Nobservations_point_triangulated,
int calibration_object_width_n,
int calibration_object_height_n,
int Ncameras_intrinsics, int Ncameras_extrinsics,
int Nframes,
int Npoints, int Npoints_fixed,
mrcal_problem_selections_t problem_selections,
const mrcal_lensmodel_t* lensmodel)
{
return
mrcal_num_measurements_boards( Nobservations_board,
calibration_object_width_n,
calibration_object_height_n) +
mrcal_num_measurements_points(Nobservations_point) +
mrcal_num_measurements_points_triangulated(observations_point_triangulated,
Nobservations_point_triangulated) +
mrcal_num_measurements_regularization(Ncameras_intrinsics, Ncameras_extrinsics,
Nframes,
Npoints, Npoints_fixed, Nobservations_board,
problem_selections,
lensmodel);
}
static bool has_calobject_warp(mrcal_problem_selections_t problem_selections,
int Nobservations_board)
{
return problem_selections.do_optimize_calobject_warp && Nobservations_board>0;
}
int _mrcal_num_j_nonzero(int Nobservations_board,
int Nobservations_point,
// May be NULL if we don't have any of these
const mrcal_observation_point_triangulated_t* observations_point_triangulated,
int Nobservations_point_triangulated,
int calibration_object_width_n,
int calibration_object_height_n,
int Ncameras_intrinsics, int Ncameras_extrinsics,
int Nframes,
int Npoints, int Npoints_fixed,
const mrcal_observation_board_t* observations_board,
const mrcal_observation_point_t* observations_point,
mrcal_problem_selections_t problem_selections,
const mrcal_lensmodel_t* lensmodel)
{
// each observation depends on all the parameters for THAT frame and for
// THAT camera. Camera0 doesn't have extrinsics, so I need to loop through
// all my observations
// Each projected point has an x and y measurement, and each one depends on
// some number of the intrinsic parameters. Parametric models are simple:
// each one depends on ALL of the intrinsics. Splined models are sparse,
// however, and there's only a partial dependence
int Nintrinsics_per_measurement;
if(lensmodel->type == MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC)
{
int run_len =
lensmodel->LENSMODEL_SPLINED_STEREOGRAPHIC__config.order + 1;
Nintrinsics_per_measurement =
(problem_selections.do_optimize_intrinsics_core ? 4 : 0) +
(problem_selections.do_optimize_intrinsics_distortions ? (run_len*run_len) : 0);
}
else
Nintrinsics_per_measurement =
mrcal_num_intrinsics_optimization_params(problem_selections, lensmodel);
// x depends on fx,cx but NOT on fy, cy. And similarly for y.
if( problem_selections.do_optimize_intrinsics_core &&
modelHasCore_fxfycxcy(lensmodel) )
Nintrinsics_per_measurement -= 2;
int N = Nobservations_board * ( (problem_selections.do_optimize_frames ? 6 : 0) +
(problem_selections.do_optimize_extrinsics ? 6 : 0) +
(has_calobject_warp(problem_selections,Nobservations_board) ? MRCAL_NSTATE_CALOBJECT_WARP : 0) +
Nintrinsics_per_measurement );
// initial estimate counts extrinsics for the reference camera, which need
// to be subtracted off
if(problem_selections.do_optimize_extrinsics)
for(int i=0; i<Nobservations_board; i++)
if(observations_board[i].icam.extrinsics < 0)
N -= 6;
// *2 because I have separate x and y measurements
N *= 2*calibration_object_width_n*calibration_object_height_n;
// Now the point observations
for(int i=0; i<Nobservations_point; i++)
{
N += 2*Nintrinsics_per_measurement;
if( problem_selections.do_optimize_frames &&
observations_point[i].i_point < Npoints-Npoints_fixed )
N += 2*3;
if( problem_selections.do_optimize_extrinsics &&
observations_point[i].icam.extrinsics >= 0 )
N += 2*6;
}
// And the triangulated point observations
if(observations_point_triangulated != NULL &&
Nobservations_point_triangulated > 0)
{
// Similar loop as in
// mrcal_num_measurements_points_triangulated_initial_Npoints(). If the
// data layout changes, update this and that
for(int i0=0; i0<Nobservations_point_triangulated; i0++)
{
if(observations_point_triangulated[i0].last_in_set)
continue;
int Nvars0 = Nintrinsics_per_measurement;
if( problem_selections.do_optimize_extrinsics &&
observations_point_triangulated[i0].icam.extrinsics >= 0 )
Nvars0 += 6;
int i1 = i0;
do
{
i1++;
int Nvars1 = Nintrinsics_per_measurement;
if( problem_selections.do_optimize_extrinsics &&
observations_point_triangulated[i1].icam.extrinsics >= 0 )
Nvars1 += 6;
N += Nvars0 + Nvars1;
} while(!observations_point_triangulated[i1].last_in_set);
}
}
// Regularization
if(lensmodel->type == MRCAL_LENSMODEL_SPLINED_STEREOGRAPHIC)
{
if(problem_selections.do_apply_regularization)
{
// Each regularization term depends on
// - two values for distortions
// - one value for the center pixel
N +=
Ncameras_intrinsics *
2 *
num_regularization_terms_percamera(problem_selections,
lensmodel);
// I multiplied by 2, so I double-counted the center pixel
// contributions. Subtract those off
if(problem_selections.do_optimize_intrinsics_core)
N -= Ncameras_intrinsics*2;
}
}
else
N +=
Ncameras_intrinsics *
num_regularization_terms_percamera(problem_selections,
lensmodel);
if(problem_selections.do_apply_regularization_unity_cam01 &&
problem_selections.do_optimize_extrinsics &&
Ncameras_extrinsics > 0)
{
#if defined ENABLE_TRIANGULATED_WARNINGS && ENABLE_TRIANGULATED_WARNINGS
#warning "triangulated-solve: I assume that camera0 is at the reference"
#endif
N += 3; // translation only
}
return N;
}
// Used in the spline-based projection function.
//
// See bsplines.py for the derivation of the spline expressions and for
// justification of the 2D scheme
//
// Here we sample two interpolated surfaces at once: one each for the x and y
// focal-length scales
//
// The sampling function assumes evenly spaced knots.
// a,b,c,d are sequential control points
// x is in [0,1] between b and c. Function looks like this:
// double A = fA(x);
// double B = fB(x);
// double C = fC(x);
// double D = fD(x);
// return A*a + B*b + C*c + D*d;
// I need to sample many such 1D segments, so I compute A,B,C,D separately,
// and apply them together
static
void get_sample_coeffs__cubic(double* ABCD, double* ABCDgrad, double x)
{
double x2 = x*x;
double x3 = x2*x;
ABCD[0] = (-x3 + 3*x2 - 3*x + 1)/6;
ABCD[1] = (3 * x3/2 - 3*x2 + 2)/3;
ABCD[2] = (-3 * x3 + 3*x2 + 3*x + 1)/6;
ABCD[3] = x3 / 6;
ABCDgrad[0] = -x2/2 + x - 1./2.;
ABCDgrad[1] = 3*x2/2 - 2*x;
ABCDgrad[2] = -3*x2/2 + x + 1./2.;
ABCDgrad[3] = x2 / 2;
}
static
void interp__cubic(double* out, const double* ABCDx, const double* ABCDy,
// control points
const double* c,
int stridey)
{
double cinterp[4][2];
const int stridex = 2;
for(int iy=0; iy<4; iy++)
for(int k=0;k<2;k++)
cinterp[iy][k] =
ABCDx[0] * c[iy*stridey + 0*stridex + k] +
ABCDx[1] * c[iy*stridey + 1*stridex + k] +
ABCDx[2] * c[iy*stridey + 2*stridex + k] +
ABCDx[3] * c[iy*stridey + 3*stridex + k];
for(int k=0;k<2;k++)
out[k] =
ABCDy[0] * cinterp[0][k] +
ABCDy[1] * cinterp[1][k] +
ABCDy[2] * cinterp[2][k] +
ABCDy[3] * cinterp[3][k];
}
static
void sample_bspline_surface_cubic(double* out,
double* dout_dx,
double* dout_dy,
double* ABCDx_ABCDy,
double x, double y,
// control points
const double* c,
int stridey
// stridex is 2: the control points from the
// two surfaces are next to each other. Better
// cache locality maybe
)
{
double* ABCDx = &ABCDx_ABCDy[0];
double* ABCDy = &ABCDx_ABCDy[4];
// 4 samples along one dimension, and then one sample along the other
// dimension, using the 4 samples as the control points. Order doesn't
// matter. See bsplines.py
//
// I do this twice: one for each focal length surface
double ABCDgradx[4];
double ABCDgrady[4];
get_sample_coeffs__cubic(ABCDx, ABCDgradx, x);
get_sample_coeffs__cubic(ABCDy, ABCDgrady, y);
// the intrinsics gradient is flatten(ABCDx[0..3] * ABCDy[0..3]) for both x
// and y. By returning ABCD[xy] and not the cartesian products, I make
// smaller temporary data arrays
interp__cubic(out, ABCDx, ABCDy, c, stridey);
interp__cubic(dout_dx, ABCDgradx, ABCDy, c, stridey);
interp__cubic(dout_dy, ABCDx, ABCDgrady, c, stridey);
}
// The sampling function assumes evenly spaced knots.
// a,b,c are sequential control points
// x is in [-1/2,1/2] around b. Function looks like this:
// double A = fA(x);
// double B = fB(x);
// double C = fC(x);
// return A*a + B*b + C*c;
// I need to sample many such 1D segments, so I compute A,B,C separately,
// and apply them together
static
void get_sample_coeffs__quadratic(double* ABC, double* ABCgrad, double x)
{
double x2 = x*x;
ABC[0] = (4*x2 - 4*x + 1)/8;
ABC[1] = (3 - 4*x2)/4;
ABC[2] = (4*x2 + 4*x + 1)/8;
ABCgrad[0] = x - 1./2.;
ABCgrad[1] = -2.*x;
ABCgrad[2] = x + 1./2.;
}
static
void interp__quadratic(double* out, const double* ABCx, const double* ABCy,
// control points
const double* c,
int stridey)