RGBColorModel.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:  RGBColorModel.cpp
00037 // Author:    Pedram Azad
00038 // Date:      2005
00039 // ****************************************************************************
00040 
00041 
00042 // ****************************************************************************
00043 // Includes
00044 // ****************************************************************************
00045 
00046 #include <new> // for explicitly using correct new/delete operators on VC DSPs
00047 
00048 #include "RGBColorModel.h"
00049 
00050 #include "Math/Math3d.h"
00051 
00052 #include <math.h>
00053 #include <stdio.h>
00054 
00055 
00056 
00057 // *****************************************************************
00058 // Constructor / Destructor
00059 // *****************************************************************
00060 
00061 CRGBColorModel::CRGBColorModel()
00062 {
00063         m_pTriplets = 0;
00064         m_nMaxNumberOfTriplets = 0;
00065         m_nCurrentPosition = 0;
00066         m_fFactor = 0.5f;
00067 }
00068 
00069 CRGBColorModel::~CRGBColorModel()
00070 {
00071         if (m_pTriplets)
00072                 delete [] m_pTriplets;
00073 }
00074 
00075 
00076 // ****************************************************************************
00077 // Methods
00078 // ****************************************************************************
00079 
00080 void CRGBColorModel::Reset(int nMaxNumberOfTriplets)
00081 {
00082         if (m_pTriplets)
00083                 delete [] m_pTriplets;
00084                 
00085         m_nMaxNumberOfTriplets = nMaxNumberOfTriplets;
00086         m_nCurrentPosition = 0;
00087                 
00088         m_pTriplets = new Vec3d[nMaxNumberOfTriplets];
00089 }
00090 
00091 bool CRGBColorModel::AddRGBTriplet(int r, int g, int b)
00092 {
00093         if (m_nCurrentPosition >= m_nMaxNumberOfTriplets)
00094                 return false;
00095 
00096         Math3d::SetVec(m_pTriplets[m_nCurrentPosition++], float(r), float(g), float(b));
00097         
00098         return true;
00099 }
00100 
00101 void CRGBColorModel::CalculateColorModel()
00102 {
00103         Mat3d rgb_covariance;
00104         int i;
00105         
00106         Math3d::SetVec(rgb_mean, Math3d::zero_vec);
00107         
00108         for (i = 0; i < m_nCurrentPosition; i++)
00109                 Math3d::AddToVec(rgb_mean, m_pTriplets[i]);
00110                 
00111         Math3d::MulVecScalar(rgb_mean, 1.0f / m_nCurrentPosition, rgb_mean);
00112         
00113         Math3d::SetMat(rgb_covariance, Math3d::zero_mat);
00114         
00115         for (i = 0; i < m_nCurrentPosition; i++)
00116         {
00117                 const float r = m_pTriplets[i].x - rgb_mean.x;
00118                 const float g = m_pTriplets[i].y - rgb_mean.y;
00119                 const float b = m_pTriplets[i].z - rgb_mean.z;
00120                 rgb_covariance.r1 += r * r;
00121                 rgb_covariance.r2 += r * g;
00122                 rgb_covariance.r3 += r * b;
00123                 rgb_covariance.r4 += r * g;
00124                 rgb_covariance.r5 += g * g;
00125                 rgb_covariance.r6 += g * b;
00126                 rgb_covariance.r7 += r * b;
00127                 rgb_covariance.r8 += g * b;
00128                 rgb_covariance.r9 += b * b;
00129         }
00130         
00131         Math3d::MulMatScalar(rgb_covariance, 1.0f / (m_nCurrentPosition - 1), rgb_covariance);
00132         Math3d::Invert(rgb_covariance, inverse_rgb_covariance);
00133         
00134         printf("mean = %f %f %f\n", rgb_mean.x, rgb_mean.y, rgb_mean.z);
00135 }
00136 
00137 float CRGBColorModel::CalculateColorProbability(const Vec3d &rgb)
00138 {
00139         Vec3d diff;
00140         
00141         Math3d::SubtractVecVec(rgb, rgb_mean, diff);
00142 
00143         return exp(-m_fFactor * Math3d::EvaluateForm(diff, inverse_rgb_covariance));
00144 }
00145 
00146 float CRGBColorModel::CalculateColorDistanceSquared(int r, int g, int b)
00147 {
00148         const float rd = (r - rgb_mean.x);
00149         const float gd = (g - rgb_mean.y);
00150         const float bd = (b - rgb_mean.z);
00151         
00152         return rd * rd + gd * gd + bd * bd;
00153 }
00154         
00155 bool CRGBColorModel::LoadFromFile(const char *pFileName)
00156 {
00157         FILE *f = fopen(pFileName, "r");
00158         if (!f)
00159                 return false;
00160         
00161         if (fscanf(f, "%f %f %f\n", &rgb_mean.x, &rgb_mean.y, &rgb_mean.z) == EOF)
00162         {
00163                 fclose(f);
00164                 return false;
00165         }
00166                 
00167         if (fscanf(f, "%f %f %f %f %f %f %f %f %f\n",
00168                 &inverse_rgb_covariance.r1, &inverse_rgb_covariance.r2, &inverse_rgb_covariance.r3,
00169                 &inverse_rgb_covariance.r4, &inverse_rgb_covariance.r5, &inverse_rgb_covariance.r6,
00170                 &inverse_rgb_covariance.r7, &inverse_rgb_covariance.r8, &inverse_rgb_covariance.r9) == EOF)
00171         {
00172                 fclose(f);
00173                 return false;
00174         }
00175                 
00176         fclose(f);
00177                 
00178         return true;
00179 }
00180 
00181 bool CRGBColorModel::SaveToFile(const char *pFileName)
00182 {
00183         FILE *f = fopen(pFileName, "w");
00184         if (!f)
00185                 return false;
00186         
00187         if (fprintf(f, "%.10f %.10f %.10f\n", rgb_mean.x, rgb_mean.y, rgb_mean.z) < 0)
00188         {
00189                 fclose(f);
00190                 return false;
00191         }
00192                 
00193         if (fprintf(f, "%.10f %.10f %.10f %.10f %.10f %.10f %.10f %.10f %.10f\n",
00194                 inverse_rgb_covariance.r1, inverse_rgb_covariance.r2, inverse_rgb_covariance.r3,
00195                 inverse_rgb_covariance.r4, inverse_rgb_covariance.r5, inverse_rgb_covariance.r6,
00196                 inverse_rgb_covariance.r7, inverse_rgb_covariance.r8, inverse_rgb_covariance.r9) < 0)
00197         {
00198                 fclose(f);
00199                 return false;
00200         }
00201                 
00202         fclose(f);
00203         
00204         return true;
00205 }
00206 
00207 void CRGBColorModel::SetMean(const Vec3d &mean)
00208 {
00209         Math3d::SetVec(rgb_mean, mean);
00210 }
00211 
00212 void CRGBColorModel::SetInverseCovariance(const Mat3d &inverse_covariance)
00213 {
00214         Math3d::SetMat(inverse_rgb_covariance, inverse_covariance);
00215 }


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:58