LinearAlgebra.cpp
Go to the documentation of this file.
00001 // ****************************************************************************
00002 // This file is part of the Integrating Vision Toolkit (IVT).
00003 //
00004 // The IVT is maintained by the Karlsruhe Institute of Technology (KIT)
00005 // (www.kit.edu) in cooperation with the company Keyetech (www.keyetech.de).
00006 //
00007 // Copyright (C) 2014 Karlsruhe Institute of Technology (KIT).
00008 // All rights reserved.
00009 //
00010 // Redistribution and use in source and binary forms, with or without
00011 // modification, are permitted provided that the following conditions are met:
00012 //
00013 // 1. Redistributions of source code must retain the above copyright
00014 //    notice, this list of conditions and the following disclaimer.
00015 //
00016 // 2. Redistributions in binary form must reproduce the above copyright
00017 //    notice, this list of conditions and the following disclaimer in the
00018 //    documentation and/or other materials provided with the distribution.
00019 //
00020 // 3. Neither the name of the KIT nor the names of its contributors may be
00021 //    used to endorse or promote products derived from this software
00022 //    without specific prior written permission.
00023 //
00024 // THIS SOFTWARE IS PROVIDED BY THE KIT AND CONTRIBUTORS “AS IS” AND ANY
00025 // EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00026 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00027 // DISCLAIMED. IN NO EVENT SHALL THE KIT OR CONTRIBUTORS BE LIABLE FOR ANY
00028 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00029 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00031 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00032 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
00033 // THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00034 // ****************************************************************************
00035 // ****************************************************************************
00036 // Filename:  LinearAlgebra.cpp
00037 // Author:    Pedram Azad
00038 // Date:      23.01.2008
00039 // ****************************************************************************
00040 
00041 
00042 // ****************************************************************************
00043 // Includes
00044 // ****************************************************************************
00045 
00046 #include <new> // for explicitly using correct new/delete operators on VC DSPs
00047 
00048 #include "LinearAlgebra.h"
00049 #include "Image/ImageProcessor.h"
00050 #include "Helpers/Quicksort.h"
00051 #include "Helpers/helpers.h"
00052 #include "Math/FloatMatrix.h"
00053 #include "Math/FloatVector.h"
00054 #include "Math/DoubleMatrix.h"
00055 #include "Math/DoubleVector.h"
00056 
00057 #include <stdio.h>
00058 #include <math.h>
00059 #include <float.h>
00060 #include <string.h>
00061 
00062 
00063 
00064 // ****************************************************************************
00065 // Functions
00066 // ****************************************************************************
00067 
00068 void LinearAlgebra::SelfProduct(const CFloatMatrix *pMatrix, CFloatMatrix *pResultMatrix, bool AAT)
00069 {
00070         if (
00071                 (AAT && (pResultMatrix->columns != pMatrix->rows || pResultMatrix->rows != pMatrix->rows)) ||
00072                 (!AAT && (pResultMatrix->columns != pMatrix->columns || pResultMatrix->rows != pMatrix->columns))
00073         )
00074         {
00075                 printf("error: matrix dimensions do not match for LinearAlgebra::SelfProduct\n");
00076                 return;
00077         }
00078 
00079         if (!AAT)
00080         {
00081                 CFloatMatrix *pTransposedMatrix = new CFloatMatrix(pMatrix->rows, pMatrix->columns);
00082                 Transpose(pMatrix, pTransposedMatrix);
00083                 pMatrix = pTransposedMatrix;
00084         }
00085 
00086         const int columns = pMatrix->columns;
00087         const int rows = pMatrix->rows;
00088 
00089         const float *data = pMatrix->data;
00090         float *result = pResultMatrix->data;
00091 
00092         if (data != result)
00093         {
00094                 for (int i = 0, input_offset1 = 0; i < rows; i++, input_offset1 += columns)
00095                 {
00096                         for (int j = i, input_offset2 = input_offset1; j < rows; j++, input_offset2 += columns)
00097                         {
00098                                 const float *data1 = data + input_offset1;
00099                                 const float *data2 = data + input_offset2;
00100                                 float sum = 0;
00101 
00102                                 for (int k = 0; k < columns; k++)
00103                                         sum += data1[k] * data2[k];
00104 
00105                                 result[i * rows + j] = result[j * rows + i] = sum;
00106                         }
00107                 }
00108         }
00109         else
00110         {
00111                 CFloatMatrix temp(pResultMatrix);
00112                 float *temp_data = temp.data;
00113 
00114                 for (int i = 0, input_offset1 = 0; i < rows; i++, input_offset1 += columns)
00115                 {
00116                         for (int j = i, input_offset2 = input_offset1; j < rows; j++, input_offset2 += columns)
00117                         {
00118                                 const float *data1 = data + input_offset1;
00119                                 const float *data2 = data + input_offset2;
00120                                 float sum = 0;
00121 
00122                                 for (int k = 0; k < columns; k++)
00123                                         sum += data1[k] * data2[k];
00124 
00125                                 temp_data[i * rows + j] = temp_data[j * rows + i] = sum;
00126                         }
00127                 }
00128 
00129                 memcpy(pResultMatrix->data, temp_data, pResultMatrix->rows * pResultMatrix->columns * sizeof(float));
00130         }
00131 
00132         if (!AAT)
00133                 delete pMatrix;
00134 }
00135 
00136 void LinearAlgebra::MulMatMat(const CFloatMatrix *A, const CFloatMatrix *B, CFloatMatrix *pResultMatrix, bool bTransposeB)
00137 {
00138         if (!bTransposeB && (A->columns != B->rows || pResultMatrix->columns != B->columns || pResultMatrix->rows != A->rows))
00139         {
00140                 printf("error: matrices A, B, and pResultMatrix do not satisfy requirements for LinearAlgebra::Multiply\n");
00141                 return;
00142         }
00143 
00144         if (bTransposeB && (A->columns != B->columns || pResultMatrix->columns != B->rows || pResultMatrix->rows != A->rows))
00145         {
00146                 printf("error: matrices A, B, and pResultMatrix do not satisfy requirements for LinearAlgebra::Multiply\n");
00147                 return;
00148         }
00149 
00150         const float *data1 = A->data;
00151         const float *data2 = B->data;
00152         float *result = pResultMatrix->data;
00153 
00154         const int nSize = pResultMatrix->columns * pResultMatrix->rows;
00155 
00156         if (bTransposeB)
00157         {
00158                 const int rowsA = A->rows;
00159                 const int rowsB = B->rows;
00160                 const int columns = A->columns;
00161 
00162                 if (data1 != result && data2 != result)
00163                 {
00164                         for (int i = 0, input_offset1 = 0, output_offset = 0; i < rowsA; i++, input_offset1 += columns)
00165                         {
00166                                 for (int j = 0, input_offset2 = 0; j < rowsB; j++, input_offset2 += columns, output_offset++)
00167                                 {
00168                                         const float *data1_ = data1 + input_offset1;
00169                                         const float *data2_ = data2 + input_offset2;
00170                                         float sum = 0;
00171 
00172                                         for (int k = 0; k < columns; k++)
00173                                                 sum += data1_[k] * data2_[k];
00174 
00175                                         result[output_offset] = sum;
00176                                 }
00177                         }
00178                 }
00179                 else
00180                 {
00181                         CFloatMatrix temp(pResultMatrix);
00182                         float *temp_data = temp.data;
00183 
00184                         int l;
00185 
00186                         for (l = 0; l < nSize; l++)
00187                                 temp_data[l] = 0;
00188 
00189                         for (int i = 0, input_offset1 = 0, output_offset = 0; i < rowsA; i++, input_offset1 += columns)
00190                         {
00191                                 for (int j = 0, input_offset2 = input_offset1; j < rowsB; j++, input_offset2 += columns, output_offset++)
00192                                 {
00193                                         const float *data1_ = data1 + input_offset1;
00194                                         const float *data2_ = data2 + input_offset2;
00195                                         float sum = 0;
00196 
00197                                         for (int k = 0; k < columns; k++)
00198                                                 sum += data1_[k] * data2_[k];
00199 
00200                                         temp_data[output_offset] = sum;
00201                                 }
00202                         }
00203 
00204                         for (l = 0; l < nSize; l++)
00205                                 result[l] = temp_data[l];
00206                 }
00207         }
00208         else
00209         {
00210                 const int i_max = A->rows;
00211                 const int j_max = B->columns;
00212                 const int k_max = A->columns;
00213 
00214                 // not optimized yet
00215                 if (data1 != result && data2 != result)
00216                 {
00217                         for (int l = 0; l < nSize; l++)
00218                                 result[l] = 0;
00219 
00220                         for (int i = 0, input1_offset = 0; i < i_max; i++)
00221                         {
00222                                 const int result_offset_start = i * j_max;
00223 
00224                                 for (int k = 0, input2_offset = 0; k < k_max; k++, input1_offset++)
00225                                         for (int j = 0, result_offset = result_offset_start; j < j_max; j++, result_offset++, input2_offset++)
00226                                                 result[result_offset] += data1[input1_offset] * data2[input2_offset];
00227                         }
00228                 }
00229                 else
00230                 {
00231                         CFloatMatrix temp(pResultMatrix);
00232                         float *temp_data = temp.data;
00233 
00234                         int l;
00235 
00236                         for (l = 0; l < nSize; l++)
00237                                 temp_data[l] = 0;
00238 
00239                         for (int i = 0, input1_offset = 0; i < i_max; i++)
00240                         {
00241                                 const int result_offset_start = i * j_max;
00242 
00243                                 for (int k = 0, input2_offset = 0; k < k_max; k++, input1_offset++)
00244                                         for (int j = 0, result_offset = result_offset_start; j < j_max; j++, result_offset++, input2_offset++)
00245                                                 temp_data[result_offset] += data1[input1_offset] * data2[input2_offset];
00246                         }
00247 
00248                         for (l = 0; l < nSize; l++)
00249                                 result[l] = temp_data[l];
00250                 }
00251         }
00252 }
00253 
00254 void LinearAlgebra::Transpose(const CFloatMatrix *pMatrix, CFloatMatrix *pResultMatrix)
00255 {
00256         if (pMatrix->columns != pResultMatrix->rows || pMatrix->rows != pResultMatrix->columns)
00257         {
00258                 printf("error: input and output matrix do not match LinearAlgebra::Transpose\n");
00259                 return;
00260         }
00261 
00262         const int rows = pMatrix->rows;
00263         const int columns = pMatrix->columns;
00264         const float *input = pMatrix->data;
00265         float *output = pResultMatrix->data;
00266 
00267         if (input != output)
00268         {
00269                 for (int i = 0, input_offset = 0; i < rows; i++)
00270                         for (int j = 0, output_offset = i; j < columns; j++, input_offset++, output_offset += rows)
00271                                 output[output_offset] = input[input_offset];
00272         }
00273         else
00274         {
00275                 // not optimized yet
00276                 CFloatMatrix temp(pResultMatrix);
00277                 float *temp_data = temp.data;
00278 
00279                 int i, input_offset;
00280 
00281                 for (i = 0, input_offset = 0; i < rows; i++)
00282                         for (int j = 0, output_offset = i; j < columns; j++, input_offset++, output_offset += rows)
00283                                 temp_data[output_offset] = input[input_offset];
00284 
00285                 const int nSize = rows * columns;
00286 
00287                 for (i = 0; i < nSize; i++)
00288                         output[i] = temp_data[i];
00289         }
00290 }
00291 
00292 void LinearAlgebra::MulMatVec(const CFloatMatrix *pMatrix, const CFloatVector *pVector, CFloatVector *pResultVector)
00293 {
00294         if (pMatrix->columns != pVector->dimension || pMatrix->rows != pResultVector->dimension)
00295         {
00296                 printf("error: input matrix and vector and output vector do not match for CFloatMatrix::Multiply\n");
00297                 return;
00298         }
00299         
00300         const int rows = pMatrix->rows;
00301         const int columns = pMatrix->columns;
00302         const float *data_m = pMatrix->data;
00303         const float *data_v = pVector->data;
00304         float *data_r = pResultVector->data;
00305         
00306         if (data_r != data_v)
00307         {
00308                 for (int i = 0, offset = 0; i < rows; i++)
00309                 {
00310                         float sum = 0.0f;
00311                         
00312                         for (int j = 0; j < columns; j++, offset++)
00313                                 sum += data_m[offset] * data_v[j];
00314                                 
00315                         data_r[i] = sum;
00316                 }
00317         }
00318         else
00319         {
00320                 float *temp = new float[rows];
00321                 int i, offset;
00322 
00323                 for (i = 0, offset = 0; i < rows; i++)
00324                 {
00325                         float sum = 0.0f;
00326                         
00327                         for (int j = 0; j < columns; j++, offset++)
00328                                 sum += data_m[offset] * data_v[j];
00329                                 
00330                         temp[i] = sum;
00331                 }
00332 
00333                 for (i = 0; i < rows; i++)
00334                         data_r[i] = temp[i];
00335 
00336                 delete [] temp;
00337         }
00338 }
00339 
00340 void LinearAlgebra::MulMatVec(const CFloatMatrix *pMatrix, const CFloatVector *pVector1, const CFloatVector *pVector2, CFloatVector *pResultVector)
00341 {
00342         MulMatVec(pMatrix, pVector1, pResultVector);
00343         AddToVec(pResultVector, pVector2);
00344 }
00345 
00346 void LinearAlgebra::AddMatMat(const CFloatMatrix *pMatrix1, const CFloatMatrix *pMatrix2, CFloatMatrix *pResultMatrix)
00347 {
00348         if (pMatrix1->rows != pMatrix2->rows || pMatrix1->columns != pMatrix2->columns ||
00349                 pMatrix1->rows != pResultMatrix->rows || pMatrix1->columns != pResultMatrix->columns)
00350         {
00351                 printf("error: matrix dimensions do not match in LinearAlgebra::AddMatMat\n");
00352                 return;
00353         }
00354 
00355         const int nSize = pMatrix1->rows * pMatrix1->columns;
00356         const float *data1 = pMatrix1->data;
00357         const float *data2 = pMatrix2->data;
00358         float *result = pResultMatrix->data;
00359 
00360         for (int i = 0; i < nSize; i++)
00361                 result[i] = data1[i] + data2[i];
00362 }
00363 
00364 void LinearAlgebra::SubtractMatMat(const CFloatMatrix *pMatrix1, const CFloatMatrix *pMatrix2, CFloatMatrix *pResultMatrix)
00365 {
00366         if (pMatrix1->rows != pMatrix2->rows || pMatrix1->columns != pMatrix2->columns ||
00367                 pMatrix1->rows != pResultMatrix->rows || pMatrix1->columns != pResultMatrix->columns)
00368         {
00369                 printf("error: matrix dimensions do not match in LinearAlgebra::SubtractMatMat\n");
00370                 return;
00371         }
00372 
00373         const int nSize = pMatrix1->rows * pMatrix1->columns;
00374         const float *data1 = pMatrix1->data;
00375         const float *data2 = pMatrix2->data;
00376         float *result = pResultMatrix->data;
00377 
00378         for (int i = 0; i < nSize; i++)
00379                 result[i] = data1[i] - data2[i];
00380 }
00381 
00382 void LinearAlgebra::AddVecVec(const CFloatVector *pVector1, const CFloatVector *pVector2, CFloatVector *pResultVector)
00383 {
00384         if (pVector1->dimension != pVector2->dimension || pVector1->dimension != pResultVector->dimension)
00385         {
00386                 printf("error: vector dimensions do not match in LinearAlgebra::AddVecVec\n");
00387                 return;
00388         }
00389 
00390         const int nDimension = pVector1->dimension;
00391         const float *data1 = pVector1->data;
00392         const float *data2 = pVector2->data;
00393         float *result = pResultVector->data;
00394 
00395         for (int i = 0; i < nDimension; i++)
00396                 result[i] = data1[i] + data2[i];
00397 }
00398 
00399 void LinearAlgebra::SubtractVecVec(const CFloatVector *pVector1, const CFloatVector *pVector2, CFloatVector *pResultVector)
00400 {
00401         if (pVector1->dimension != pVector2->dimension || pVector1->dimension != pResultVector->dimension)
00402         {
00403                 printf("error: vector dimensions do not match in LinearAlgebra::SubtractVecVec\n");
00404                 return;
00405         }
00406 
00407         const int nDimension = pVector1->dimension;
00408         const float *data1 = pVector1->data;
00409         const float *data2 = pVector2->data;
00410         float *result = pResultVector->data;
00411 
00412         for (int i = 0; i < nDimension; i++)
00413                 result[i] = data1[i] - data2[i];
00414 }
00415 
00416 void LinearAlgebra::AddToMat(CFloatMatrix *pMatrix, const CFloatMatrix *pMatrixToAdd)
00417 {
00418         if (pMatrix->rows != pMatrixToAdd->rows || pMatrix->columns != pMatrixToAdd->columns)
00419         {
00420                 printf("error: matrix dimensions do not match in LinearAlgebra::AddToMat\n");
00421                 return;
00422         }
00423 
00424         const int nSize = pMatrix->rows * pMatrix->columns;
00425         float *data = pMatrix->data;
00426         const float *data_to_add = pMatrixToAdd->data;
00427 
00428         for (int i = 0; i < nSize; i++)
00429                 data[i] += data_to_add[i];
00430 }
00431 
00432 void LinearAlgebra::SubtractFromMat(CFloatMatrix *pMatrix, const CFloatMatrix *pMatrixToAdd)
00433 {
00434         if (pMatrix->rows != pMatrixToAdd->rows || pMatrix->columns != pMatrixToAdd->columns)
00435         {
00436                 printf("error: matrix dimensions do not match in LinearAlgebra::SubtractFromMat\n");
00437                 return;
00438         }
00439 
00440         const int nSize = pMatrix->rows * pMatrix->columns;
00441         float *data = pMatrix->data;
00442         const float *data_to_subtract = pMatrixToAdd->data;
00443 
00444         for (int i = 0; i < nSize; i++)
00445                 data[i] -= data_to_subtract[i];
00446 }
00447 
00448 void LinearAlgebra::AddToVec(CFloatVector *pVector, const CFloatVector *pVectorToAdd)
00449 {
00450         if (pVector->dimension != pVectorToAdd->dimension)
00451         {
00452                 printf("error: vector dimensions do not match in LinearAlgebra::AddToVec\n");
00453                 return;
00454         }
00455 
00456         const int nDimension = pVector->dimension;
00457         float *data = pVector->data;
00458         const float *data_to_add = pVectorToAdd->data;
00459 
00460         for (int i = 0; i < nDimension; i++)
00461                 data[i] += data_to_add[i];
00462 }
00463 
00464 void LinearAlgebra::SubtractFromVec(CFloatVector *pVector, const CFloatVector *pVectorToSubtract)
00465 {
00466         if (pVector->dimension != pVectorToSubtract->dimension)
00467         {
00468                 printf("error: vector dimensions do not match in LinearAlgebra::SubtractFromVec\n");
00469                 return;
00470         }
00471 
00472         const int nDimension = pVector->dimension;
00473         float *data = pVector->data;
00474         const float *data_to_subtract = pVectorToSubtract->data;
00475 
00476         for (int i = 0; i < nDimension; i++)
00477                 data[i] -= data_to_subtract[i];
00478 }
00479 
00480 
00481 void LinearAlgebra::SubtractMeanFromColumns(const CFloatMatrix *pMatrix, CFloatMatrix *pResultMatrix)
00482 {
00483         if (pMatrix->columns != pResultMatrix->columns || pMatrix->rows != pResultMatrix->rows)
00484                 return;
00485 
00486         const int columns = pMatrix->columns;
00487         const int rows = pMatrix->rows;
00488         const int max = rows * columns;
00489         const float *data = pMatrix->data;
00490         float *output = pResultMatrix->data;
00491 
00492         for (int i = 0; i < columns; i++)
00493         {
00494                 float mean = 0;
00495                 int j;
00496 
00497                 for (j = 0; j < max; j += columns)
00498                         mean += data[j];
00499 
00500                 mean /= rows;
00501 
00502                 for (j = 0; j < max; j += columns)
00503                         output[j] = data[j] - mean;
00504 
00505                 data++;
00506                 output++;
00507         }
00508 }
00509 
00510 void LinearAlgebra::SubtractMeanFromRows(const CFloatMatrix *pMatrix, CFloatMatrix *pResultMatrix)
00511 {
00512         if (pMatrix->columns != pResultMatrix->columns || pMatrix->rows != pResultMatrix->rows)
00513                 return;
00514 
00515         const int columns = pMatrix->columns;
00516         const int rows = pMatrix->rows;
00517         const float *data = pMatrix->data;
00518         float *output = pResultMatrix->data;
00519 
00520         for (int i = 0; i < rows; i++)
00521         {
00522                 float mean = 0;
00523                 int j;
00524 
00525                 for (j = 0; j < columns; j++)
00526                         mean += data[j];
00527 
00528                 mean /= columns;
00529 
00530                 for (j = 0; j < columns; j++)
00531                         output[j] = data[j] - mean;
00532 
00533                 data += columns;
00534                 output += columns;
00535         }
00536 }
00537 
00538 void LinearAlgebra::SolveLinearLeastSquaresHomogeneousSVD(const CFloatMatrix *A, CFloatVector *x)
00539 {
00540         if (A->columns != x->dimension)
00541         {
00542                 printf("error: A, x do not match LinearAlgebra::SolveLinearLeastSquaresHomogeneousSVD\n");
00543                 return;
00544         }
00545         
00546         if (A->rows < A->columns)
00547         {
00548                 printf("error: equation system is underdetermined in LinearAlgebra::SolveLinearLeastSquaresHomogeneousSVD\n");
00549                 return;
00550         }
00551         
00552         const int m = A->rows;
00553         const int n = A->columns;
00554 
00555         CFloatMatrix W(n, m), V(n, n);
00556         
00557         SVD(A, &W, 0, &V, false, false, false);
00558         
00559         for (int i = 0, offset = n - 1; i < n; i++, offset += n)
00560                 x->data[i] = V.data[offset];
00561 }
00562 
00563 void LinearAlgebra::SolveLinearLeastSquaresSVD(const CFloatMatrix *A, const CFloatVector *b, CFloatVector *x)
00564 {
00565         if (A->columns != x->dimension || A->rows != b->dimension)
00566         {
00567                 printf("error: A, b, x do not match LinearAlgebra::SolveLinearLeastSquaresSVD\n");
00568                 return;
00569         }
00570         
00571         if (A->rows < A->columns)
00572         {
00573                 printf("error: equation system is underdetermined in LinearAlgebra::SolveLinearLeastSquaresSVD\n");
00574                 return;
00575         }
00576 
00577         CFloatMatrix A_(A->rows, A->columns);
00578         CalculatePseudoInverseSVD(A, &A_);
00579         LinearAlgebra::MulMatVec(&A_, b, x);
00580 }
00581 
00582 bool LinearAlgebra::SolveLinearLeastSquaresSimple(const CFloatMatrix *A, const CFloatVector *b, CFloatVector *x)
00583 {
00584         if (A->columns != x->dimension || A->rows != b->dimension)
00585         {
00586                 printf("error: A, b, x do not match LinearAlgebra::SolveLinearLeastSquaresSimple\n");
00587                 return false;
00588         }
00589         
00590         if (A->rows < A->columns)
00591         {
00592                 printf("error: equation system is underdetermined in LinearAlgebra::SolveLinearLeastSquaresSimple\n");
00593                 return false;
00594         }
00595 
00596         CFloatMatrix A_(A->rows, A->columns);
00597         
00598         if (!CalculatePseudoInverseSimple(A, &A_))
00599                 return false;
00600         
00601         LinearAlgebra::MulMatVec(&A_, b, x);
00602         
00603         return true;
00604 }
00605 
00606 void LinearAlgebra::CalculatePseudoInverseSVD(const CFloatMatrix *pInputMatrix, CFloatMatrix *pResultMatrix)
00607 {
00608         if (pInputMatrix->columns != pResultMatrix->rows || pInputMatrix->rows != pResultMatrix->columns)
00609         {
00610                 printf("error: input and output matrix do not match LinearAlgebra::CalculatePseudoInverseSVD\n");
00611                 return;
00612         }
00613         
00614         // algorithm:
00615         // 1: compute U * W * V^T = A
00616         // 2: compute W' = W^T with all non-zero values inverted
00617         // 3: compute V * W' * U^T (=pseudoinverse of A)
00618         
00619         const CFloatMatrix *A = pInputMatrix;
00620         const int m = pInputMatrix->rows;
00621         const int n = pInputMatrix->columns;
00622         
00623         CFloatMatrix W(n, m), WT(m, n), UT(m, m), V(n, n);
00624         
00625         // calculate SVD
00626         SVD(A, &W, &UT, &V, false, true, false);
00627         
00628         // transpose middle diagonal matrix
00629         Transpose(&W, &WT);
00630         
00631         const int min = MY_MIN(m, n);
00632 
00633         int i;
00634         float fThreshold = 0.0f;
00635 
00636         for (i = 0; i < min; i++)
00637         fThreshold += WT(i, i);
00638     
00639         fThreshold *= 2 * FLT_EPSILON;
00640         
00641         // invert non-zero values (along diagonal)
00642         for (i = 0; i < min; i++)
00643                 if (WT(i, i) < fThreshold)
00644                         WT(i, i) = 0.0f;
00645                 else
00646                         WT(i, i) = 1.0f / WT(i, i);
00647 
00648         // calculate pseudoinverse
00649         CFloatMatrix temp(m, n);
00650         MulMatMat(&V, &WT, &temp);
00651         MulMatMat(&temp, &UT, pResultMatrix);
00652 }
00653 
00654 bool LinearAlgebra::CalculatePseudoInverseSimple(const CFloatMatrix *pInputMatrix, CFloatMatrix *pResultMatrix)
00655 {
00656         if (pInputMatrix->columns != pResultMatrix->rows || pInputMatrix->rows != pResultMatrix->columns)
00657         {
00658                 printf("error: input and output matrix do not match LinearAlgebra::CalculatePseudoInverseSimple\n");
00659                 return false;
00660         }
00661         
00662         // algorithm:
00663         // compute (A * A^T)^-1 * A^T
00664         
00665         const CFloatMatrix *A = pInputMatrix;
00666         const int m = pInputMatrix->rows;
00667         const int n = pInputMatrix->columns;
00668         
00669         CFloatMatrix AT(m, n), ATA(n, n), ATA_inverted(n, n);
00670         
00671         Transpose(A, &AT);
00672         SelfProduct(A, &ATA);
00673         
00674         if (!Invert(&ATA, &ATA_inverted))
00675                 return false;
00676         
00677         MulMatMat(&ATA_inverted, &AT, pResultMatrix);
00678         
00679         return true;
00680 }
00681 
00682 void LinearAlgebra::PCA(const CFloatMatrix *pData, CFloatMatrix *pTransformationMatrix, CFloatMatrix *pTransformedData, int nTargetDimension)
00683 {
00684         if (nTargetDimension > pData->columns)
00685         {
00686                 printf("error: target dimension is greater than number of columns in training data matrix in LinearAlgebra::PCA\n");
00687                 return;
00688         }
00689 
00690         const int samples = pData->rows;
00691         const int dimension = pData->columns;
00692 
00693         if (pTransformationMatrix->columns != dimension || pTransformationMatrix->rows != nTargetDimension ||
00694                 pTransformedData->columns != samples || pTransformedData->rows != nTargetDimension)
00695         {
00696                 printf("error: input to LinearAlgebra::PCA does not match\n");
00697                 return;
00698         }
00699 
00700         CFloatMatrix adjustedData(pData);
00701         CFloatMatrix covarianceMatrix(dimension, dimension);
00702         CFloatMatrix eigenValues(dimension, dimension);
00703         CFloatMatrix eigenVectors(dimension, dimension);
00704         
00705         //printf("info: subtracting mean from columns...\n");
00706         SubtractMeanFromColumns(pData, &adjustedData);
00707         
00708         //printf("info: calculating covariance matrix...\n");
00709         SelfProduct(&adjustedData, &covarianceMatrix);
00710         
00711         //printf("info: calculating SVD on %ix%i matrix...\n", dimension, dimension);
00712         SVD(&covarianceMatrix, &eigenValues, &eigenVectors, 0, true, true);
00713         
00714         //printf("info: SVD calculated\n");
00715 
00716         for (int i = 0, offset = 0; i < nTargetDimension; i++)
00717         {
00718                 for (int j = 0; j < dimension; j++)
00719                 {
00720                         pTransformationMatrix->data[offset] = eigenVectors.data[i * dimension + j];
00721                         offset++;
00722                 }
00723         }
00724 
00725         MulMatMat(pTransformationMatrix, pData, pTransformedData, true);
00726 }
00727 
00728 void LinearAlgebra::PCA(const CFloatMatrix *pData, CFloatMatrix *pTransformationMatrix, CFloatMatrix *pEigenValues)
00729 {
00730         const int dimension = pData->columns;
00731 
00732         if (pTransformationMatrix->columns != dimension || pTransformationMatrix->rows != dimension || pEigenValues->columns != 1 || pEigenValues->rows != dimension)
00733         {
00734                 printf("error: input to LinearAlgebra::PCA does not match\n");
00735                 return;
00736         }
00737 
00738         CFloatMatrix adjustedData(pData);
00739         CFloatMatrix covarianceMatrix(dimension, dimension);
00740         CFloatMatrix eigenValues(dimension, dimension);
00741         CFloatMatrix eigenVectors(dimension, dimension);
00742         
00743         //printf("info: subtracting mean from columns...\n");
00744         SubtractMeanFromColumns(pData, &adjustedData);
00745         
00746         //printf("info: calculating covariance matrix...\n");
00747         SelfProduct(&adjustedData, &covarianceMatrix);
00748         
00749         //printf("info: calculating SVD on %ix%i matrix...\n", dimension, dimension);
00750         SVD(&covarianceMatrix, &eigenValues, pTransformationMatrix, 0, true, true);
00751         
00752         //printf("info: SVD calculated\n");
00753         
00754         for (int i = 0; i < dimension; i++)
00755                 pEigenValues->data[i] = eigenValues.data[i * dimension + i];
00756 }
00757 
00758 bool LinearAlgebra::Invert(const CFloatMatrix *pInputMatrix, CFloatMatrix *pResultMatrix)
00759 {
00760         if (pInputMatrix->data == pResultMatrix->data)
00761         {
00762                 printf("error: pInputMatrix and pResultMatrix may not point to the same data in LinearAlgebra::Invert\n");
00763                 return false;
00764         }
00765         
00766         if (pInputMatrix->rows != pInputMatrix->columns)
00767         {
00768                 printf("error: input matrix must be square matrix for LinearAlgebra::Invert\n");
00769                 return false;
00770         }
00771 
00772         if (pInputMatrix->columns != pResultMatrix->columns || pInputMatrix->rows != pResultMatrix->rows)
00773         {
00774                 printf("error: input and output matrix do not match LinearAlgebra::Invert\n");
00775                 return false;
00776         }
00777 
00778         const int n = pInputMatrix->columns;
00779         int i;
00780 
00781         CFloatMatrix copiedMatrix(pInputMatrix);
00782         CFloatMatrix tempMatrix(pInputMatrix);
00783         ImageProcessor::CopyMatrix(pInputMatrix, &copiedMatrix);
00784 
00785         ImageProcessor::Zero(&tempMatrix);
00786         for (i = 0; i < n; i++)
00787                 tempMatrix[i][i] = 1;
00788 
00789         int *pPivotRows = new int[n];
00790         for (i = 0; i < n; i++)
00791                 pPivotRows[i] = 0;
00792         
00793         // invert by gauss elimination
00794         for (i = 0; i < n; i++)
00795         {
00796                 int j, nPivotColumn = 0;
00797 
00798                 float *helper1 = copiedMatrix[i];
00799                 float *helper2 = tempMatrix[i];
00800 
00801                 // determine pivot element
00802                 float max = 0;
00803                 for (j = 0; j < n; j++)
00804                         if (fabsf(helper1[j]) > max)
00805                         {
00806                                 max = fabsf(helper1[j]);
00807                                 nPivotColumn = j;
00808                         }
00809 
00810                 pPivotRows[nPivotColumn] = i;
00811 
00812                 const float fPivotElement = copiedMatrix[i][nPivotColumn];
00813 
00814                 if (fabsf(fPivotElement) < 0.00001f)
00815                 {
00816                         //printf("error: input matrix is not regular for LinearAlgebra::Invert\n");
00817                         delete [] pPivotRows;
00818                         return false;
00819                 }
00820 
00821                 const float fFactor = 1.0f / fPivotElement;
00822                 
00823                 for (j = 0; j < n; j++)
00824                 {
00825                         helper1[j] *= fFactor;
00826                         helper2[j] *= fFactor;
00827                 }
00828 
00829                 for (j = 0; j < n; j++)
00830                 {
00831                         if (i != j)
00832                         {
00833                                 const float v = copiedMatrix[j][nPivotColumn];
00834                                 int k;
00835 
00836                                 helper1 = copiedMatrix[j];
00837                                 helper2 = copiedMatrix[i];
00838                                 for (k = 0; k < n; k++)
00839                                         helper1[k] -= v * helper2[k];
00840                                 helper1[nPivotColumn] = 0; // explicitly set to zero
00841 
00842                                 helper1 = tempMatrix[j];
00843                                 helper2 = tempMatrix[i];
00844                                 for (k = 0; k < n; k++)
00845                                         helper1[k] -= v * helper2[k];
00846                         }
00847                 }
00848         }
00849 
00850         // copy result rows in pivot order
00851         for (i = 0; i < n; i++)
00852         {
00853                 float *helper1 = (*pResultMatrix)[i];
00854                 const float *helper2 = tempMatrix[pPivotRows[i]];
00855 
00856                 for (int j = 0; j < n; j++)
00857                         helper1[j] = helper2[j];
00858         }
00859 
00860         delete [] pPivotRows;
00861         
00862         return true;
00863 }
00864 
00865 void LinearAlgebra::Zero(CFloatMatrix *pMatrix)
00866 {
00867         memset(pMatrix->data, 0, pMatrix->columns * pMatrix->rows * sizeof(float));
00868 }
00869 
00870 void LinearAlgebra::Zero(CFloatVector *pVector)
00871 {
00872         memset(pVector->data, 0, pVector->dimension * sizeof(float));
00873 }
00874 
00875 
00876 
00877 
00878 
00879 // copy & paste implementation for CDoubleMatrix and CDoubleVector
00880 // not nice, but i don't like templates.
00881 
00882 void LinearAlgebra::SelfProduct(const CDoubleMatrix *pMatrix, CDoubleMatrix *pResultMatrix, bool AAT)
00883 {
00884         if (
00885                 (AAT && (pResultMatrix->columns != pMatrix->rows || pResultMatrix->rows != pMatrix->rows)) ||
00886                 (!AAT && (pResultMatrix->columns != pMatrix->columns || pResultMatrix->rows != pMatrix->columns))
00887         )
00888         {
00889                 printf("error: matrix dimensions do not match for LinearAlgebra::SelfProduct\n");
00890                 return;
00891         }
00892 
00893         if (!AAT)
00894         {
00895                 CDoubleMatrix *pTransposedMatrix = new CDoubleMatrix(pMatrix->rows, pMatrix->columns);
00896                 Transpose(pMatrix, pTransposedMatrix);
00897                 pMatrix = pTransposedMatrix;
00898         }
00899 
00900         const int columns = pMatrix->columns;
00901         const int rows = pMatrix->rows;
00902 
00903         const double *data = pMatrix->data;
00904         double *result = pResultMatrix->data;
00905 
00906         if (data != result)
00907         {
00908                 for (int i = 0, input_offset1 = 0; i < rows; i++, input_offset1 += columns)
00909                 {
00910                         for (int j = i, input_offset2 = input_offset1; j < rows; j++, input_offset2 += columns)
00911                         {
00912                                 const double *data1 = data + input_offset1;
00913                                 const double *data2 = data + input_offset2;
00914                                 double sum = 0;
00915 
00916                                 for (int k = 0; k < columns; k++)
00917                                         sum += data1[k] * data2[k];
00918 
00919                                 result[i * rows + j] = result[j * rows + i] = sum;
00920                         }
00921                 }
00922         }
00923         else
00924         {
00925                 CDoubleMatrix temp(pResultMatrix);
00926                 double *temp_data = temp.data;
00927 
00928                 for (int i = 0, input_offset1 = 0; i < rows; i++, input_offset1 += columns)
00929                 {
00930                         for (int j = i, input_offset2 = input_offset1; j < rows; j++, input_offset2 += columns)
00931                         {
00932                                 const double *data1 = data + input_offset1;
00933                                 const double *data2 = data + input_offset2;
00934                                 double sum = 0;
00935 
00936                                 for (int k = 0; k < columns; k++)
00937                                         sum += data1[k] * data2[k];
00938 
00939                                 temp_data[i * rows + j] = temp_data[j * rows + i] = sum;
00940                         }
00941                 }
00942 
00943                 memcpy(pResultMatrix->data, temp_data, pResultMatrix->rows * pResultMatrix->columns * sizeof(double));
00944         }
00945 
00946         if (!AAT)
00947                 delete pMatrix;
00948 }
00949 
00950 void LinearAlgebra::MulMatMat(const CDoubleMatrix *A, const CDoubleMatrix *B, CDoubleMatrix *pResultMatrix, bool bTransposeB)
00951 {
00952         if (!bTransposeB && (A->columns != B->rows || pResultMatrix->columns != B->columns || pResultMatrix->rows != A->rows))
00953         {
00954                 printf("error: matrices A, B, and pResultMatrix do not satisfy requirements for LinearAlgebra::Multiply\n");
00955                 return;
00956         }
00957 
00958         if (bTransposeB && (A->columns != B->columns || pResultMatrix->columns != B->rows || pResultMatrix->rows != A->rows))
00959         {
00960                 printf("error: matrices A, B, and pResultMatrix do not satisfy requirements for LinearAlgebra::Multiply\n");
00961                 return;
00962         }
00963 
00964         const double *data1 = A->data;
00965         const double *data2 = B->data;
00966         double *result = pResultMatrix->data;
00967 
00968         const int nSize = pResultMatrix->columns * pResultMatrix->rows;
00969 
00970         if (bTransposeB)
00971         {
00972                 const int rowsA = A->rows;
00973                 const int rowsB = B->rows;
00974                 const int columns = A->columns;
00975 
00976                 if (data1 != result && data2 != result)
00977                 {
00978                         for (int i = 0, input_offset1 = 0, output_offset = 0; i < rowsA; i++, input_offset1 += columns)
00979                         {
00980                                 for (int j = 0, input_offset2 = input_offset1; j < rowsB; j++, input_offset2 += columns, output_offset++)
00981                                 {
00982                                         const double *data1_ = data1 + input_offset1;
00983                                         const double *data2_ = data2 + input_offset2;
00984                                         double sum = 0;
00985 
00986                                         for (int k = 0; k < columns; k++)
00987                                                 sum += data1_[k] * data2_[k];
00988 
00989                                         result[output_offset] = sum;
00990                                 }
00991                         }
00992                 }
00993                 else
00994                 {
00995                         CDoubleMatrix temp(pResultMatrix);
00996                         double *temp_data = temp.data;
00997 
00998                         int l;
00999 
01000                         for (l = 0; l < nSize; l++)
01001                                 temp_data[l] = 0;
01002 
01003                         for (int i = 0, input_offset1 = 0, output_offset = 0; i < rowsA; i++, input_offset1 += columns)
01004                         {
01005                                 for (int j = 0, input_offset2 = input_offset1; j < rowsB; j++, input_offset2 += columns, output_offset++)
01006                                 {
01007                                         const double *data1_ = data1 + input_offset1;
01008                                         const double *data2_ = data2 + input_offset2;
01009                                         double sum = 0;
01010 
01011                                         for (int k = 0; k < columns; k++)
01012                                                 sum += data1_[k] * data2_[k];
01013 
01014                                         temp_data[output_offset] = sum;
01015                                 }
01016                         }
01017 
01018                         for (l = 0; l < nSize; l++)
01019                                 result[l] = temp_data[l];
01020                 }
01021         }
01022         else
01023         {
01024                 const int i_max = A->rows;
01025                 const int j_max = B->columns;
01026                 const int k_max = A->columns;
01027 
01028                 // not optimized yet
01029                 if (data1 != result && data2 != result)
01030                 {
01031                         for (int l = 0; l < nSize; l++)
01032                                 result[l] = 0;
01033 
01034                         for (int i = 0, input1_offset = 0; i < i_max; i++)
01035                         {
01036                                 const int result_offset_start = i * j_max;
01037 
01038                                 for (int k = 0, input2_offset = 0; k < k_max; k++, input1_offset++)
01039                                         for (int j = 0, result_offset = result_offset_start; j < j_max; j++, result_offset++, input2_offset++)
01040                                                 result[result_offset] += data1[input1_offset] * data2[input2_offset];
01041                         }
01042                 }
01043                 else
01044                 {
01045                         CDoubleMatrix temp(pResultMatrix);
01046                         double *temp_data = temp.data;
01047 
01048                         int l;
01049 
01050                         for (l = 0; l < nSize; l++)
01051                                 temp_data[l] = 0;
01052 
01053                         for (int i = 0, input1_offset = 0; i < i_max; i++)
01054                         {
01055                                 const int result_offset_start = i * j_max;
01056 
01057                                 for (int k = 0, input2_offset = 0; k < k_max; k++, input1_offset++)
01058                                         for (int j = 0, result_offset = result_offset_start; j < j_max; j++, result_offset++, input2_offset++)
01059                                                 temp_data[result_offset] += data1[input1_offset] * data2[input2_offset];
01060                         }
01061 
01062                         for (l = 0; l < nSize; l++)
01063                                 result[l] = temp_data[l];
01064                 }
01065         }
01066 }
01067 
01068 void LinearAlgebra::Transpose(const CDoubleMatrix *pMatrix, CDoubleMatrix *pResultMatrix)
01069 {
01070         if (pMatrix->columns != pResultMatrix->rows || pMatrix->rows != pResultMatrix->columns)
01071         {
01072                 printf("error: input and output matrix do not match LinearAlgebra::Transpose\n");
01073                 return;
01074         }
01075 
01076         const int rows = pMatrix->rows;
01077         const int columns = pMatrix->columns;
01078         const double *input = pMatrix->data;
01079         double *output = pResultMatrix->data;
01080 
01081         if (input != output)
01082         {
01083                 for (int i = 0, input_offset = 0; i < rows; i++)
01084                         for (int j = 0, output_offset = i; j < columns; j++, input_offset++, output_offset += rows)
01085                                 output[output_offset] = input[input_offset];
01086         }
01087         else
01088         {
01089                 // not optimized yet
01090                 CDoubleMatrix temp(pResultMatrix);
01091                 double *temp_data = temp.data;
01092 
01093                 int i, input_offset;
01094 
01095                 for (i = 0, input_offset = 0; i < rows; i++)
01096                         for (int j = 0, output_offset = i; j < columns; j++, input_offset++, output_offset += rows)
01097                                 temp_data[output_offset] = input[input_offset];
01098 
01099                 const int nSize = rows * columns;
01100 
01101                 for (i = 0; i < nSize; i++)
01102                         output[i] = temp_data[i];
01103         }
01104 }
01105 
01106 void LinearAlgebra::MulMatVec(const CDoubleMatrix *pMatrix, const CDoubleVector *pVector, CDoubleVector *pResultVector)
01107 {
01108         if (pMatrix->columns != pVector->dimension || pMatrix->rows != pResultVector->dimension)
01109         {
01110                 printf("error: input matrix and vector and output vector do not match for CDoubleMatrix::Multiply\n");
01111                 return;
01112         }
01113         
01114         const int rows = pMatrix->rows;
01115         const int columns = pMatrix->columns;
01116         const double *data_m = pMatrix->data;
01117         const double *data_v = pVector->data;
01118         double *data_r = pResultVector->data;
01119         
01120         if (data_r != data_v)
01121         {
01122                 for (int i = 0, offset = 0; i < rows; i++)
01123                 {
01124                         double sum = 0.0f;
01125                         
01126                         for (int j = 0; j < columns; j++, offset++)
01127                                 sum += data_m[offset] * data_v[j];
01128                                 
01129                         data_r[i] = sum;
01130                 }
01131         }
01132         else
01133         {
01134                 double *temp = new double[rows];
01135                 int i, offset;
01136 
01137                 for (i = 0, offset = 0; i < rows; i++)
01138                 {
01139                         double sum = 0.0f;
01140                         
01141                         for (int j = 0; j < columns; j++, offset++)
01142                                 sum += data_m[offset] * data_v[j];
01143                                 
01144                         temp[i] = sum;
01145                 }
01146 
01147                 for (i = 0; i < rows; i++)
01148                         data_r[i] = temp[i];
01149 
01150                 delete [] temp;
01151         }
01152 }
01153 
01154 void LinearAlgebra::MulMatVec(const CDoubleMatrix *pMatrix, const CDoubleVector *pVector1, const CDoubleVector *pVector2, CDoubleVector *pResultVector)
01155 {
01156         MulMatVec(pMatrix, pVector1, pResultVector);
01157         AddToVec(pResultVector, pVector2);
01158 }
01159 
01160 void LinearAlgebra::AddMatMat(const CDoubleMatrix *pMatrix1, const CDoubleMatrix *pMatrix2, CDoubleMatrix *pResultMatrix)
01161 {
01162         if (pMatrix1->rows != pMatrix2->rows || pMatrix1->columns != pMatrix2->columns ||
01163                 pMatrix1->rows != pResultMatrix->rows || pMatrix1->columns != pResultMatrix->columns)
01164         {
01165                 printf("error: matrix dimensions do not match in LinearAlgebra::AddMatMat\n");
01166                 return;
01167         }
01168 
01169         const int nSize = pMatrix1->rows * pMatrix1->columns;
01170         const double *data1 = pMatrix1->data;
01171         const double *data2 = pMatrix2->data;
01172         double *result = pResultMatrix->data;
01173 
01174         for (int i = 0; i < nSize; i++)
01175                 result[i] = data1[i] + data2[i];
01176 }
01177 
01178 void LinearAlgebra::SubtractMatMat(const CDoubleMatrix *pMatrix1, const CDoubleMatrix *pMatrix2, CDoubleMatrix *pResultMatrix)
01179 {
01180         if (pMatrix1->rows != pMatrix2->rows || pMatrix1->columns != pMatrix2->columns ||
01181                 pMatrix1->rows != pResultMatrix->rows || pMatrix1->columns != pResultMatrix->columns)
01182         {
01183                 printf("error: matrix dimensions do not match in LinearAlgebra::SubtractMatMat\n");
01184                 return;
01185         }
01186 
01187         const int nSize = pMatrix1->rows * pMatrix1->columns;
01188         const double *data1 = pMatrix1->data;
01189         const double *data2 = pMatrix2->data;
01190         double *result = pResultMatrix->data;
01191 
01192         for (int i = 0; i < nSize; i++)
01193                 result[i] = data1[i] - data2[i];
01194 }
01195 
01196 void LinearAlgebra::AddVecVec(const CDoubleVector *pVector1, const CDoubleVector *pVector2, CDoubleVector *pResultVector)
01197 {
01198         if (pVector1->dimension != pVector2->dimension || pVector1->dimension != pResultVector->dimension)
01199         {
01200                 printf("error: vector dimensions do not match in LinearAlgebra::AddVecVec\n");
01201                 return;
01202         }
01203 
01204         const int nDimension = pVector1->dimension;
01205         const double *data1 = pVector1->data;
01206         const double *data2 = pVector2->data;
01207         double *result = pResultVector->data;
01208 
01209         for (int i = 0; i < nDimension; i++)
01210                 result[i] = data1[i] + data2[i];
01211 }
01212 
01213 void LinearAlgebra::SubtractVecVec(const CDoubleVector *pVector1, const CDoubleVector *pVector2, CDoubleVector *pResultVector)
01214 {
01215         if (pVector1->dimension != pVector2->dimension || pVector1->dimension != pResultVector->dimension)
01216         {
01217                 printf("error: vector dimensions do not match in LinearAlgebra::SubtractVecVec\n");
01218                 return;
01219         }
01220 
01221         const int nDimension = pVector1->dimension;
01222         const double *data1 = pVector1->data;
01223         const double *data2 = pVector2->data;
01224         double *result = pResultVector->data;
01225 
01226         for (int i = 0; i < nDimension; i++)
01227                 result[i] = data1[i] - data2[i];
01228 }
01229 
01230 void LinearAlgebra::AddToMat(CDoubleMatrix *pMatrix, const CDoubleMatrix *pMatrixToAdd)
01231 {
01232         if (pMatrix->rows != pMatrixToAdd->rows || pMatrix->columns != pMatrixToAdd->columns)
01233         {
01234                 printf("error: matrix dimensions do not match in LinearAlgebra::AddToMat\n");
01235                 return;
01236         }
01237 
01238         const int nSize = pMatrix->rows * pMatrix->columns;
01239         double *data = pMatrix->data;
01240         const double *data_to_add = pMatrixToAdd->data;
01241 
01242         for (int i = 0; i < nSize; i++)
01243                 data[i] += data_to_add[i];
01244 }
01245 
01246 void LinearAlgebra::SubtractFromMat(CDoubleMatrix *pMatrix, const CDoubleMatrix *pMatrixToAdd)
01247 {
01248         if (pMatrix->rows != pMatrixToAdd->rows || pMatrix->columns != pMatrixToAdd->columns)
01249         {
01250                 printf("error: matrix dimensions do not match in LinearAlgebra::SubtractFromMat\n");
01251                 return;
01252         }
01253 
01254         const int nSize = pMatrix->rows * pMatrix->columns;
01255         double *data = pMatrix->data;
01256         const double *data_to_subtract = pMatrixToAdd->data;
01257 
01258         for (int i = 0; i < nSize; i++)
01259                 data[i] -= data_to_subtract[i];
01260 }
01261 
01262 void LinearAlgebra::AddToVec(CDoubleVector *pVector, const CDoubleVector *pVectorToAdd)
01263 {
01264         if (pVector->dimension != pVectorToAdd->dimension)
01265         {
01266                 printf("error: vector dimensions do not match in LinearAlgebra::AddToVec\n");
01267                 return;
01268         }
01269 
01270         const int nDimension = pVector->dimension;
01271         double *data = pVector->data;
01272         const double *data_to_add = pVectorToAdd->data;
01273 
01274         for (int i = 0; i < nDimension; i++)
01275                 data[i] += data_to_add[i];
01276 }
01277 
01278 void LinearAlgebra::SubtractFromVec(CDoubleVector *pVector, const CDoubleVector *pVectorToSubtract)
01279 {
01280         if (pVector->dimension != pVectorToSubtract->dimension)
01281         {
01282                 printf("error: vector dimensions do not match in LinearAlgebra::SubtractFromVec\n");
01283                 return;
01284         }
01285 
01286         const int nDimension = pVector->dimension;
01287         double *data = pVector->data;
01288         const double *data_to_subtract = pVectorToSubtract->data;
01289 
01290         for (int i = 0; i < nDimension; i++)
01291                 data[i] -= data_to_subtract[i];
01292 }
01293 
01294 
01295 void LinearAlgebra::SubtractMeanFromColumns(const CDoubleMatrix *pMatrix, CDoubleMatrix *pResultMatrix)
01296 {
01297         if (pMatrix->columns != pResultMatrix->columns || pMatrix->rows != pResultMatrix->rows)
01298                 return;
01299 
01300         const int columns = pMatrix->columns;
01301         const int rows = pMatrix->rows;
01302         const int max = rows * columns;
01303         const double *data = pMatrix->data;
01304         double *output = pResultMatrix->data;
01305 
01306         for (int i = 0; i < columns; i++)
01307         {
01308                 double mean = 0;
01309                 int j;
01310 
01311                 for (j = 0; j < max; j += columns)
01312                         mean += data[j];
01313 
01314                 mean /= rows;
01315 
01316                 for (j = 0; j < max; j += columns)
01317                         output[j] = data[j] - mean;
01318 
01319                 data++;
01320                 output++;
01321         }
01322 }
01323 
01324 void LinearAlgebra::SubtractMeanFromRows(const CDoubleMatrix *pMatrix, CDoubleMatrix *pResultMatrix)
01325 {
01326         if (pMatrix->columns != pResultMatrix->columns || pMatrix->rows != pResultMatrix->rows)
01327                 return;
01328 
01329         const int columns = pMatrix->columns;
01330         const int rows = pMatrix->rows;
01331         const double *data = pMatrix->data;
01332         double *output = pResultMatrix->data;
01333 
01334         for (int i = 0; i < rows; i++)
01335         {
01336                 double mean = 0;
01337                 int j;
01338 
01339                 for (j = 0; j < columns; j++)
01340                         mean += data[j];
01341 
01342                 mean /= columns;
01343 
01344                 for (j = 0; j < columns; j++)
01345                         output[j] = data[j] - mean;
01346 
01347                 data += columns;
01348                 output += columns;
01349         }
01350 }
01351 
01352 bool LinearAlgebra::Invert(const CDoubleMatrix *pInputMatrix, CDoubleMatrix *pResultMatrix)
01353 {
01354         if (pInputMatrix->data == pResultMatrix->data)
01355         {
01356                 printf("error: pInputMatrix and pResultMatrix may not point to the same data in LinearAlgebra::Invert\n");
01357                 return false;
01358         }
01359         
01360         if (pInputMatrix->rows != pInputMatrix->columns)
01361         {
01362                 printf("error: input matrix must be square matrix for LinearAlgebra::Invert\n");
01363                 return false;
01364         }
01365 
01366         if (pInputMatrix->columns != pResultMatrix->columns || pInputMatrix->rows != pResultMatrix->rows)
01367         {
01368                 printf("error: input and output matrix do not match LinearAlgebra::Invert\n");
01369                 return false;
01370         }
01371 
01372         const int n = pInputMatrix->columns;
01373         int i;
01374 
01375         CDoubleMatrix copiedMatrix(pInputMatrix);
01376         CDoubleMatrix tempMatrix(pInputMatrix);
01377         ImageProcessor::CopyMatrix(pInputMatrix, &copiedMatrix);
01378 
01379         ImageProcessor::Zero(&tempMatrix);
01380         for (i = 0; i < n; i++)
01381                 tempMatrix[i][i] = 1;
01382 
01383         int *pPivotRows = new int[n];
01384         for (i = 0; i < n; i++)
01385                 pPivotRows[i] = 0;
01386         
01387         // invert by gauss elimination
01388         for (i = 0; i < n; i++)
01389         {
01390                 int j, nPivotColumn = 0;
01391 
01392                 double *helper1 = copiedMatrix[i];
01393                 double *helper2 = tempMatrix[i];
01394 
01395                 // determine pivot element
01396                 double max = 0;
01397                 for (j = 0; j < n; j++)
01398                         if (fabs(helper1[j]) > max)
01399                         {
01400                                 max = fabs(helper1[j]);
01401                                 nPivotColumn = j;
01402                         }
01403 
01404                 pPivotRows[nPivotColumn] = i;
01405 
01406                 const double dPivotElement = copiedMatrix[i][nPivotColumn];
01407 
01408                 if (fabs(dPivotElement) < 0.00001)
01409                 {
01410                         //printf("error: input matrix is not regular for LinearAlgebra::Invert\n");
01411                         delete [] pPivotRows;
01412                         return false;
01413                 }
01414 
01415                 const double dFactor = 1.0 / dPivotElement;
01416                 
01417                 for (j = 0; j < n; j++)
01418                 {
01419                         helper1[j] *= dFactor;
01420                         helper2[j] *= dFactor;
01421                 }
01422 
01423                 for (j = 0; j < n; j++)
01424                 {
01425                         if (i != j)
01426                         {
01427                                 const double v = copiedMatrix[j][nPivotColumn];
01428                                 int k;
01429 
01430                                 helper1 = copiedMatrix[j];
01431                                 helper2 = copiedMatrix[i];
01432                                 for (k = 0; k < n; k++)
01433                                         helper1[k] -= v * helper2[k];
01434                                 helper1[nPivotColumn] = 0; // explicitly set to zero
01435 
01436                                 helper1 = tempMatrix[j];
01437                                 helper2 = tempMatrix[i];
01438                                 for (k = 0; k < n; k++)
01439                                         helper1[k] -= v * helper2[k];
01440                         }
01441                 }
01442         }
01443 
01444         // copy result rows in pivot order
01445         for (i = 0; i < n; i++)
01446         {
01447                 double *helper1 = (*pResultMatrix)[i];
01448                 const double *helper2 = tempMatrix[pPivotRows[i]];
01449 
01450                 for (int j = 0; j < n; j++)
01451                         helper1[j] = helper2[j];
01452         }
01453 
01454         delete [] pPivotRows;
01455         
01456         return true;
01457 }
01458 
01459 void LinearAlgebra::SolveLinearLeastSquaresHomogeneousSVD(const CDoubleMatrix *A, CDoubleVector *x)
01460 {
01461         if (A->columns != x->dimension)
01462         {
01463                 printf("error: A, x do not match LinearAlgebra::SolveLinearLeastSquaresHomogeneousSVD\n");
01464                 return;
01465         }
01466         
01467         if (A->rows < A->columns)
01468         {
01469                 printf("error: equation system is underdetermined in LinearAlgebra::SolveLinearLeastSquaresHomogeneousSVD\n");
01470                 return;
01471         }
01472         
01473         const int m = A->rows;
01474         const int n = A->columns;
01475 
01476         CDoubleMatrix W(n, m), V(n, n);
01477         
01478         SVD(A, &W, 0, &V, false, false, false);
01479         
01480         for (int i = 0, offset = n - 1; i < n; i++, offset += n)
01481                 x->data[i] = V.data[offset];
01482 }
01483 
01484 void LinearAlgebra::SolveLinearLeastSquaresSVD(const CDoubleMatrix *A, const CDoubleVector *b, CDoubleVector *x)
01485 {
01486         if (A->columns != x->dimension || A->rows != b->dimension)
01487         {
01488                 printf("error: A, b, x do not match LinearAlgebra::SolveLinearLeastSquaresSVD\n");
01489                 return;
01490         }
01491         
01492         if (A->rows < A->columns)
01493         {
01494                 printf("error: equation system is underdetermined in LinearAlgebra::SolveLinearLeastSquaresSVD\n");
01495                 return;
01496         }
01497 
01498         CDoubleMatrix A_(A->rows, A->columns);
01499         CalculatePseudoInverseSVD(A, &A_);
01500         MulMatVec(&A_, b, x);
01501 }
01502 
01503 bool LinearAlgebra::SolveLinearLeastSquaresSimple(const CDoubleMatrix *A, const CDoubleVector *b, CDoubleVector *x)
01504 {
01505         if (A->columns != x->dimension || A->rows != b->dimension)
01506         {
01507                 printf("error: A, b, x do not match LinearAlgebra::SolveLinearLeastSquaresSimple\n");
01508                 return false;
01509         }
01510         
01511         if (A->rows < A->columns)
01512         {
01513                 printf("error: equation system is underdetermined in LinearAlgebra::SolveLinearLeastSquaresSimple\n");
01514                 return false;
01515         }
01516 
01517         CDoubleMatrix A_(A->rows, A->columns);
01518         
01519         if (!CalculatePseudoInverseSimple(A, &A_))
01520                 return false;
01521         
01522         MulMatVec(&A_, b, x);
01523         
01524         return true;
01525 }
01526 
01527 void LinearAlgebra::CalculatePseudoInverseSVD(const CDoubleMatrix *pInputMatrix, CDoubleMatrix *pResultMatrix)
01528 {
01529         if (pInputMatrix->columns != pResultMatrix->rows || pInputMatrix->rows != pResultMatrix->columns)
01530         {
01531                 printf("error: input and output matrix do not match LinearAlgebra::CalculatePseudoInverseSVD\n");
01532                 return;
01533         }
01534         
01535         // algorithm:
01536         // 1: compute U * W * V^T = A
01537         // 2: compute W' = W^T with all non-zero values inverted
01538         // 3: compute V * W' * U^T (=pseudoinverse of A)
01539         
01540         const CDoubleMatrix *A = pInputMatrix;
01541         const int m = pInputMatrix->rows;
01542         const int n = pInputMatrix->columns;
01543         
01544         CDoubleMatrix W(n, m), WT(m, n), UT(m, m), V(n, n);
01545         
01546         // calculate SVD
01547         SVD(A, &W, &UT, &V, false, true, false);
01548         
01549         // transpose middle diagonal matrix
01550         Transpose(&W, &WT);
01551         
01552         const int min = MY_MIN(m, n);
01553 
01554         int i;
01555         double dThreshold = 0.0;
01556 
01557         for(i = 0; i < min; i++)
01558         dThreshold += WT(i, i);
01559     
01560         dThreshold *= 2 * DBL_EPSILON;
01561         
01562         // invert non-zero values (along diagonal)
01563         for (i = 0; i < min; i++)
01564                 if (WT(i, i) < dThreshold)
01565                         WT(i, i) = 0;
01566                 else
01567                         WT(i, i) = 1.0 / WT(i, i);
01568 
01569         // calculate pseudoinverse
01570         CDoubleMatrix temp(m, n);
01571         MulMatMat(&V, &WT, &temp);
01572         MulMatMat(&temp, &UT, pResultMatrix);
01573 }
01574 
01575 bool LinearAlgebra::CalculatePseudoInverseSimple(const CDoubleMatrix *pInputMatrix, CDoubleMatrix *pResultMatrix)
01576 {
01577         if (pInputMatrix->columns != pResultMatrix->rows || pInputMatrix->rows != pResultMatrix->columns)
01578         {
01579                 printf("error: input and output matrix do not match LinearAlgebra::CalculatePseudoInverseSimple\n");
01580                 return false;
01581         }
01582         
01583         // algorithm:
01584         // compute (A * A^T)^-1 * A^T
01585         
01586         const CDoubleMatrix *A = pInputMatrix;
01587         const int m = pInputMatrix->rows;
01588         const int n = pInputMatrix->columns;
01589         
01590         CDoubleMatrix AT(m, n), ATA(n, n), ATA_inverted(n, n);
01591         
01592         Transpose(A, &AT);
01593         SelfProduct(A, &ATA);
01594         
01595         if (!Invert(&ATA, &ATA_inverted))
01596                 return false;
01597         
01598         MulMatMat(&ATA_inverted, &AT, pResultMatrix);
01599         
01600         return true;
01601 }
01602 
01603 void LinearAlgebra::Zero(CDoubleVector *pVector)
01604 {
01605         memset(pVector->data, 0, pVector->dimension * sizeof(double));
01606 }
01607 
01608 void LinearAlgebra::Zero(CDoubleMatrix *pMatrix)
01609 {
01610         memset(pMatrix->data, 0, pMatrix->columns * pMatrix->rows * sizeof(double));
01611 }
01612 
01613 
01614 
01615 
01616 bool LinearAlgebra::DetermineAffineTransformation(const Vec2d *pSourcePoints, const Vec2d *pTargetPoints, int nPoints, Mat3d &A, bool bUseSVD)
01617 {
01618         if (nPoints < 3)
01619         {
01620                 printf("error: not enough input point pairs for LinearAlgebra::DetermineAffineTransformation (must be at least 3)\n");
01621                 return false;
01622         }
01623         
01624         CFloatMatrix M(6, 2 * nPoints);
01625         CFloatVector b(2 * nPoints);
01626         
01627         float *data = M.data;
01628         
01629         for (int i = 0, offset = 0; i < nPoints; i++, offset += 12)
01630         {
01631                 data[offset] = pSourcePoints[i].x;
01632                 data[offset + 1] = pSourcePoints[i].y;
01633                 data[offset + 2] = 1;
01634                 data[offset + 3] = 0;
01635                 data[offset + 4] = 0;
01636                 data[offset + 5] = 0;
01637                 
01638                 data[offset + 6] = 0;
01639                 data[offset + 7] = 0;
01640                 data[offset + 8] = 0;
01641                 data[offset + 9] = pSourcePoints[i].x;
01642                 data[offset + 10] = pSourcePoints[i].y;
01643                 data[offset + 11] = 1;
01644 
01645                 const int index = 2 * i;
01646                 b.data[index] = pTargetPoints[i].x;
01647                 b.data[index + 1] = pTargetPoints[i].y;
01648         }
01649         
01650         CFloatVector x(6);
01651         
01652         for (int i = 0; i < 6; i++)
01653                 x.data[i] = 0.0f;
01654         
01655         bool bRet = true;
01656         
01657         if (bUseSVD)
01658                 SolveLinearLeastSquaresSVD(&M, &b, &x);
01659         else
01660                 bRet = SolveLinearLeastSquaresSimple(&M, &b, &x);
01661         
01662         if (!bRet)
01663                 return false;
01664         
01665         Math3d::SetMat(A, x.data[0], x.data[1], x.data[2], x.data[3], x.data[4], x.data[5], 0.0f, 0.0f, 1.0f);
01666         
01667         return true;
01668 }
01669 
01670 bool LinearAlgebra::DetermineHomography(const Vec2d *pSourcePoints, const Vec2d *pTargetPoints, int nPoints, Mat3d &A, bool bUseSVD)
01671 {
01672         if (nPoints < 4)
01673         {
01674                 printf("error: not enough input point pairs for LinearAlgebra::DetermineHomography (must be at least 4)\n");
01675                 return false;
01676         }
01677 
01678         // this least squares problem becomes numerically instable when
01679         // using float instead of double!!
01680         CDoubleMatrix M(8, 2 * nPoints);
01681         CDoubleVector b(2 * nPoints);
01682         
01683         double *data = M.data;
01684         
01685         for (int i = 0, offset = 0; i < nPoints; i++, offset += 16)
01686         {
01687                 data[offset] = pSourcePoints[i].x;
01688                 data[offset + 1] = pSourcePoints[i].y;
01689                 data[offset + 2] = 1;
01690                 data[offset + 3] = 0;
01691                 data[offset + 4] = 0;
01692                 data[offset + 5] = 0;
01693                 data[offset + 6] = -pSourcePoints[i].x * pTargetPoints[i].x;
01694                 data[offset + 7] = -pSourcePoints[i].y * pTargetPoints[i].x;
01695                 
01696                 data[offset + 8] = 0;
01697                 data[offset + 9] = 0;
01698                 data[offset + 10] = 0;
01699                 data[offset + 11] = pSourcePoints[i].x;
01700                 data[offset + 12] = pSourcePoints[i].y;
01701                 data[offset + 13] = 1;
01702                 data[offset + 14] = -pSourcePoints[i].x * pTargetPoints[i].y;
01703                 data[offset + 15] = -pSourcePoints[i].y * pTargetPoints[i].y;
01704 
01705                 const int index = 2 * i;
01706                 b.data[index] = pTargetPoints[i].x;
01707                 b.data[index + 1] = pTargetPoints[i].y;
01708         }
01709         
01710         CDoubleVector x(8);
01711         
01712         for (int i = 0; i < 8; i++)
01713                 x.data[i] = 0.0;
01714         
01715         bool bRet = true;
01716         
01717         if (bUseSVD)
01718                 SolveLinearLeastSquaresSVD(&M, &b, &x);
01719         else
01720                 bRet = SolveLinearLeastSquaresSimple(&M, &b, &x);
01721         
01722         if (!bRet)
01723                 return false;
01724         
01725         Math3d::SetMat(A, float(x.data[0]), float(x.data[1]), float(x.data[2]), float(x.data[3]), float(x.data[4]), float(x.data[5]), float(x.data[6]), float(x.data[7]), 1.0f);
01726         
01727         return true;
01728 }


asr_ivt
Author(s): Allgeyer Tobias, Hutmacher Robin, Kleinert Daniel, Meißner Pascal, Scholz Jonas, Stöckle Patrick
autogenerated on Thu Jun 6 2019 21:46:57