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
|
/////////////////////////////////////////////////////////////////////////////////
////
//// Simple drivers for sparse bundle adjustment based on the
//// Levenberg - Marquardt minimization algorithm
//// This file provides simple wrappers to the functions defined in sba_levmar.c
//// Copyright (C) 2004-2009 Manolis Lourakis (lourakis at ics forth gr)
//// Institute of Computer Science, Foundation for Research & Technology - Hellas
//// Heraklion, Crete, Greece.
////
//// 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 2 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.
////
///////////////////////////////////////////////////////////////////////////////////
#include <float.h>
#include <math.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include "sba.h"
#define FABS(x) (((x) >= 0) ? (x) : -(x))
struct wrap_motstr_data_ {
void (*proj)(int j, int i, double *aj, double *bi, double *xij, void *adata); // Q
void (*projac)(int j, int i, double *aj, double *bi, double *Aij, double *Bij, void *adata); // dQ/da, dQ/db
int cnp, pnp, mnp; /* parameter numbers */
void *adata;
};
struct wrap_mot_data_ {
void (*proj)(int j, int i, double *aj, double *xij, void *adata); // Q
void (*projac)(int j, int i, double *aj, double *Aij, void *adata); // dQ/da
int cnp, mnp; /* parameter numbers */
void *adata;
};
struct wrap_str_data_ {
void (*proj)(int j, int i, double *bi, double *xij, void *adata); // Q
void (*projac)(int j, int i, double *bi, double *Bij, void *adata); // dQ/db
int pnp, mnp; /* parameter numbers */
void *adata;
};
/* Routines to estimate the estimated measurement vector (i.e. "func") and
* its sparse jacobian (i.e. "fjac") needed by BA expert drivers. Code below
* makes use of user-supplied functions computing "Q", "dQ/da", d"Q/db",
* i.e. predicted projection and associated jacobians for a SINGLE image measurement.
* Notice also that what follows is two pairs of "func" and corresponding "fjac" routines.
* The first is to be used in full (i.e. motion + structure) BA, the second in
* motion only BA.
*/
/* FULL BUNDLE ADJUSTMENT */
/* Given a parameter vector p made up of the 3D coordinates of n points and the parameters of m cameras, compute in
* hx the prediction of the measurements, i.e. the projections of 3D points in the m images. The measurements
* are returned in the order (hx_11^T, .. hx_1m^T, ..., hx_n1^T, .. hx_nm^T)^T, where hx_ij is the predicted
* projection of the i-th point on the j-th camera.
* Caller supplies rcidxs and rcsubs which can be used as working memory.
* Notice that depending on idxij, some of the hx_ij might be missing
*
*/
static void sba_motstr_Qs(double *p, struct sba_crsm *idxij, int *rcidxs, int *rcsubs, double *hx, void *adata) {
register int i, j;
int cnp, pnp, mnp;
double *pa, *pb, *paj, *pbi, *pxij;
int n, m, nnz;
struct wrap_motstr_data_ *wdata;
void (*proj)(int j, int i, double *aj, double *bi, double *xij, void *proj_adata);
void *proj_adata;
wdata = (struct wrap_motstr_data_ *)adata;
cnp = wdata->cnp;
pnp = wdata->pnp;
mnp = wdata->mnp;
proj = wdata->proj;
proj_adata = wdata->adata;
n = idxij->nr;
m = idxij->nc;
pa = p;
pb = p + m * cnp;
for (j = 0; j < m; ++j) {
/* j-th camera parameters */
paj = pa + j * cnp;
nnz = sba_crsm_col_elmidxs(idxij, j, rcidxs, rcsubs); /* find nonzero hx_ij, i=0...n-1 */
for (i = 0; i < nnz; ++i) {
pbi = pb + rcsubs[i] * pnp;
pxij = hx + idxij->val[rcidxs[i]] * mnp; // set pxij to point to hx_ij
(*proj)(j, rcsubs[i], paj, pbi, pxij, proj_adata); // evaluate Q in pxij
}
}
}
/* Given a parameter vector p made up of the 3D coordinates of n points and the parameters of m cameras, compute in
* jac the jacobian of the predicted measurements, i.e. the jacobian of the projections of 3D points in the m images.
* The jacobian is returned in the order (A_11, B_11, ..., A_1m, B_1m, ..., A_n1, B_n1, ..., A_nm, B_nm),
* where A_ij=dx_ij/db_j and B_ij=dx_ij/db_i (see HZ).
* Caller supplies rcidxs and rcsubs which can be used as working memory.
* Notice that depending on idxij, some of the A_ij, B_ij might be missing
*
*/
static void sba_motstr_Qs_jac(double *p, struct sba_crsm *idxij, int *rcidxs, int *rcsubs, double *jac, void *adata) {
register int i, j;
int cnp, pnp, mnp;
double *pa, *pb, *paj, *pbi, *pAij, *pBij;
int n, m, nnz, Asz, Bsz, ABsz, idx;
struct wrap_motstr_data_ *wdata;
void (*projac)(int j, int i, double *aj, double *bi, double *Aij, double *Bij, void *projac_adata);
void *projac_adata;
wdata = (struct wrap_motstr_data_ *)adata;
cnp = wdata->cnp;
pnp = wdata->pnp;
mnp = wdata->mnp;
projac = wdata->projac;
projac_adata = wdata->adata;
n = idxij->nr;
m = idxij->nc;
pa = p;
pb = p + m * cnp;
Asz = mnp * cnp;
Bsz = mnp * pnp;
ABsz = Asz + Bsz;
for (j = 0; j < m; ++j) {
/* j-th camera parameters */
paj = pa + j * cnp;
nnz = sba_crsm_col_elmidxs(idxij, j, rcidxs, rcsubs); /* find nonzero hx_ij, i=0...n-1 */
for (i = 0; i < nnz; ++i) {
pbi = pb + rcsubs[i] * pnp;
idx = idxij->val[rcidxs[i]];
pAij = jac + idx * ABsz; // set pAij to point to A_ij
pBij = pAij + Asz; // set pBij to point to B_ij
(*projac)(j, rcsubs[i], paj, pbi, pAij, pBij, projac_adata); // evaluate dQ/da, dQ/db in pAij, pBij
}
}
}
/* Given a parameter vector p made up of the 3D coordinates of n points and the parameters of m cameras, compute in
* jac the jacobian of the predicted measurements, i.e. the jacobian of the projections of 3D points in the m images.
* The jacobian is approximated with the aid of finite differences and is returned in the order
* (A_11, B_11, ..., A_1m, B_1m, ..., A_n1, B_n1, ..., A_nm, B_nm),
* where A_ij=dx_ij/da_j and B_ij=dx_ij/db_i (see HZ).
* Notice that depending on idxij, some of the A_ij, B_ij might be missing
*
* Problem-specific information is assumed to be stored in a structure pointed to by "dat".
*
* NOTE: This function is provided mainly for illustration purposes; in case that execution time is a concern,
* the jacobian should be computed analytically
*/
static void sba_motstr_Qs_fdjac(
double *p, /* I: current parameter estimate, (m*cnp+n*pnp)x1 */
struct sba_crsm *idxij, /* I: sparse matrix containing the location of x_ij in hx */
int *rcidxs, /* work array for the indexes of nonzero elements of a single sparse matrix row/column */
int *rcsubs, /* work array for the subscripts of nonzero elements in a single sparse matrix row/column */
double *jac, /* O: array for storing the approximated jacobian */
void *dat) /* I: points to a "wrap_motstr_data_" structure */
{
register int i, j, ii, jj;
double *pa, *pb, *paj, *pbi;
register double *pAB;
int n, m, nnz, Asz, Bsz, ABsz;
double tmp;
register double d, d1;
struct wrap_motstr_data_ *fdjd;
void (*proj)(int j, int i, double *aj, double *bi, double *xij, void *adata);
double *hxij, *hxxij;
int cnp, pnp, mnp;
void *adata;
/* retrieve problem-specific information passed in *dat */
fdjd = (struct wrap_motstr_data_ *)dat;
proj = fdjd->proj;
cnp = fdjd->cnp;
pnp = fdjd->pnp;
mnp = fdjd->mnp;
adata = fdjd->adata;
n = idxij->nr;
m = idxij->nc;
pa = p;
pb = p + m * cnp;
Asz = mnp * cnp;
Bsz = mnp * pnp;
ABsz = Asz + Bsz;
/* allocate memory for hxij, hxxij */
if ((hxij = malloc(2 * mnp * sizeof(double))) == NULL) {
fprintf(stderr, "memory allocation request failed in sba_motstr_Qs_fdjac()!\n");
exit(1);
}
hxxij = hxij + mnp;
/* compute A_ij */
for (j = 0; j < m; ++j) {
paj = pa + j * cnp; // j-th camera parameters
nnz = sba_crsm_col_elmidxs(idxij, j, rcidxs, rcsubs); /* find nonzero A_ij, i=0...n-1 */
for (jj = 0; jj < cnp; ++jj) {
/* determine d=max(SBA_DELTA_SCALE*|paj[jj]|, SBA_MIN_DELTA), see HZ */
d = (double)(SBA_DELTA_SCALE)*paj[jj]; // force evaluation
d = FABS(d);
if (d < SBA_MIN_DELTA)
d = SBA_MIN_DELTA;
d1 = 1.0 / d; /* invert so that divisions can be carried out faster as multiplications */
for (i = 0; i < nnz; ++i) {
pbi = pb + rcsubs[i] * pnp; // i-th point parameters
(*proj)(j, rcsubs[i], paj, pbi, hxij, adata); // evaluate supplied function on current solution
tmp = paj[jj];
paj[jj] += d;
(*proj)(j, rcsubs[i], paj, pbi, hxxij, adata);
paj[jj] = tmp; /* restore */
pAB = jac + idxij->val[rcidxs[i]] * ABsz; // set pAB to point to A_ij
for (ii = 0; ii < mnp; ++ii)
pAB[ii * cnp + jj] = (hxxij[ii] - hxij[ii]) * d1;
}
}
}
/* compute B_ij */
for (i = 0; i < n; ++i) {
pbi = pb + i * pnp; // i-th point parameters
nnz = sba_crsm_row_elmidxs(idxij, i, rcidxs, rcsubs); /* find nonzero B_ij, j=0...m-1 */
for (jj = 0; jj < pnp; ++jj) {
/* determine d=max(SBA_DELTA_SCALE*|pbi[jj]|, SBA_MIN_DELTA), see HZ */
d = (double)(SBA_DELTA_SCALE)*pbi[jj]; // force evaluation
d = FABS(d);
if (d < SBA_MIN_DELTA)
d = SBA_MIN_DELTA;
d1 = 1.0 / d; /* invert so that divisions can be carried out faster as multiplications */
for (j = 0; j < nnz; ++j) {
paj = pa + rcsubs[j] * cnp; // j-th camera parameters
(*proj)(rcsubs[j], i, paj, pbi, hxij, adata); // evaluate supplied function on current solution
tmp = pbi[jj];
pbi[jj] += d;
(*proj)(rcsubs[j], i, paj, pbi, hxxij, adata);
pbi[jj] = tmp; /* restore */
pAB = jac + idxij->val[rcidxs[j]] * ABsz + Asz; // set pAB to point to B_ij
for (ii = 0; ii < mnp; ++ii)
pAB[ii * pnp + jj] = (hxxij[ii] - hxij[ii]) * d1;
}
}
}
free(hxij);
}
/* BUNDLE ADJUSTMENT FOR CAMERA PARAMETERS ONLY */
/* Given a parameter vector p made up of the parameters of m cameras, compute in
* hx the prediction of the measurements, i.e. the projections of 3D points in the m images.
* The measurements are returned in the order (hx_11^T, .. hx_1m^T, ..., hx_n1^T, .. hx_nm^T)^T,
* where hx_ij is the predicted projection of the i-th point on the j-th camera.
* Caller supplies rcidxs and rcsubs which can be used as working memory.
* Notice that depending on idxij, some of the hx_ij might be missing
*
*/
static void sba_mot_Qs(double *p, struct sba_crsm *idxij, int *rcidxs, int *rcsubs, double *hx, void *adata) {
register int i, j;
int cnp, mnp;
double *paj, *pxij;
// int n;
int m, nnz;
struct wrap_mot_data_ *wdata;
void (*proj)(int j, int i, double *aj, double *xij, void *proj_adata);
void *proj_adata;
wdata = (struct wrap_mot_data_ *)adata;
cnp = wdata->cnp;
mnp = wdata->mnp;
proj = wdata->proj;
proj_adata = wdata->adata;
// n=idxij->nr;
m = idxij->nc;
for (j = 0; j < m; ++j) {
/* j-th camera parameters */
paj = p + j * cnp;
nnz = sba_crsm_col_elmidxs(idxij, j, rcidxs, rcsubs); /* find nonzero hx_ij, i=0...n-1 */
for (i = 0; i < nnz; ++i) {
pxij = hx + idxij->val[rcidxs[i]] * mnp; // set pxij to point to hx_ij
(*proj)(j, rcsubs[i], paj, pxij, proj_adata); // evaluate Q in pxij
}
}
}
/* Given a parameter vector p made up of the parameters of m cameras, compute in jac
* the jacobian of the predicted measurements, i.e. the jacobian of the projections of 3D points in the m images.
* The jacobian is returned in the order (A_11, ..., A_1m, ..., A_n1, ..., A_nm),
* where A_ij=dx_ij/db_j (see HZ).
* Caller supplies rcidxs and rcsubs which can be used as working memory.
* Notice that depending on idxij, some of the A_ij might be missing
*
*/
static void sba_mot_Qs_jac(double *p, struct sba_crsm *idxij, int *rcidxs, int *rcsubs, double *jac, void *adata) {
register int i, j;
int cnp, mnp;
double *paj, *pAij;
// int n;
int m, nnz, Asz, idx;
struct wrap_mot_data_ *wdata;
void (*projac)(int j, int i, double *aj, double *Aij, void *projac_adata);
void *projac_adata;
wdata = (struct wrap_mot_data_ *)adata;
cnp = wdata->cnp;
mnp = wdata->mnp;
projac = wdata->projac;
projac_adata = wdata->adata;
// n=idxij->nr;
m = idxij->nc;
Asz = mnp * cnp;
for (j = 0; j < m; ++j) {
/* j-th camera parameters */
paj = p + j * cnp;
nnz = sba_crsm_col_elmidxs(idxij, j, rcidxs, rcsubs); /* find nonzero hx_ij, i=0...n-1 */
for (i = 0; i < nnz; ++i) {
idx = idxij->val[rcidxs[i]];
pAij = jac + idx * Asz; // set pAij to point to A_ij
(*projac)(j, rcsubs[i], paj, pAij, projac_adata); // evaluate dQ/da in pAij
}
}
}
/* Given a parameter vector p made up of the parameters of m cameras, compute in jac the jacobian
* of the predicted measurements, i.e. the jacobian of the projections of 3D points in the m images.
* The jacobian is approximated with the aid of finite differences and is returned in the order
* (A_11, ..., A_1m, ..., A_n1, ..., A_nm), where A_ij=dx_ij/da_j (see HZ).
* Notice that depending on idxij, some of the A_ij might be missing
*
* Problem-specific information is assumed to be stored in a structure pointed to by "dat".
*
* NOTE: This function is provided mainly for illustration purposes; in case that execution time is a concern,
* the jacobian should be computed analytically
*/
static void sba_mot_Qs_fdjac(
double *p, /* I: current parameter estimate, (m*cnp)x1 */
struct sba_crsm *idxij, /* I: sparse matrix containing the location of x_ij in hx */
int *rcidxs, /* work array for the indexes of nonzero elements of a single sparse matrix row/column */
int *rcsubs, /* work array for the subscripts of nonzero elements in a single sparse matrix row/column */
double *jac, /* O: array for storing the approximated jacobian */
void *dat) /* I: points to a "wrap_mot_data_" structure */
{
register int i, j, ii, jj;
double *paj;
register double *pA;
// int n;
int m, nnz, Asz;
double tmp;
register double d, d1;
struct wrap_mot_data_ *fdjd;
void (*proj)(int j, int i, double *aj, double *xij, void *adata);
double *hxij, *hxxij;
int cnp, mnp;
void *adata;
/* retrieve problem-specific information passed in *dat */
fdjd = (struct wrap_mot_data_ *)dat;
proj = fdjd->proj;
cnp = fdjd->cnp;
mnp = fdjd->mnp;
adata = fdjd->adata;
// n=idxij->nr;
m = idxij->nc;
Asz = mnp * cnp;
/* allocate memory for hxij, hxxij */
if ((hxij = malloc(2 * mnp * sizeof(double))) == NULL) {
fprintf(stderr, "memory allocation request failed in sba_mot_Qs_fdjac()!\n");
exit(1);
}
hxxij = hxij + mnp;
/* compute A_ij */
for (j = 0; j < m; ++j) {
paj = p + j * cnp; // j-th camera parameters
nnz = sba_crsm_col_elmidxs(idxij, j, rcidxs, rcsubs); /* find nonzero A_ij, i=0...n-1 */
for (jj = 0; jj < cnp; ++jj) {
/* determine d=max(SBA_DELTA_SCALE*|paj[jj]|, SBA_MIN_DELTA), see HZ */
d = (double)(SBA_DELTA_SCALE)*paj[jj]; // force evaluation
d = FABS(d);
if (d < SBA_MIN_DELTA)
d = SBA_MIN_DELTA;
d1 = 1.0 / d; /* invert so that divisions can be carried out faster as multiplications */
for (i = 0; i < nnz; ++i) {
(*proj)(j, rcsubs[i], paj, hxij, adata); // evaluate supplied function on current solution
tmp = paj[jj];
paj[jj] += d;
(*proj)(j, rcsubs[i], paj, hxxij, adata);
paj[jj] = tmp; /* restore */
pA = jac + idxij->val[rcidxs[i]] * Asz; // set pA to point to A_ij
for (ii = 0; ii < mnp; ++ii)
pA[ii * cnp + jj] = (hxxij[ii] - hxij[ii]) * d1;
}
}
}
free(hxij);
}
/* BUNDLE ADJUSTMENT FOR STRUCTURE PARAMETERS ONLY */
/* Given a parameter vector p made up of the 3D coordinates of n points, compute in
* hx the prediction of the measurements, i.e. the projections of 3D points in the m images. The measurements
* are returned in the order (hx_11^T, .. hx_1m^T, ..., hx_n1^T, .. hx_nm^T)^T, where hx_ij is the predicted
* projection of the i-th point on the j-th camera.
* Caller supplies rcidxs and rcsubs which can be used as working memory.
* Notice that depending on idxij, some of the hx_ij might be missing
*
*/
static void sba_str_Qs(double *p, struct sba_crsm *idxij, int *rcidxs, int *rcsubs, double *hx, void *adata) {
register int i, j;
int pnp, mnp;
double *pbi, *pxij;
// int n;
int m, nnz;
struct wrap_str_data_ *wdata;
void (*proj)(int j, int i, double *bi, double *xij, void *proj_adata);
void *proj_adata;
wdata = (struct wrap_str_data_ *)adata;
pnp = wdata->pnp;
mnp = wdata->mnp;
proj = wdata->proj;
proj_adata = wdata->adata;
// n=idxij->nr;
m = idxij->nc;
for (j = 0; j < m; ++j) {
nnz = sba_crsm_col_elmidxs(idxij, j, rcidxs, rcsubs); /* find nonzero hx_ij, i=0...n-1 */
for (i = 0; i < nnz; ++i) {
pbi = p + rcsubs[i] * pnp;
pxij = hx + idxij->val[rcidxs[i]] * mnp; // set pxij to point to hx_ij
(*proj)(j, rcsubs[i], pbi, pxij, proj_adata); // evaluate Q in pxij
}
}
}
/* Given a parameter vector p made up of the 3D coordinates of n points, compute in
* jac the jacobian of the predicted measurements, i.e. the jacobian of the projections of 3D points in the m images.
* The jacobian is returned in the order (B_11, ..., B_1m, ..., B_n1, ..., B_nm), where B_ij=dx_ij/db_i (see HZ).
* Caller supplies rcidxs and rcsubs which can be used as working memory.
* Notice that depending on idxij, some of the B_ij might be missing
*
*/
static void sba_str_Qs_jac(double *p, struct sba_crsm *idxij, int *rcidxs, int *rcsubs, double *jac, void *adata) {
register int i, j;
int pnp, mnp;
double *pbi, *pBij;
// int n;
int m, nnz, Bsz, idx;
struct wrap_str_data_ *wdata;
void (*projac)(int j, int i, double *bi, double *Bij, void *projac_adata);
void *projac_adata;
wdata = (struct wrap_str_data_ *)adata;
pnp = wdata->pnp;
mnp = wdata->mnp;
projac = wdata->projac;
projac_adata = wdata->adata;
// n=idxij->nr;
m = idxij->nc;
Bsz = mnp * pnp;
for (j = 0; j < m; ++j) {
nnz = sba_crsm_col_elmidxs(idxij, j, rcidxs, rcsubs); /* find nonzero hx_ij, i=0...n-1 */
for (i = 0; i < nnz; ++i) {
pbi = p + rcsubs[i] * pnp;
idx = idxij->val[rcidxs[i]];
pBij = jac + idx * Bsz; // set pBij to point to B_ij
(*projac)(j, rcsubs[i], pbi, pBij, projac_adata); // evaluate dQ/db in pBij
}
}
}
/* Given a parameter vector p made up of the 3D coordinates of n points, compute in
* jac the jacobian of the predicted measurements, i.e. the jacobian of the projections of 3D points in the m images.
* The jacobian is approximated with the aid of finite differences and is returned in the order
* (B_11, ..., B_1m, ..., B_n1, ..., B_nm), where B_ij=dx_ij/db_i (see HZ).
* Notice that depending on idxij, some of the B_ij might be missing
*
* Problem-specific information is assumed to be stored in a structure pointed to by "dat".
*
* NOTE: This function is provided mainly for illustration purposes; in case that execution time is a concern,
* the jacobian should be computed analytically
*/
static void sba_str_Qs_fdjac(
double *p, /* I: current parameter estimate, (n*pnp)x1 */
struct sba_crsm *idxij, /* I: sparse matrix containing the location of x_ij in hx */
int *rcidxs, /* work array for the indexes of nonzero elements of a single sparse matrix row/column */
int *rcsubs, /* work array for the subscripts of nonzero elements in a single sparse matrix row/column */
double *jac, /* O: array for storing the approximated jacobian */
void *dat) /* I: points to a "wrap_str_data_" structure */
{
register int i, j, ii, jj;
double *pbi;
register double *pB;
// int m;
int n, nnz, Bsz;
double tmp;
register double d, d1;
struct wrap_str_data_ *fdjd;
void (*proj)(int j, int i, double *bi, double *xij, void *adata);
double *hxij, *hxxij;
int pnp, mnp;
void *adata;
/* retrieve problem-specific information passed in *dat */
fdjd = (struct wrap_str_data_ *)dat;
proj = fdjd->proj;
pnp = fdjd->pnp;
mnp = fdjd->mnp;
adata = fdjd->adata;
n = idxij->nr;
// m=idxij->nc;
Bsz = mnp * pnp;
/* allocate memory for hxij, hxxij */
if ((hxij = malloc(2 * mnp * sizeof(double))) == NULL) {
fprintf(stderr, "memory allocation request failed in sba_str_Qs_fdjac()!\n");
exit(1);
}
hxxij = hxij + mnp;
/* compute B_ij */
for (i = 0; i < n; ++i) {
pbi = p + i * pnp; // i-th point parameters
nnz = sba_crsm_row_elmidxs(idxij, i, rcidxs, rcsubs); /* find nonzero B_ij, j=0...m-1 */
for (jj = 0; jj < pnp; ++jj) {
/* determine d=max(SBA_DELTA_SCALE*|pbi[jj]|, SBA_MIN_DELTA), see HZ */
d = (double)(SBA_DELTA_SCALE)*pbi[jj]; // force evaluation
d = FABS(d);
if (d < SBA_MIN_DELTA)
d = SBA_MIN_DELTA;
d1 = 1.0 / d; /* invert so that divisions can be carried out faster as multiplications */
for (j = 0; j < nnz; ++j) {
(*proj)(rcsubs[j], i, pbi, hxij, adata); // evaluate supplied function on current solution
tmp = pbi[jj];
pbi[jj] += d;
(*proj)(rcsubs[j], i, pbi, hxxij, adata);
pbi[jj] = tmp; /* restore */
pB = jac + idxij->val[rcidxs[j]] * Bsz; // set pB to point to B_ij
for (ii = 0; ii < mnp; ++ii)
pB[ii * pnp + jj] = (hxxij[ii] - hxij[ii]) * d1;
}
}
}
free(hxij);
}
/*
* Simple driver to sba_motstr_levmar_x for bundle adjustment on camera and structure parameters.
*
* Returns the number of iterations (>=0) if successfull, SBA_ERROR if failed
*/
int sba_motstr_levmar(
const int n, /* number of points */
const int ncon, /* number of points (starting from the 1st) whose parameters should not be modified.
* All B_ij (see below) with i<ncon are assumed to be zero
*/
const int m, /* number of images */
const int mcon, /* number of images (starting from the 1st) whose parameters should not be modified.
* All A_ij (see below) with j<mcon are assumed to be zero
*/
char *vmask, /* visibility mask: vmask[i, j]=1 if point i visible in image j, 0 otherwise. nxm */
double *p, /* initial parameter vector p0: (a1, ..., am, b1, ..., bn).
* aj are the image j parameters, bi are the i-th point parameters,
* size m*cnp + n*pnp
*/
const int cnp, /* number of parameters for ONE camera; e.g. 6 for Euclidean cameras */
const int pnp, /* number of parameters for ONE point; e.g. 3 for Euclidean points */
double *x, /* measurements vector: (x_11^T, .. x_1m^T, ..., x_n1^T, .. x_nm^T)^T where
* x_ij is the projection of the i-th point on the j-th image.
* NOTE: some of the x_ij might be missing, if point i is not visible in image j;
* see vmask[i, j], max. size n*m*mnp
*/
double *covx, /* measurements covariance matrices: (Sigma_x_11, .. Sigma_x_1m, ..., Sigma_x_n1, .. Sigma_x_nm),
* where Sigma_x_ij is the mnp x mnp covariance of x_ij stored row-by-row. Set to NULL if no
* covariance estimates are available (identity matrices are implicitly used in this case).
* NOTE: a certain Sigma_x_ij is missing if the corresponding x_ij is also missing;
* see vmask[i, j], max. size n*m*mnp*mnp
*/
const int mnp, /* number of parameters for EACH measurement; usually 2 */
void (*proj)(int j, int i, double *aj, double *bi, double *xij, void *adata),
/* functional relation computing a SINGLE image measurement. Assuming that
* the parameters of point i are bi and the parameters of camera j aj,
* computes a prediction of \hat{x}_{ij}. aj is cnp x 1, bi is pnp x 1 and
* xij is mnp x 1. This function is called only if point i is visible in
* image j (i.e. vmask[i, j]==1)
*/
void (*projac)(int j, int i, double *aj, double *bi, double *Aij, double *Bij, void *adata),
/* functional relation to evaluate d x_ij / d a_j and
* d x_ij / d b_i in Aij and Bij resp.
* This function is called only if point i is visible in * image j
* (i.e. vmask[i, j]==1). Also, A_ij and B_ij are mnp x cnp and mnp x pnp
* matrices resp. and they should be stored in row-major order.
*
* If NULL, the jacobians are approximated by repetitive proj calls
* and finite differences.
*/
void *adata, /* pointer to possibly additional data, passed uninterpreted to proj, projac */
const int itmax, /* I: maximum number of iterations. itmax==0 signals jacobian verification followed by immediate
return */
const int verbose, /* I: verbosity */
const double opts[SBA_OPTSSZ],
/* I: minim. options [\mu, \epsilon1, \epsilon2, \epsilon3, \epsilon4]. Respectively the scale factor for initial
* \mu,
* stoping thresholds for ||J^T e||_inf, ||dp||_2, ||e||_2 and (||e||_2-||e_new||_2)/||e||_2
*/
double info[SBA_INFOSZ]
/* O: information regarding the minimization. Set to NULL if don't care
* info[0]=||e||_2 at initial p.
* info[1-4]=[ ||e||_2, ||J^T e||_inf, ||dp||_2, mu/max[J^T J]_ii ], all computed at estimated p.
* info[5]= # iterations,
* info[6]=reason for terminating: 1 - stopped by small gradient J^T e
* 2 - stopped by small dp
* 3 - stopped by itmax
* 4 - stopped by small relative reduction in ||e||_2
* 5 - too many attempts to increase damping. Restart with increased mu
* 6 - stopped by small ||e||_2
* 7 - stopped by invalid (i.e. NaN or Inf) "func" values. This is a user error
* info[7]= # function evaluations
* info[8]= # jacobian evaluations
* info[9]= # number of linear systems solved, i.e. number of attempts for reducing error
*/
) {
int retval;
struct wrap_motstr_data_ wdata;
static void (*fjac)(double *p, struct sba_crsm *idxij, int *rcidxs, int *rcsubs, double *jac, void *adata);
wdata.proj = proj;
wdata.projac = projac;
wdata.cnp = cnp;
wdata.pnp = pnp;
wdata.mnp = mnp;
wdata.adata = adata;
fjac = (projac) ? sba_motstr_Qs_jac : sba_motstr_Qs_fdjac;
retval = sba_motstr_levmar_x(n, ncon, m, mcon, vmask, p, cnp, pnp, x, covx, mnp, sba_motstr_Qs, fjac, &wdata, itmax,
verbose, opts, info);
if (info) {
register int i;
int nvis;
/* count visible image points */
for (i = nvis = 0; i < n * m; ++i)
nvis += (vmask[i] != 0);
/* each "func" & "fjac" evaluation requires nvis "proj" & "projac" evaluations */
info[7] *= nvis;
info[8] *= nvis;
}
return retval;
}
/*
* Simple driver to sba_mot_levmar_x for bundle adjustment on camera parameters.
*
* Returns the number of iterations (>=0) if successfull, SBA_ERROR if failed
*/
int sba_mot_levmar(
const int n, /* number of points */
const int m, /* number of images */
const int mcon, /* number of images (starting from the 1st) whose parameters should not be modified.
* All A_ij (see below) with j<mcon are assumed to be zero
*/
char *vmask, /* visibility mask: vmask[i, j]=1 if point i visible in image j, 0 otherwise. nxm */
double *p, /* initial parameter vector p0: (a1, ..., am).
* aj are the image j parameters, size m*cnp */
const int cnp, /* number of parameters for ONE camera; e.g. 6 for Euclidean cameras */
double *x, /* measurements vector: (x_11^T, .. x_1m^T, ..., x_n1^T, .. x_nm^T)^T where
* x_ij is the projection of the i-th point on the j-th image.
* NOTE: some of the x_ij might be missing, if point i is not visible in image j;
* see vmask[i, j], max. size n*m*mnp
*/
double *covx, /* measurements covariance matrices: (Sigma_x_11, .. Sigma_x_1m, ..., Sigma_x_n1, .. Sigma_x_nm),
* where Sigma_x_ij is the mnp x mnp covariance of x_ij stored row-by-row. Set to NULL if no
* covariance estimates are available (identity matrices are implicitly used in this case).
* NOTE: a certain Sigma_x_ij is missing if the corresponding x_ij is also missing;
* see vmask[i, j], max. size n*m*mnp*mnp
*/
const int mnp, /* number of parameters for EACH measurement; usually 2 */
void (*proj)(int j, int i, double *aj, double *xij, void *adata),
/* functional relation computing a SINGLE image measurement. Assuming that
* the parameters of camera j are aj, computes a prediction of \hat{x}_{ij}
* for point i. aj is cnp x 1 and xij is mnp x 1.
* This function is called only if point i is visible in image j (i.e. vmask[i, j]==1)
*/
void (*projac)(int j, int i, double *aj, double *Aij, void *adata),
/* functional relation to evaluate d x_ij / d a_j in Aij
* This function is called only if point i is visible in image j
* (i.e. vmask[i, j]==1). Also, A_ij are a mnp x cnp matrices
* and should be stored in row-major order.
*
* If NULL, the jacobian is approximated by repetitive proj calls
* and finite differences.
*/
void *adata, /* pointer to possibly additional data, passed uninterpreted to proj, projac */
const int itmax, /* I: maximum number of iterations. itmax==0 signals jacobian verification followed by immediate
return */
const int verbose, /* I: verbosity */
const double opts[SBA_OPTSSZ],
/* I: minim. options [\mu, \epsilon1, \epsilon2, \epsilon3, \epsilon]. Respectively the scale factor for initial
* \mu,
* stoping thresholds for ||J^T e||_inf, ||dp||_2, ||e||_2 and (||e||_2-||e_new||_2)/||e||_2
*/
double info[SBA_INFOSZ]
/* O: information regarding the minimization. Set to NULL if don't care
* info[0]=||e||_2 at initial p.
* info[1-4]=[ ||e||_2, ||J^T e||_inf, ||dp||_2, mu/max[J^T J]_ii ], all computed at estimated p.
* info[5]= # iterations,
* info[6]=reason for terminating: 1 - stopped by small gradient J^T e
* 2 - stopped by small dp
* 3 - stopped by itmax
* 4 - stopped by small relative reduction in ||e||_2
* 5 - too many attempts to increase damping. Restart with increased mu
* 6 - stopped by small ||e||_2
* 7 - stopped by invalid (i.e. NaN or Inf) "func" values. This is a user error
* info[7]= # function evaluations
* info[8]= # jacobian evaluations
* info[9]= # number of linear systems solved, i.e. number of attempts for reducing error
*/
) {
int retval;
struct wrap_mot_data_ wdata;
void (*fjac)(double *p, struct sba_crsm *idxij, int *rcidxs, int *rcsubs, double *jac, void *adata);
wdata.proj = proj;
wdata.projac = projac;
wdata.cnp = cnp;
wdata.mnp = mnp;
wdata.adata = adata;
fjac = (projac) ? sba_mot_Qs_jac : sba_mot_Qs_fdjac;
retval =
sba_mot_levmar_x(n, m, mcon, vmask, p, cnp, x, covx, mnp, sba_mot_Qs, fjac, &wdata, itmax, verbose, opts, info);
if (info) {
register int i;
int nvis;
/* count visible image points */
for (i = nvis = 0; i < n * m; ++i)
nvis += (vmask[i] != 0);
/* each "func" & "fjac" evaluation requires nvis "proj" & "projac" evaluations */
info[7] *= nvis;
info[8] *= nvis;
}
return retval;
}
/*
* Simple driver to sba_str_levmar_x for bundle adjustment on structure parameters.
*
* Returns the number of iterations (>=0) if successfull, SBA_ERROR if failed
*/
int sba_str_levmar(
const int n, /* number of points */
const int ncon, /* number of points (starting from the 1st) whose parameters should not be modified.
* All B_ij (see below) with i<ncon are assumed to be zero
*/
const int m, /* number of images */
char *vmask, /* visibility mask: vmask[i, j]=1 if point i visible in image j, 0 otherwise. nxm */
double *p, /* initial parameter vector p0: (b1, ..., bn).
* bi are the i-th point parameters, size n*pnp
*/
const int pnp, /* number of parameters for ONE point; e.g. 3 for Euclidean points */
double *x, /* measurements vector: (x_11^T, .. x_1m^T, ..., x_n1^T, .. x_nm^T)^T where
* x_ij is the projection of the i-th point on the j-th image.
* NOTE: some of the x_ij might be missing, if point i is not visible in image j;
* see vmask[i, j], max. size n*m*mnp
*/
double *covx, /* measurements covariance matrices: (Sigma_x_11, .. Sigma_x_1m, ..., Sigma_x_n1, .. Sigma_x_nm),
* where Sigma_x_ij is the mnp x mnp covariance of x_ij stored row-by-row. Set to NULL if no
* covariance estimates are available (identity matrices are implicitly used in this case).
* NOTE: a certain Sigma_x_ij is missing if the corresponding x_ij is also missing;
* see vmask[i, j], max. size n*m*mnp*mnp
*/
const int mnp, /* number of parameters for EACH measurement; usually 2 */
void (*proj)(int j, int i, double *bi, double *xij, void *adata),
/* functional relation computing a SINGLE image measurement. Assuming that
* the parameters of point i are bi, computes a prediction of \hat{x}_{ij}.
* bi is pnp x 1 and xij is mnp x 1. This function is called only if point
* i is visible in image j (i.e. vmask[i, j]==1)
*/
void (*projac)(int j, int i, double *bi, double *Bij, void *adata),
/* functional relation to evaluate d x_ij / d b_i in Bij.
* This function is called only if point i is visible in image j
* (i.e. vmask[i, j]==1). Also, B_ij are mnp x pnp matrices
* and they should be stored in row-major order.
*
* If NULL, the jacobians are approximated by repetitive proj calls
* and finite differences.
*/
void *adata, /* pointer to possibly additional data, passed uninterpreted to proj, projac */
const int itmax, /* I: maximum number of iterations. itmax==0 signals jacobian verification followed by immediate
return */
const int verbose, /* I: verbosity */
const double opts[SBA_OPTSSZ],
/* I: minim. options [\mu, \epsilon1, \epsilon2, \epsilon3, \epsilon4]. Respectively the scale factor for initial
* \mu,
* stoping thresholds for ||J^T e||_inf, ||dp||_2, ||e||_2 and (||e||_2-||e_new||_2)/||e||_2
*/
double info[SBA_INFOSZ]
/* O: information regarding the minimization. Set to NULL if don't care
* info[0]=||e||_2 at initial p.
* info[1-4]=[ ||e||_2, ||J^T e||_inf, ||dp||_2, mu/max[J^T J]_ii ], all computed at estimated p.
* info[5]= # iterations,
* info[6]=reason for terminating: 1 - stopped by small gradient J^T e
* 2 - stopped by small dp
* 3 - stopped by itmax
* 4 - stopped by small relative reduction in ||e||_2
* 5 - too many attempts to increase damping. Restart with increased mu
* 6 - stopped by small ||e||_2
* 7 - stopped by invalid (i.e. NaN or Inf) "func" values. This is a user error
* info[7]= # function evaluations
* info[8]= # jacobian evaluations
* info[9]= # number of linear systems solved, i.e. number of attempts for reducing error
*/
) {
int retval;
struct wrap_str_data_ wdata;
static void (*fjac)(double *p, struct sba_crsm *idxij, int *rcidxs, int *rcsubs, double *jac, void *adata);
wdata.proj = proj;
wdata.projac = projac;
wdata.pnp = pnp;
wdata.mnp = mnp;
wdata.adata = adata;
fjac = (projac) ? sba_str_Qs_jac : sba_str_Qs_fdjac;
retval =
sba_str_levmar_x(n, ncon, m, vmask, p, pnp, x, covx, mnp, sba_str_Qs, fjac, &wdata, itmax, verbose, opts, info);
if (info) {
register int i;
int nvis;
/* count visible image points */
for (i = nvis = 0; i < n * m; ++i)
nvis += (vmask[i] != 0);
/* each "func" & "fjac" evaluation requires nvis "proj" & "projac" evaluations */
info[7] *= nvis;
info[8] *= nvis;
}
return retval;
}
|