9 #include "BundleAdjust.h"
17 #include <QCoreApplication>
23 #include <boost/lexical_cast.hpp>
24 #include <boost/numeric/ublas/io.hpp>
25 #include <boost/numeric/ublas/matrix_sparse.hpp>
26 #include <boost/numeric/ublas/vector_proxy.hpp>
29 #include "Application.h"
30 #include "BundleObservation.h"
31 #include "IsisBundleObservation.h"
32 #include "BundleObservationSolveSettings.h"
33 #include "BundleResults.h"
34 #include "BundleSettings.h"
35 #include "BundleSolutionInfo.h"
36 #include "BundleTargetBody.h"
38 #include "CameraDetectorMap.h"
39 #include "CameraDistortionMap.h"
40 #include "CameraFocalPlaneMap.h"
41 #include "CameraGroundMap.h"
42 #include "CSMCamera.h"
44 #include "ControlPoint.h"
45 #include "CorrelationMatrix.h"
47 #include "ImageList.h"
50 #include "Longitude.h"
51 #include "MaximumLikelihoodWFunctions.h"
52 #include "SpecialPixel.h"
53 #include "StatCumProbDistDynCalc.h"
54 #include "SurfacePoint.h"
57 using namespace boost::numeric::ublas;
75 const char* message) {
89 errlog +=
". (See print.prt for details)";
105 const QString &cnetFile,
106 const QString &cubeList,
113 m_printSummary = printSummary;
115 m_cnetFileName = cnetFile;
118 bundleSettings->controlPointCoordTypeReports()) );
123 m_bundleResults.setOutputControlNet(m_controlNet);
125 m_bundleSettings = bundleSettings;
126 m_bundleTargetBody = bundleSettings->bundleTargetBody();
151 m_printSummary = printSummary;
153 m_cnetFileName = cnetFile;
160 m_bundleResults.setOutputControlNet(m_controlNet);
161 m_serialNumberList = &snlist;
162 m_bundleSettings = bundleSettings;
163 m_bundleTargetBody = bundleSettings->bundleTargetBody();
188 m_printSummary = printSummary;
197 m_bundleResults.setOutputControlNet(m_controlNet);
198 m_serialNumberList = &snlist;
199 m_bundleSettings = bundleSettings;
200 m_bundleTargetBody = bundleSettings->bundleTargetBody();
224 m_printSummary = printSummary;
233 m_bundleResults.setOutputControlNet(m_controlNet);
234 m_serialNumberList = &snlist;
235 m_bundleSettings = bundleSettings;
236 m_bundleTargetBody = bundleSettings->bundleTargetBody();
252 const QString &cubeList,
255 m_printSummary = printSummary;
264 m_bundleResults.setOutputControlNet(m_controlNet);
266 m_bundleSettings = bundleSettings;
267 m_bundleTargetBody = bundleSettings->bundleTargetBody();
286 m_bundleSettings = bundleSettings;
295 m_bundleResults.setOutputControlNet(m_controlNet);
297 m_imageLists = imgLists;
305 foreach (
Image *image, *imgList) {
311 m_bundleTargetBody = bundleSettings->bundleTargetBody();
313 m_printSummary = printSummary;
316 m_cnetFileName = control.
fileName();
330 BundleAdjust::~BundleAdjust() {
333 delete m_serialNumberList;
336 freeCHOLMODLibraryVariables();
373 emit(statusUpdate(
"Initialization"));
374 m_previousNumberImagePartials = 0;
382 m_iterationSummary =
"";
388 m_controlNet->SetImages(*m_serialNumberList, progress);
391 m_controlNet->ClearJigsawRejected();
394 int numImages = m_serialNumberList->size();
397 m_normalInverse.clear();
399 m_imageSolution.clear();
404 m_cholmodNormal = NULL;
405 m_cholmodTriplet = NULL;
412 for (
int i = 0; i < numImages; i++) {
415 QString observationNumber = m_serialNumberList->observationNumber(i);
416 QString instrumentId = m_serialNumberList->spacecraftInstrumentId(i);
417 QString serialNumber = m_serialNumberList->serialNumber(i);
418 QString fileName = m_serialNumberList->fileName(i);
425 QString msg =
"In BundleAdjust::init(): image " + fileName +
"is null." +
"\n";
426 throw IException(IException::Programmer, msg, _FILEINFO_);
430 m_bundleObservations.addNew(image, observationNumber, instrumentId, m_bundleSettings);
433 QString msg =
"In BundleAdjust::init(): observation "
434 + observationNumber +
"is null." +
"\n";
435 throw IException(IException::Programmer, msg, _FILEINFO_);
440 int numControlPoints = m_controlNet->GetNumPoints();
441 for (
int i = 0; i < numControlPoints; i++) {
443 if (point->IsIgnored()) {
448 (m_bundleSettings, point));
449 m_bundleControlPoints.append(bundleControlPoint);
453 int numMeasures = bundleControlPoint->size();
454 for (
int j=0; j < numMeasures; j++) {
456 QString cubeSerialNumber = measure->cubeSerialNumber();
459 m_bundleObservations.observationByCubeSerialNumber(cubeSerialNumber);
460 BundleImageQsp image = observation->imageByCubeSerialNumber(cubeSerialNumber);
462 measure->setParentObservation(observation);
463 measure->setParentImage(image);
477 if (m_bundleSettings->validateNetwork()) {
480 m_bundleResults.maximumLikelihoodSetUp(m_bundleSettings->maximumLikelihoodEstimatorModels());
496 m_rank = m_bundleObservations.numberParameters();
498 if (m_bundleSettings->solveTargetBody()) {
499 m_rank += m_bundleSettings->numberTargetBodyParameters();
501 if (m_bundleTargetBody->solveMeanRadius() || m_bundleTargetBody->solveTriaxialRadii()) {
502 outputBundleStatus(
"Warning: Solving for the target body radii (triaxial or mean) "
503 "is NOT possible and likely increases error in the solve.\n");
506 if (m_bundleTargetBody->solveMeanRadius()){
508 bool isMeanRadiusValid =
true;
509 double localRadius, aprioriRadius;
513 SurfacePoint surfacepoint = point->adjustedSurfacePoint();
516 aprioriRadius = m_bundleTargetBody->meanRadius().meters();
520 if (aprioriRadius >= 2 * localRadius || aprioriRadius <= localRadius / 2) {
521 isMeanRadiusValid =
false;
525 if (!isMeanRadiusValid) {
526 outputBundleStatus(
"Warning: User-entered MeanRadiusValue appears to be inaccurate. "
527 "This can cause a bundle failure.\n");
532 int num3DPoints = m_bundleControlPoints.size();
534 m_bundleResults.setNumberUnknownParameters(m_rank + 3 * num3DPoints);
536 m_imageSolution.resize(m_rank);
540 initializeCHOLMODLibraryVariables();
543 initializeNormalEquationsMatrix();
566 bool BundleAdjust::validateNetwork() {
568 outputBundleStatus(
"\nValidating network...");
570 int imagesWithInsufficientMeasures = 0;
571 QString msg =
"Images with one or less measures:\n";
572 int numObservations = m_bundleObservations.size();
573 for (
int i = 0; i < numObservations; i++) {
574 int numImages = m_bundleObservations.at(i)->size();
575 for (
int j = 0; j < numImages; j++) {
577 int numMeasures = m_controlNet->
578 GetNumberOfValidMeasuresInImage(bundleImage->serialNumber());
580 if (numMeasures > 1) {
584 imagesWithInsufficientMeasures++;
585 msg += bundleImage->fileName() +
": " +
toString(numMeasures) +
"\n";
589 if ( imagesWithInsufficientMeasures > 0 ) {
590 throw IException(IException::User, msg, _FILEINFO_);
593 outputBundleStatus(
"\nValidation complete!...\n");
604 bool BundleAdjust::initializeCHOLMODLibraryVariables() {
609 m_cholmodTriplet = NULL;
611 cholmod_start(&m_cholmodCommon);
617 m_cholmodCommon.nmethods = 1;
618 m_cholmodCommon.method[0].ordering = CHOLMOD_AMD;
634 bool BundleAdjust::initializeNormalEquationsMatrix() {
636 int nBlockColumns = m_bundleObservations.size();
638 if (m_bundleSettings->solveTargetBody())
641 m_sparseNormals.setNumberOfColumns(nBlockColumns);
643 m_sparseNormals.at(0)->setStartColumn(0);
646 if (m_bundleSettings->solveTargetBody()) {
647 nParameters += m_bundleSettings->numberTargetBodyParameters();
648 m_sparseNormals.at(1)->setStartColumn(nParameters);
651 for (
int i = 2; i < nBlockColumns; i++) {
652 nParameters += m_bundleObservations.at(observation)->numberParameters();
653 m_sparseNormals.at(i)->setStartColumn(nParameters);
658 for (
int i = 0; i < nBlockColumns; i++) {
659 m_sparseNormals.at(i)->setStartColumn(nParameters);
660 nParameters += m_bundleObservations.at(i)->numberParameters();
676 bool BundleAdjust::freeCHOLMODLibraryVariables() {
678 cholmod_free_triplet(&m_cholmodTriplet, &m_cholmodCommon);
679 cholmod_free_sparse(&m_cholmodNormal, &m_cholmodCommon);
680 cholmod_free_factor(&m_L, &m_cholmodCommon);
682 cholmod_finish(&m_cholmodCommon);
699 return bundleSolveInformation();
707 void BundleAdjust::abortBundle() {
726 bool BundleAdjust::solveCholesky() {
727 emit(statusBarUpdate(
"Solving"));
745 m_controlNet->ComputeApriori();
749 if (m_bundleTargetBody && m_bundleTargetBody->solveMeanRadius()) {
750 int numControlPoints = m_bundleControlPoints.size();
751 for (
int i = 0; i < numControlPoints; i++) {
753 SurfacePoint surfacepoint = point->adjustedSurfacePoint();
757 point->setAdjustedSurfacePoint(surfacepoint);
762 if (m_bundleTargetBody && m_bundleTargetBody->solveTriaxialRadii()
763 && m_bundleSettings->controlPointCoordTypeBundle() == SurfacePoint::Latitudinal) {
764 int numControlPoints = m_bundleControlPoints.size();
765 for (
int i = 0; i < numControlPoints; i++) {
767 SurfacePoint surfacepoint = point->adjustedSurfacePoint();
773 point->setAdjustedSurfacePoint(surfacepoint);
780 double previousSigma0 = 0.0;
783 clock_t solveStartClock = clock();
787 emit iterationUpdate(m_iteration);
791 m_bundleResults.setConverged(
false);
792 emit statusUpdate(
"\n aborting...");
798 emit statusUpdate( QString(
"starting iteration %1\n").arg(m_iteration) );
800 clock_t iterationStartClock = clock();
803 if (m_iteration != 1) {
804 m_sparseNormals.zeroBlocks();
808 if (!formNormalEquations()) {
809 m_bundleResults.setConverged(
false);
815 m_bundleResults.setConverged(
false);
816 emit statusUpdate(
"\n aborting...");
823 if (!solveSystem()) {
824 outputBundleStatus(
"\nsolve failed!");
825 m_bundleResults.setConverged(
false);
831 m_bundleResults.setConverged(
false);
832 emit statusUpdate(
"\n aborting...");
839 applyParameterCorrections();
843 m_bundleResults.setConverged(
false);
844 emit statusUpdate(
"\n aborting...");
851 vtpv = computeResiduals();
854 if ( m_bundleSettings->outlierRejection() ) {
855 computeRejectionLimit();
861 m_bundleResults.setConverged(
false);
862 emit statusUpdate(
"\n aborting...");
869 m_bundleResults.computeSigma0(vtpv, m_bundleSettings->convergenceCriteria());
876 emit statusUpdate(QString(
"Iteration: %1 \n")
878 emit statusUpdate(QString(
"Sigma0: %1 \n")
879 .arg(m_bundleResults.sigma0(),
883 emit statusUpdate(QString(
"Observations: %1 \n")
884 .arg(m_bundleResults.numberObservations()));
885 emit statusUpdate(QString(
"Constrained Parameters:%1 \n")
886 .arg(m_bundleResults.numberConstrainedPointParameters()));
887 emit statusUpdate(QString(
"Unknowns: %1 \n")
888 .arg(m_bundleResults.numberUnknownParameters()));
889 emit statusUpdate(QString(
"Degrees of Freedom: %1 \n")
890 .arg(m_bundleResults.degreesOfFreedom()));
891 emit iterationUpdate(m_iteration);
894 if (m_bundleSettings->convergenceCriteria() == BundleSettings::Sigma0) {
895 if (fabs(previousSigma0 - m_bundleResults.sigma0())
896 <= m_bundleSettings->convergenceCriteriaThreshold()) {
901 if (m_bundleResults.maximumLikelihoodModelIndex()
902 < m_bundleResults.numberMaximumLikelihoodModels() - 1
903 && m_bundleResults.maximumLikelihoodModelIndex()
907 if (m_bundleResults.numberMaximumLikelihoodModels()
908 > m_bundleResults.maximumLikelihoodModelIndex() + 1) {
911 m_bundleResults.incrementMaximumLikelihoodModelIndex();
915 m_bundleResults.setConverged(
true);
916 emit statusUpdate(
"Bundle has converged\n");
917 emit statusBarUpdate(
"Converged");
924 int numConvergedParams = 0;
925 int numImgParams = m_imageSolution.size();
926 for (
int ij = 0; ij < numImgParams; ij++) {
927 if (fabs(m_imageSolution(ij)) > m_bundleSettings->convergenceCriteriaThreshold()) {
931 numConvergedParams++;
934 if ( numConvergedParams == numImgParams ) {
935 m_bundleResults.setConverged(
true);
936 emit statusUpdate(
"Bundle has converged\n");
937 emit statusBarUpdate(
"Converged");
942 m_bundleResults.printMaximumLikelihoodTierInformation();
943 clock_t iterationStopClock = clock();
944 double iterationTime = (iterationStopClock - iterationStartClock)
945 / (
double)CLOCKS_PER_SEC;
946 emit statusUpdate( QString(
"End of Iteration %1 \n").arg(m_iteration) );
947 emit statusUpdate( QString(
"Elapsed Time: %1 \n").arg(iterationTime,
953 if (m_iteration >= m_bundleSettings->convergenceCriteriaMaximumIterations()) {
954 emit(statusBarUpdate(
"Max Iterations Reached"));
960 if (!m_bundleResults.converged()) {
961 m_bundleResults.initializeResidualsProbabilityDistribution(101);
968 if (!m_bundleResults.converged() || !m_bundleSettings->errorPropagation()) {
969 cholmod_free_factor(&m_L, &m_cholmodCommon);
976 previousSigma0 = m_bundleResults.sigma0();
979 if (m_bundleResults.converged() && m_bundleSettings->errorPropagation()) {
980 clock_t errorPropStartClock = clock();
982 outputBundleStatus(
"\nStarting Error Propagation");
985 emit statusUpdate(
"\n\nError Propagation Complete\n");
986 clock_t errorPropStopClock = clock();
987 m_bundleResults.setElapsedTimeErrorProp((errorPropStopClock - errorPropStartClock)
988 / (
double)CLOCKS_PER_SEC);
991 clock_t solveStopClock = clock();
992 m_bundleResults.setElapsedTime((solveStopClock - solveStartClock)
993 / (
double)CLOCKS_PER_SEC);
997 m_bundleResults.setIterations(m_iteration);
998 m_bundleResults.setObservations(m_bundleObservations);
999 m_bundleResults.setBundleControlPoints(m_bundleControlPoints);
1001 emit resultsReady(bundleSolveInformation());
1003 emit statusUpdate(
"\nBundle Complete\n");
1008 m_bundleResults.setConverged(
false);
1009 emit statusUpdate(
"\n aborting...");
1010 emit statusBarUpdate(
"Failed to Converge");
1012 QString msg =
"Could not solve bundle adjust.";
1035 return bundleSolutionInfo;
1050 bool BundleAdjust::formNormalEquations() {
1051 emit(statusBarUpdate(
"Forming Normal Equations"));
1052 bool status =
false;
1054 m_bundleResults.setNumberObservations(0);
1055 m_bundleResults.resetNumberConstrainedPointParameters();
1062 static boost::numeric::ublas::symmetric_matrix<double, upper> N22(3);
1065 boost::numeric::ublas::compressed_vector<double> n1(m_rank);
1067 m_RHS.resize(m_rank);
1071 if (m_bundleSettings->solveTargetBody()) {
1072 int numTargetBodyParameters = m_bundleSettings->numberTargetBodyParameters();
1074 coeffTarget.resize(2,numTargetBodyParameters);
1083 coeffPoint3D.clear();
1089 int numGood3DPoints = 0;
1090 int numRejected3DPoints = 0;
1092 int num3DPoints = m_bundleControlPoints.size();
1094 outputBundleStatus(
"\n\n");
1096 for (
int i = 0; i < num3DPoints; i++) {
1097 emit(pointUpdate(i+1));
1100 if (point->isRejected()) {
1101 numRejected3DPoints++;
1114 int numMeasures = point->size();
1115 for (
int j = 0; j < numMeasures; j++) {
1120 if (measure->isRejected()) {
1124 status = computePartials(coeffTarget, coeffImage, coeffPoint3D, coeffRHS, *measure,
1134 int numObs = m_bundleResults.numberObservations();
1135 m_bundleResults.setNumberObservations(numObs + 2);
1137 formMeasureNormals(N22, N12, n1, n2, coeffTarget, coeffImage, coeffPoint3D, coeffRHS,
1138 measure->observationIndex());
1142 formPointNormals(N22, N12, n2, m_RHS, point);
1151 formWeightedNormals(n1, m_RHS);
1154 m_bundleResults.setNumberUnknownParameters(m_rank + 3 * numGood3DPoints);
1179 bool BundleAdjust::formMeasureNormals(symmetric_matrix<double, upper>&N22,
1181 compressed_vector<double> &n1,
1183 matrix<double> &coeffTarget,
1184 matrix<double> &coeffImage,
1185 matrix<double> &coeffPoint3D,
1186 vector<double> &coeffRHS,
1187 int observationIndex) {
1189 static symmetric_matrix<double, upper> N11;
1190 static matrix<double> N11TargetImage;
1192 int blockIndex = observationIndex;
1195 int numTargetPartials = coeffTarget.size2();
1196 if (m_bundleSettings->solveTargetBody()) {
1199 static vector<double> n1Target(numTargetPartials);
1200 n1Target.resize(numTargetPartials);
1204 N11.resize(numTargetPartials);
1207 N11 = prod(trans(coeffTarget), coeffTarget);
1210 m_sparseNormals.insertMatrixBlock(0, 0, numTargetPartials, numTargetPartials);
1212 (*(*m_sparseNormals[0])[0]) += N11;
1215 N11TargetImage.resize(numTargetPartials, coeffImage.size2());
1216 N11TargetImage.clear();
1217 N11TargetImage = prod(trans(coeffTarget),coeffImage);
1219 m_sparseNormals.insertMatrixBlock(blockIndex, 0,
1220 numTargetPartials, coeffImage.size2());
1221 (*(*m_sparseNormals[blockIndex])[0]) += N11TargetImage;
1224 static matrix<double> N12Target(numTargetPartials, 3);
1227 N12Target = prod(trans(coeffTarget), coeffPoint3D);
1231 *N12[0] += N12Target;
1234 n1Target = prod(trans(coeffTarget), coeffRHS);
1237 for (
int i = 0; i < numTargetPartials; i++) {
1238 n1(i) += n1Target(i);
1247 int numImagePartials = coeffImage.size2();
1250 n1Image.resize(numImagePartials);
1254 N11.resize(numImagePartials);
1257 N11 = prod(trans(coeffImage), coeffImage);
1259 int t = m_sparseNormals.at(blockIndex)->startColumn();
1262 m_sparseNormals.insertMatrixBlock(blockIndex, blockIndex,
1263 numImagePartials, numImagePartials);
1265 (*(*m_sparseNormals[blockIndex])[blockIndex]) += N11;
1268 static matrix<double> N12Image(numImagePartials, 3);
1269 N12Image.resize(numImagePartials, 3);
1272 N12Image = prod(trans(coeffImage), coeffPoint3D);
1276 *N12[blockIndex] += N12Image;
1279 n1Image = prod(trans(coeffImage), coeffRHS);
1284 for (
int i = 0; i < numImagePartials; i++) {
1285 n1(i + t) += n1Image(i);
1289 N22 += prod(trans(coeffPoint3D), coeffPoint3D);
1292 n2 += prod(trans(coeffPoint3D), coeffRHS);
1315 bool BundleAdjust::formPointNormals(symmetric_matrix<double, upper>&N22,
1321 boost::numeric::ublas::bounded_vector<double, 3> &NIC = bundleControlPoint->nicVector();
1329 boost::numeric::ublas::bounded_vector<double, 3> &weights
1330 = bundleControlPoint->weights();
1331 boost::numeric::ublas::bounded_vector<double, 3> &corrections
1332 = bundleControlPoint->corrections();
1334 if (weights(0) > 0.0) {
1335 N22(0,0) += weights(0);
1336 n2(0) += (-weights(0) * corrections(0));
1337 m_bundleResults.incrementNumberConstrainedPointParameters(1);
1340 if (weights(1) > 0.0) {
1341 N22(1,1) += weights(1);
1342 n2(1) += (-weights(1) * corrections(1));
1343 m_bundleResults.incrementNumberConstrainedPointParameters(1);
1346 if (weights(2) > 0.0) {
1347 N22(2,2) += weights(2);
1348 n2(2) += (-weights(2) * corrections(2));
1349 m_bundleResults.incrementNumberConstrainedPointParameters(1);
1358 bundleControlPoint->setAdjustedSurfacePoint(
SurfacePoint);
1361 productATransB(N22, N12, Q);
1364 NIC = prod(N22, n2);
1370 accumProductAlphaAB(-1.0, Q, n2, nj);
1387 bool BundleAdjust::formWeightedNormals(compressed_vector<double> &n1,
1388 vector<double> &nj) {
1390 m_bundleResults.resetNumberConstrainedImageParameters();
1394 for (
int i = 0; i < m_sparseNormals.size(); i++) {
1396 if ( !diagonalBlock )
1399 if (m_bundleSettings->solveTargetBody() && i == 0) {
1400 m_bundleResults.resetNumberConstrainedTargetParameters();
1403 vector<double> weights = m_bundleTargetBody->parameterWeights();
1404 vector<double> corrections = m_bundleTargetBody->parameterCorrections();
1406 int blockSize = diagonalBlock->size1();
1407 for (
int j = 0; j < blockSize; j++) {
1408 if (weights[j] > 0.0) {
1409 (*diagonalBlock)(j,j) += weights[j];
1410 nj[n] -= weights[j] * corrections(j);
1411 m_bundleResults.incrementNumberConstrainedTargetParameters(1);
1420 if (m_bundleSettings->solveTargetBody()) {
1421 observation = m_bundleObservations.at(i-1);
1424 observation = m_bundleObservations.at(i);
1430 int blockSize = diagonalBlock->size1();
1431 for (
int j = 0; j < blockSize; j++) {
1432 if (weights(j) > 0.0) {
1433 (*diagonalBlock)(j,j) += weights(j);
1434 nj[n] -= weights(j) * corrections(j);
1435 m_bundleResults.incrementNumberConstrainedImageParameters(1);
1458 bool BundleAdjust::productATransB(symmetric_matrix <double,upper> &N22,
1462 QMapIterator< int, LinearAlgebra::Matrix * > N12it(N12);
1464 while ( N12it.hasNext() ) {
1467 int rowIndex = N12it.key();
1472 *(Q[rowIndex]) = prod(N22,trans(*(N12it.value())));
1491 QMapIterator<int, LinearAlgebra::Matrix*> N12it(N12);
1492 QMapIterator<int, LinearAlgebra::Matrix*> Qit(Q);
1495 while ( N12it.hasNext() ) {
1498 int rowIndex = N12it.key();
1501 while ( Qit.hasNext() ) {
1504 int columnIndex = Qit.key();
1506 if ( rowIndex > columnIndex ) {
1513 m_sparseNormals.insertMatrixBlock(columnIndex, rowIndex,
1514 N12block->size1(), Qblock->size2());
1516 (*(*m_sparseNormals[columnIndex])[rowIndex]) -= prod(*N12block,*Qblock);
1533 void BundleAdjust::accumProductAlphaAB(
double alpha,
1536 vector<double> &nj) {
1544 QMapIterator<int, LinearAlgebra::Matrix*> Qit(Q);
1546 while ( Qit.hasNext() ) {
1549 int columnIndex = Qit.key();
1554 numParams = m_sparseNormals.at(columnIndex)->startColumn();
1556 for (
unsigned i = 0; i < blockProduct.size(); i++) {
1557 nj(numParams+i) += alpha*blockProduct(i);
1572 bool BundleAdjust::solveSystem() {
1575 if ( !loadCholmodTriplet() ) {
1576 QString msg =
"CHOLMOD: Failed to load Triplet matrix";
1577 throw IException(IException::Programmer, msg, _FILEINFO_);
1581 m_cholmodNormal = cholmod_triplet_to_sparse(m_cholmodTriplet,
1582 m_cholmodTriplet->nnz,
1587 m_L = cholmod_analyze(m_cholmodNormal, &m_cholmodCommon);
1591 cholmod_factorize(m_cholmodNormal, m_L, &m_cholmodCommon);
1594 if (m_cholmodCommon.status == CHOLMOD_NOT_POSDEF) {
1595 QString msg =
"Matrix NOT positive-definite: failure at column " +
toString((
int) m_L->minor);
1603 cholmod_dense *x, *b;
1606 b = cholmod_zeros(m_cholmodNormal->nrow, 1, m_cholmodNormal->xtype, &m_cholmodCommon);
1609 double *px = (
double*)b->x;
1610 for (
int i = 0; i < m_rank; i++) {
1615 x = cholmod_solve(CHOLMOD_A, m_L, b, &m_cholmodCommon);
1618 double *sx = (
double*)x->x;
1619 for (
int i = 0; i < m_rank; i++) {
1620 m_imageSolution[i] = sx[i];
1624 cholmod_free_sparse(&m_cholmodNormal, &m_cholmodCommon);
1625 cholmod_free_dense(&b, &m_cholmodCommon);
1626 cholmod_free_dense(&x, &m_cholmodCommon);
1643 bool BundleAdjust::loadCholmodTriplet() {
1645 if ( m_iteration == 1 ) {
1646 int numElements = m_sparseNormals.numberOfElements();
1647 m_cholmodTriplet = cholmod_allocate_triplet(m_rank, m_rank, numElements,
1648 -1, CHOLMOD_REAL, &m_cholmodCommon);
1650 if ( !m_cholmodTriplet ) {
1651 outputBundleStatus(
"\nTriplet allocation failure\n");
1654 m_cholmodTriplet->nnz = 0;
1657 int *tripletColumns = (
int*) m_cholmodTriplet->i;
1658 int *tripletRows = (
int*) m_cholmodTriplet->j;
1659 double *tripletValues = (
double*)m_cholmodTriplet->x;
1665 int numBlockcolumns = m_sparseNormals.size();
1666 for (
int columnIndex = 0; columnIndex < numBlockcolumns; columnIndex++) {
1670 if ( !normalsColumn ) {
1671 QString status =
"\nSparseBlockColumnMatrix retrieval failure at column " +
1672 QString::number(columnIndex);
1673 outputBundleStatus(status);
1677 int numLeadingColumns = normalsColumn->
startColumn();
1679 QMapIterator< int, LinearAlgebra::Matrix * > it(*normalsColumn);
1681 while ( it.hasNext() ) {
1684 int rowIndex = it.key();
1688 int numLeadingRows = m_sparseNormals.at(rowIndex)->startColumn();
1691 if ( !normalsBlock ) {
1692 QString status =
"\nmatrix block retrieval failure at column ";
1693 status.append(columnIndex);
1694 status.append(
", row ");
1695 status.append(rowIndex);
1696 outputBundleStatus(status);
1697 status =
"Total # of block columns: " + QString::number(numBlockcolumns);
1698 outputBundleStatus(status);
1699 status =
"Total # of blocks: " + QString::number(m_sparseNormals.numberOfBlocks());
1700 outputBundleStatus(status);
1704 if ( columnIndex == rowIndex ) {
1705 for (
unsigned ii = 0; ii < normalsBlock->size1(); ii++) {
1706 for (
unsigned jj = ii; jj < normalsBlock->size2(); jj++) {
1707 entryValue = normalsBlock->at_element(ii,jj);
1708 int entryColumnIndex = jj + numLeadingColumns;
1709 int entryRowIndex = ii + numLeadingRows;
1711 if ( m_iteration == 1 ) {
1712 tripletColumns[numEntries] = entryColumnIndex;
1713 tripletRows[numEntries] = entryRowIndex;
1714 m_cholmodTriplet->nnz++;
1717 tripletValues[numEntries] = entryValue;
1724 for (
unsigned ii = 0; ii < normalsBlock->size1(); ii++) {
1725 for (
unsigned jj = 0; jj < normalsBlock->size2(); jj++) {
1726 entryValue = normalsBlock->at_element(ii,jj);
1727 int entryColumnIndex = jj + numLeadingColumns;
1728 int entryRowIndex = ii + numLeadingRows;
1730 if ( m_iteration ==1 ) {
1731 tripletColumns[numEntries] = entryRowIndex;
1732 tripletRows[numEntries] = entryColumnIndex;
1733 m_cholmodTriplet->nnz++;
1736 tripletValues[numEntries] = entryValue;
1757 bool BundleAdjust::cholmodInverse() {
1761 m_normalInverse.resize(m_rank);
1766 b = cholmod_zeros ( m_rank, 1, CHOLMOD_REAL, &m_cholmodCommon ) ;
1767 double *pb = (
double*)b->x;
1771 for (i = 0; i < m_rank; i++) {
1777 x = cholmod_solve ( CHOLMOD_A, m_L, b, &m_cholmodCommon ) ;
1781 for (j = 0; j <= i; j++) {
1782 m_normalInverse(j, i) = px[j];
1785 cholmod_free_dense(&x,&m_cholmodCommon);
1788 cholmod_free_dense(&b,&m_cholmodCommon);
1806 bool BundleAdjust::invert3x3(symmetric_matrix<double, upper> &m) {
1810 boost::numeric::ublas::symmetric_matrix< double, upper > c = m;
1812 den = m(0, 0) * (m(1, 1) * m(2, 2) - m(1, 2) * m(2, 1))
1813 - m(0, 1) * (m(1, 0) * m(2, 2) - m(1, 2) * m(2, 0))
1814 + m(0, 2) * (m(1, 0) * m(2, 1) - m(1, 1) * m(2, 0));
1817 if (fabs(den) < 1.0e-100) {
1823 m(0, 0) = (c(1, 1) * c(2, 2) - c(1, 2) * c(2, 1)) * det;
1824 m(0, 1) = (c(0, 2) * c(2, 1) - c(0, 1) * c(2, 2)) * det;
1825 m(0, 2) = (c(0, 1) * c(1, 2) - c(0, 2) * c(1, 1)) * det;
1826 m(1, 1) = (c(0, 0) * c(2, 2) - c(0, 2) * c(2, 0)) * det;
1827 m(1, 2) = (c(0, 2) * c(1, 0) - c(0, 0) * c(1, 2)) * det;
1828 m(2, 2) = (c(0, 0) * c(1, 1) - c(0, 1) * c(1, 0)) * det;
1853 bool BundleAdjust::computePartials(matrix<double> &coeffTarget,
1854 matrix<double> &coeffImage,
1855 matrix<double> &coeffPoint3D,
1856 vector<double> &coeffRHS,
1863 int numImagePartials = observation->numberParameters();
1868 if (numImagePartials != m_previousNumberImagePartials) {
1869 coeffImage.resize(2,numImagePartials);
1870 m_previousNumberImagePartials = numImagePartials;
1887 double computedX, computedY;
1889 &computedX, &computedY,
false))) {
1890 QString msg =
"Unable to map apriori surface point for measure ";
1892 throw IException(IException::User, msg, _FILEINFO_);
1896 if (m_bundleSettings->solveTargetBody()) {
1897 observation->computeTargetPartials(coeffTarget, measure, m_bundleSettings, m_bundleTargetBody);
1900 observation->computeImagePartials(coeffImage, measure);
1906 observation->computePoint3DPartials(coeffPoint3D, measure, coordType);
1909 observation->computeRHSPartials(coeffRHS, measure);
1911 double deltaX = coeffRHS(0);
1912 double deltaY = coeffRHS(1);
1914 m_bundleResults.addResidualsProbabilityDistributionObservation(observation->computeObservationValue(measure, deltaX));
1915 m_bundleResults.addResidualsProbabilityDistributionObservation(observation->computeObservationValue(measure, deltaY));
1917 if (m_bundleResults.numberMaximumLikelihoodModels()
1918 > m_bundleResults.maximumLikelihoodModelIndex()) {
1920 double residualR2ZScore = sqrt(deltaX * deltaX + deltaY * deltaY) / sqrt(2.0);
1923 m_bundleResults.addProbabilityDistributionObservation(residualR2ZScore);
1925 int currentModelIndex = m_bundleResults.maximumLikelihoodModelIndex();
1926 double observationWeight = m_bundleResults.maximumLikelihoodModelWFunc(currentModelIndex)
1927 .sqrtWeightScaler(residualR2ZScore);
1928 coeffImage *= observationWeight;
1929 coeffPoint3D *= observationWeight;
1930 coeffRHS *= observationWeight;
1932 if (m_bundleSettings->solveTargetBody()) {
1933 coeffTarget *= observationWeight;
1944 void BundleAdjust::applyParameterCorrections() {
1945 emit(statusBarUpdate(
"Updating Parameters"));
1950 if (m_bundleSettings->solveTargetBody()) {
1951 int numTargetBodyParameters = m_bundleTargetBody->numberParameters();
1953 m_bundleTargetBody->applyParameterCorrections(subrange(m_imageSolution,0,
1954 numTargetBodyParameters));
1956 t += numTargetBodyParameters;
1960 int numObservations = m_bundleObservations.size();
1961 for (
int i = 0; i < numObservations; i++) {
1964 int numParameters = observation->numberParameters();
1966 observation->applyParameterCorrections(subrange(m_imageSolution,t,t+numParameters));
1968 if (m_bundleSettings->solveTargetBody()) {
1972 isisObservation->updateBodyRotation();
1981 int numControlPoints = m_bundleControlPoints.size();
1983 for (
int i = 0; i < numControlPoints; i++) {
1986 if (point->isRejected()) {
1991 point->applyParameterCorrections(m_imageSolution, m_sparseNormals,
1992 m_bundleTargetBody);
2010 double BundleAdjust::computeResiduals() {
2011 emit(statusBarUpdate(
"Computing Residuals"));
2013 double vtpvControl = 0.0;
2014 double vtpvImage = 0.0;
2019 m_xResiduals.Reset();
2020 m_yResiduals.Reset();
2021 m_xyResiduals.Reset();
2024 int numObjectPoints = m_bundleControlPoints.size();
2026 for (
int i = 0; i < numObjectPoints; i++) {
2030 point->computeResiduals();
2032 int numMeasures = point->numberOfMeasures();
2033 for (
int j = 0; j < numMeasures; j++) {
2036 weight = 1.4 * (measure->camera())->PixelPitch();
2037 weight = 1.0 / weight;
2040 vx = measure->focalPlaneMeasuredX() - measure->focalPlaneComputedX();
2041 vy = measure->focalPlaneMeasuredY() - measure->focalPlaneComputedY();
2044 if (measure->isRejected()) {
2048 m_xResiduals.AddData(vx);
2049 m_yResiduals.AddData(vy);
2050 m_xyResiduals.AddData(vx);
2051 m_xyResiduals.AddData(vy);
2053 vtpv += vx * vx * weight + vy * vy * weight;
2059 for (
int i = 0; i < numObjectPoints; i++) {
2063 boost::numeric::ublas::bounded_vector<double, 3> weights = bundleControlPoint->weights();
2064 boost::numeric::ublas::bounded_vector<double, 3> corrections =
2065 bundleControlPoint->corrections();
2067 if ( weights(0) > 0.0 ) {
2068 vtpvControl += corrections(0) * corrections(0) * weights(0);
2070 if ( weights(1) > 0.0 ) {
2071 vtpvControl += corrections(1) * corrections(1) * weights(1);
2073 if ( weights(2) > 0.0 ) {
2074 vtpvControl += corrections(2) * corrections(2) * weights(2);
2081 for (
int i = 0; i < m_bundleObservations.size(); i++) {
2088 for (
int j = 0; j < (int)corrections.size(); j++) {
2089 if (weights[j] > 0.0) {
2091 vtpvImage += v * v * weights[j];
2097 double vtpvTargetBody = 0.0;
2098 if ( m_bundleTargetBody) {
2099 vtpvTargetBody = m_bundleTargetBody->vtpv();
2102 vtpv = vtpv + vtpvControl + vtpvImage + vtpvTargetBody;
2106 m_bundleResults.setRmsXYResiduals(m_xResiduals.Rms(), m_yResiduals.Rms(), m_xyResiduals.Rms());
2118 bool BundleAdjust::wrapUp() {
2122 for (
int i = 0; i < m_bundleControlPoints.size(); i++) {
2124 point->computeResiduals();
2127 computeBundleStatistics();
2147 bool BundleAdjust::computeRejectionLimit() {
2150 int numResiduals = m_bundleResults.numberObservations() / 2;
2152 std::vector<double> residuals;
2154 residuals.resize(numResiduals);
2157 int residualIndex = 0;
2158 int numObjectPoints = m_bundleControlPoints.size();
2159 for (
int i = 0; i < numObjectPoints; i++) {
2163 if ( point->isRejected() ) {
2167 int numMeasures = point->numberOfMeasures();
2168 for (
int j = 0; j < numMeasures; j++) {
2172 if ( measure->isRejected() ) {
2176 vx = measure->sampleResidual();
2177 vy = measure->lineResidual();
2179 residuals[residualIndex] = sqrt(vx*vx + vy*vy);
2186 std::sort(residuals.begin(), residuals.end());
2192 int midpointIndex = numResiduals / 2;
2194 if ( numResiduals % 2 == 0 ) {
2195 median = (residuals[midpointIndex - 1] + residuals[midpointIndex]) / 2;
2198 median = residuals[midpointIndex];
2202 for (
int i = 0; i < numResiduals; i++) {
2203 residuals[i] = fabs(residuals[i] - median);
2206 std::sort(residuals.begin(), residuals.end());
2208 if ( numResiduals % 2 == 0 ) {
2209 medianDev = (residuals[midpointIndex - 1] + residuals[midpointIndex]) / 2;
2212 medianDev = residuals[midpointIndex];
2215 QString status =
"\nmedian deviation: ";
2216 status.append(QString(
"%1").arg(medianDev));
2217 status.append(
"\n");
2218 outputBundleStatus(status);
2220 mad = 1.4826 * medianDev;
2223 status.append(QString(
"%1").arg(mad));
2224 status.append(
"\n");
2225 outputBundleStatus(status);
2227 m_bundleResults.setRejectionLimit(median
2228 + m_bundleSettings->outlierRejectionMultiplier() * mad);
2230 status =
"\nRejection Limit: ";
2231 status.append(QString(
"%1").arg(m_bundleResults.rejectionLimit()));
2232 status.append(
"\n");
2233 outputBundleStatus(status);
2246 bool BundleAdjust::flagOutliers() {
2249 int totalNumRejected = 0;
2251 int maxResidualIndex;
2254 double usedRejectionLimit = m_bundleResults.rejectionLimit();
2258 int numComingBack = 0;
2260 int numObjectPoints = m_bundleControlPoints.size();
2262 outputBundleStatus(
"\n");
2263 for (
int i = 0; i < numObjectPoints; i++) {
2266 point->zeroNumberOfRejectedMeasures();
2269 maxResidualIndex = -1;
2272 int numMeasures = point->numberOfMeasures();
2273 for (
int j = 0; j < numMeasures; j++) {
2277 vx = measure->sampleResidual();
2278 vy = measure->lineResidual();
2280 sumSquares = sqrt(vx*vx + vy*vy);
2283 if ( sumSquares <= usedRejectionLimit ) {
2286 if ( measure->isRejected() ) {
2287 QString status =
"Coming back in: ";
2288 status.append(QString(
"%1").arg(point->id().toLatin1().data()));
2289 status.append(
"\r");
2290 outputBundleStatus(status);
2292 m_controlNet->DecrementNumberOfRejectedMeasuresInImage(measure->cubeSerialNumber());
2295 measure->setRejected(
false);
2300 if ( measure->isRejected() ) {
2306 if ( sumSquares > maxResidual ) {
2307 maxResidual = sumSquares;
2308 maxResidualIndex = j;
2313 if ( maxResidual == -1.0 || maxResidual <= usedRejectionLimit ) {
2314 point->setNumberOfRejectedMeasures(numRejected);
2320 if ((numMeasures - (numRejected + 1)) < 2) {
2321 point->setNumberOfRejectedMeasures(numRejected);
2330 rejected->setRejected(
true);
2332 point->setNumberOfRejectedMeasures(numRejected);
2333 m_controlNet->IncrementNumberOfRejectedMeasuresInImage(rejected->cubeSerialNumber());
2337 if ( ( numMeasures-numRejected ) < 2 ) {
2338 point->setRejected(
true);
2339 QString status =
"Rejecting Entire Point: ";
2340 status.append(QString(
"%1").arg(point->id().toLatin1().data()));
2341 status.append(
"\r");
2342 outputBundleStatus(status);
2345 point->setRejected(
false);
2349 int numberRejectedObservations = 2*totalNumRejected;
2351 QString status =
"\nRejected Observations:";
2352 status.append(QString(
"%1").arg(numberRejectedObservations));
2353 status.append(
" (Rejection Limit:");
2354 status.append(QString(
"%1").arg(usedRejectionLimit));
2355 status.append(
")\n");
2356 outputBundleStatus(status);
2358 m_bundleResults.setNumberRejectedObservations(numberRejectedObservations);
2360 status =
"\nMeasures that came back: ";
2361 status.append(QString(
"%1").arg(numComingBack));
2362 status.append(
"\n");
2363 outputBundleStatus(status);
2378 if (m_imageLists.count() > 0) {
2379 return m_imageLists;
2381 else if (m_serialNumberList->size() > 0) {
2384 for (
int i = 0; i < m_serialNumberList->size(); i++) {
2385 Image *image =
new Image(m_serialNumberList->fileName(i));
2389 m_imageLists.append(imgList);
2392 QString msg =
"Invalid image in serial number list\n";
2393 throw IException(IException::Programmer, msg, _FILEINFO_);
2397 QString msg =
"No images used in bundle adjust\n";
2398 throw IException(IException::Programmer, msg, _FILEINFO_);
2401 return m_imageLists;
2425 bool BundleAdjust::errorPropagation() {
2426 emit(statusBarUpdate(
"Error Propagation"));
2428 cholmod_free_triplet(&m_cholmodTriplet, &m_cholmodCommon);
2429 cholmod_free_sparse(&m_cholmodNormal, &m_cholmodCommon);
2435 double sigma0Squared = m_bundleResults.sigma0() * m_bundleResults.sigma0();
2437 int numObjectPoints = m_bundleControlPoints.size();
2439 std::string currentTime = iTime::CurrentLocalTime().toLatin1().data();
2441 QString status =
" Time: ";
2442 status.append(currentTime.c_str());
2443 status.append(
"\n\n");
2444 outputBundleStatus(status);
2447 std::vector< symmetric_matrix<double> > pointCovariances(numObjectPoints,
2448 symmetric_matrix<double>(3));
2449 for (
int d = 0; d < numObjectPoints; d++) {
2450 pointCovariances[d].clear();
2456 b = cholmod_zeros ( m_rank, 1, CHOLMOD_REAL, &m_cholmodCommon );
2457 double *pb = (
double*)b->x;
2464 FileName matrixFile(m_bundleSettings->outputFilePrefix() +
"inverseMatrix.dat");
2468 QFile matrixOutput(matrixFile.expanded());
2471 if (m_bundleSettings->createInverseMatrix()) {
2473 matrixOutput.open(QIODevice::WriteOnly);
2475 QDataStream outStream(&matrixOutput);
2478 int columnIndex = 0;
2480 int numBlockColumns = m_sparseNormals.size();
2481 for (i = 0; i < numBlockColumns; i++) {
2488 inverseMatrix.insertMatrixBlock(i, numRows, numColumns);
2489 inverseMatrix.zeroBlocks();
2494 inverseMatrix.insertMatrixBlock(i, numRows, numColumns);
2495 inverseMatrix.zeroBlocks();
2501 inverseMatrix.wipe();
2504 for (j = 0; j < (i+1); j++) {
2508 inverseMatrix.insertMatrixBlock(j, numRows, numColumns);
2516 for (j = 0; j < numColumns; j++) {
2517 if ( columnIndex > 0 ) {
2518 pb[columnIndex - 1] = 0.0;
2520 pb[columnIndex] = 1.0;
2522 x = cholmod_solve ( CHOLMOD_A, m_L, b, &m_cholmodCommon );
2527 for (k = 0; k < inverseMatrix.size(); k++) {
2530 int sz1 = matrix->size1();
2532 for (
int ii = 0; ii < sz1; ii++) {
2533 (*matrix)(ii,localCol) = px[ii + rp];
2535 rp += matrix->size1();
2541 cholmod_free_dense(&x,&m_cholmodCommon);
2545 if (m_bundleSettings->solveTargetBody() && i == 0) {
2546 vector< double > &adjustedSigmas = m_bundleTargetBody->adjustedSigmas();
2547 matrix< double > *targetCovMatrix = inverseMatrix.value(i);
2549 for (
int z = 0; z < numColumns; z++)
2550 adjustedSigmas[z] = sqrt((*targetCovMatrix)(z,z))*m_bundleResults.sigma0();
2555 if (m_bundleSettings->solveTargetBody()) {
2556 observation = m_bundleObservations.at(i-1);
2559 observation = m_bundleObservations.at(i);
2561 vector< double > &adjustedSigmas = observation->adjustedSigmas();
2562 matrix< double > *imageCovMatrix = inverseMatrix.value(i);
2563 for (
int z = 0; z < numColumns; z++) {
2564 adjustedSigmas[z] = sqrt((*imageCovMatrix)(z,z))*m_bundleResults.sigma0();
2569 if (m_bundleSettings->createInverseMatrix()) {
2570 outStream << inverseMatrix;
2575 for (j = 0; j < numObjectPoints; j++) {
2576 emit(pointUpdate(j+1));
2578 if ( point->isRejected() ) {
2584 QString status =
"\rError Propagation: Inverse Block ";
2585 status.append(QString::number(i+1));
2586 status.append(
" of ");
2587 status.append(QString::number(numBlockColumns));
2588 status.append(
"; Point ");
2589 status.append(QString::number(j+1));
2590 status.append(
" of ");
2591 status.append(QString::number(numObjectPoints));
2592 outputBundleStatus(status);
2603 boost::numeric::ublas::symmetric_matrix<double> &covariance = pointCovariances[pointIndex];
2614 QMapIterator< int, LinearAlgebra::Matrix * > it(Q);
2615 while ( it.hasNext() ) {
2618 int nKey = it.key();
2626 if ( !secondQBlock ) {
2632 if ( !inverseBlock ) {
2636 T = prod(*inverseBlock, trans(*firstQBlock));
2637 T = prod(*secondQBlock,T);
2647 catch (std::exception &e) {
2648 outputBundleStatus(
"\n\n");
2649 QString msg =
"Input data and settings are not sufficiently stable "
2650 "for error propagation.";
2651 throw IException(IException::User, msg, _FILEINFO_);
2658 if (m_bundleSettings->createInverseMatrix()) {
2660 matrixOutput.close();
2662 m_bundleResults.setCorrMatCovFileName(matrixFile);
2666 m_sparseNormals.wipe();
2669 cholmod_free_dense(&b,&m_cholmodCommon);
2671 outputBundleStatus(
"\n\n");
2675 status =
"\rFilling point covariance matrices: Time ";
2676 status.append(currentTime.c_str());
2677 outputBundleStatus(status);
2678 outputBundleStatus(
"\n\n");
2683 for (j = 0; j < numObjectPoints; j++) {
2687 if ( point->isRejected() ) {
2692 status =
"\rError Propagation: Filling point covariance matrices ";
2693 status.append(QString(
"%1").arg(j+1));
2694 status.append(
" of ");
2695 status.append(QString(
"%1").arg(numObjectPoints));
2696 status.append(
"\r");
2697 outputBundleStatus(status);
2701 boost::numeric::ublas::symmetric_matrix<double> &covariance = pointCovariances[pointIndex];
2709 boost::numeric::ublas::symmetric_matrix <double,boost::numeric::ublas::upper> pCovar;
2711 if (m_bundleSettings->controlPointCoordTypeBundle() == SurfacePoint::Latitudinal) {
2712 pCovar =
SurfacePoint.GetSphericalMatrix(SurfacePoint::Kilometers);
2716 pCovar =
SurfacePoint.GetRectangularMatrix(SurfacePoint::Kilometers);
2718 pCovar += covariance;
2719 pCovar *= sigma0Squared;
2774 return m_controlNet;
2784 return m_serialNumberList;
2793 int BundleAdjust::numberOfImages()
const {
2794 return m_serialNumberList->
size();
2806 QString BundleAdjust::fileName(
int i) {
2807 return m_serialNumberList->fileName(i);
2816 double BundleAdjust::iteration()
const {
2832 return m_controlNet->Camera(i)->instrumentRotation()->Cache(
"InstrumentPointing");
2847 return m_controlNet->Camera(i)->instrumentPosition()->Cache(
"InstrumentPosition");
2859 QString BundleAdjust::modelState(
int i) {
2862 QString msg =
"Cannot get model state for image [" +
toString(i) +
2863 "] because it is not a CSM camera model.";
2864 throw IException(IException::Programmer, msg, _FILEINFO_);
2880 void BundleAdjust::iterationSummary() {
2881 QString iterationNumber;
2883 if ( m_bundleResults.converged() ) {
2884 iterationNumber =
"Iteration" +
toString(m_iteration) +
": Final";
2887 iterationNumber =
"Iteration" +
toString(m_iteration);
2890 PvlGroup summaryGroup(iterationNumber);
2893 toString( m_bundleResults.sigma0() ) );
2895 toString( m_bundleResults.numberObservations() ) );
2896 summaryGroup +=
PvlKeyword(
"Constrained_Point_Parameters",
2897 toString( m_bundleResults.numberConstrainedPointParameters() ) );
2898 summaryGroup +=
PvlKeyword(
"Constrained_Image_Parameters",
2899 toString( m_bundleResults.numberConstrainedImageParameters() ) );
2900 if (m_bundleSettings->bundleTargetBody()) {
2901 summaryGroup +=
PvlKeyword(
"Constrained_Target_Parameters",
2902 toString( m_bundleResults.numberConstrainedTargetParameters() ) );
2904 summaryGroup +=
PvlKeyword(
"Unknown_Parameters",
2905 toString( m_bundleResults.numberUnknownParameters() ) );
2906 summaryGroup +=
PvlKeyword(
"Degrees_of_Freedom",
2907 toString( m_bundleResults.degreesOfFreedom() ) );
2908 summaryGroup +=
PvlKeyword(
"Rejected_Measures",
2909 toString( m_bundleResults.numberRejectedObservations()/2) );
2911 if ( m_bundleResults.numberMaximumLikelihoodModels() >
2912 m_bundleResults.maximumLikelihoodModelIndex() ) {
2915 summaryGroup +=
PvlKeyword(
"Maximum_Likelihood_Tier: ",
2916 toString( m_bundleResults.maximumLikelihoodModelIndex() ) );
2917 summaryGroup +=
PvlKeyword(
"Median_of_R^2_residuals: ",
2918 toString( m_bundleResults.maximumLikelihoodMedianR2Residuals() ) );
2921 if ( m_bundleResults.converged() ) {
2922 summaryGroup +=
PvlKeyword(
"Converged",
"TRUE");
2923 summaryGroup +=
PvlKeyword(
"TotalElapsedTime",
toString( m_bundleResults.elapsedTime() ) );
2925 if (m_bundleSettings->errorPropagation()) {
2926 summaryGroup +=
PvlKeyword(
"ErrorPropagationElapsedTime",
2927 toString( m_bundleResults.elapsedTimeErrorProp() ) );
2931 std::ostringstream ostr;
2932 ostr << summaryGroup << std::endl;
2933 m_iterationSummary += QString::fromStdString( ostr.str() );
2935 if (m_printSummary && iApp != NULL) {
2936 Application::Log(summaryGroup);
2939 std::cout << summaryGroup << std::endl;
2949 bool BundleAdjust::isConverged() {
2950 return m_bundleResults.converged();
2959 bool BundleAdjust::isAborted() {
2971 QString BundleAdjust::iterationSummaryGroup()
const {
2972 return m_iterationSummary;
2985 void BundleAdjust::outputBundleStatus(QString status) {
2987 printf(
"%s", status.toStdString().c_str());
2989 else if (QCoreApplication::applicationName() !=
"ipce") {
2990 printf(
"%s", status.toStdString().c_str());
3031 bool BundleAdjust::computeBundleStatistics() {
3036 int numberImages = m_serialNumberList->size();
3041 int numObjectPoints = m_bundleControlPoints.size();
3042 for (
int i = 0; i < numObjectPoints; i++) {
3046 if (point->isRejected()) {
3050 int numMeasures = point->numberOfMeasures();
3051 for (
int j = 0; j < numMeasures; j++) {
3055 if (measure->isRejected()) {
3059 double sampleResidual = fabs(measure->sampleResidual());
3060 double lineResidual = fabs(measure->lineResidual());
3063 int imageIndex = m_serialNumberList->serialNumberIndex(measure->cubeSerialNumber());
3066 rmsImageSampleResiduals[imageIndex].AddData(sampleResidual);
3067 rmsImageLineResiduals[imageIndex].AddData(lineResidual);
3068 rmsImageResiduals[imageIndex].AddData(lineResidual);
3069 rmsImageResiduals[imageIndex].AddData(sampleResidual);
3074 if (m_bundleSettings->errorPropagation()) {
3080 QString minSigmaCoord1PointId =
"";
3083 QString maxSigmaCoord1PointId =
"";
3087 QString minSigmaCoord2PointId =
"";
3090 QString maxSigmaCoord2PointId =
"";
3094 QString minSigmaCoord3PointId =
"";
3097 QString maxSigmaCoord3PointId =
"";
3104 Distance sigmaCoord1Dist, sigmaCoord2Dist, sigmaCoord3Dist;
3107 int numPoints = m_bundleControlPoints.size();
3109 for (
int i = 0; i < numPoints; i++) {
3113 maxSigmaCoord1Dist = point->adjustedSurfacePoint().GetSigmaDistance(type,
3115 minSigmaCoord1Dist = maxSigmaCoord1Dist;
3117 maxSigmaCoord2Dist = point->adjustedSurfacePoint().GetSigmaDistance(type,
3119 minSigmaCoord2Dist = maxSigmaCoord2Dist;
3121 maxSigmaCoord1PointId = point->id();
3122 maxSigmaCoord2PointId = maxSigmaCoord1PointId;
3123 minSigmaCoord1PointId = maxSigmaCoord1PointId;
3124 minSigmaCoord2PointId = maxSigmaCoord1PointId;
3127 if (m_bundleSettings->solveRadius() || type == SurfacePoint::Rectangular) {
3128 maxSigmaCoord3Dist = point->adjustedSurfacePoint().GetSigmaDistance(type,
3129 SurfacePoint::Three);
3130 minSigmaCoord3Dist = maxSigmaCoord3Dist;
3132 maxSigmaCoord3PointId = maxSigmaCoord1PointId;
3133 minSigmaCoord3PointId = maxSigmaCoord1PointId;
3138 for (
int i = 0; i < numPoints; i++) {
3142 sigmaCoord1Dist = point->adjustedSurfacePoint().GetSigmaDistance(type,
3144 sigmaCoord2Dist = point->adjustedSurfacePoint().GetSigmaDistance(type,
3146 sigmaCoord3Dist = point->adjustedSurfacePoint().GetSigmaDistance(type,
3147 SurfacePoint::Three);
3153 if (sigmaCoord1Dist > maxSigmaCoord1Dist) {
3154 maxSigmaCoord1Dist = sigmaCoord1Dist;
3155 maxSigmaCoord1PointId = point->id();
3157 if (sigmaCoord2Dist > maxSigmaCoord2Dist) {
3158 maxSigmaCoord2Dist = sigmaCoord2Dist;
3159 maxSigmaCoord2PointId = point->id();
3161 if (m_bundleSettings->solveRadius() || type == SurfacePoint::Rectangular) {
3162 if (sigmaCoord3Dist > maxSigmaCoord3Dist) {
3163 maxSigmaCoord3Dist = sigmaCoord3Dist;
3164 maxSigmaCoord3PointId = point->id();
3167 if (sigmaCoord1Dist < minSigmaCoord1Dist) {
3168 minSigmaCoord1Dist = sigmaCoord1Dist;
3169 minSigmaCoord1PointId = point->id();
3171 if (sigmaCoord2Dist < minSigmaCoord2Dist) {
3172 minSigmaCoord2Dist = sigmaCoord2Dist;
3173 minSigmaCoord2PointId = point->id();
3175 if (m_bundleSettings->solveRadius() || type == SurfacePoint::Rectangular) {
3176 if (sigmaCoord3Dist < minSigmaCoord3Dist) {
3177 minSigmaCoord3Dist = sigmaCoord3Dist;
3178 minSigmaCoord3PointId = point->id();
3184 m_bundleResults.resizeSigmaStatisticsVectors(numberImages);
3186 m_bundleResults.setSigmaCoord1Range(minSigmaCoord1Dist, maxSigmaCoord1Dist,
3187 minSigmaCoord1PointId, maxSigmaCoord1PointId);
3189 m_bundleResults.setSigmaCoord2Range(minSigmaCoord2Dist, maxSigmaCoord2Dist,
3190 minSigmaCoord2PointId, maxSigmaCoord2PointId);
3192 m_bundleResults.setSigmaCoord3Range(minSigmaCoord3Dist, maxSigmaCoord3Dist,
3193 minSigmaCoord3PointId, maxSigmaCoord3PointId);
3195 m_bundleResults.setRmsFromSigmaStatistics(sigmaCoord1Stats.
Rms(),
3196 sigmaCoord2Stats.
Rms(),
3197 sigmaCoord3Stats.
Rms());
3199 m_bundleResults.setRmsImageResidualLists(rmsImageLineResiduals.toList(),
3200 rmsImageSampleResiduals.toList(),
3201 rmsImageResiduals.toList());