$search
00001 /* 00002 * Copyright (c) 2011, Mårten Björkman (celle@csc.kth.se) 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are 00007 * met: 00008 * 00009 * 1.Redistributions of source code must retain the above copyright 00010 * notice, this list of conditions and the following disclaimer. 00011 * 2.Redistributions in binary form must reproduce the above 00012 * copyright notice, this list of conditions and the following 00013 * disclaimer in the documentation and/or other materials provided 00014 * with the distribution. 00015 * 3.The name of Mårten Björkman may not be used to endorse or 00016 * promote products derived from this software without specific 00017 * prior written permission. 00018 * 00019 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00020 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00021 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR 00022 * A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT 00023 * HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, 00024 * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT 00025 * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, 00026 * DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY 00027 * THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 00028 * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 00029 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00030 */ 00031 00032 #include <cmath> 00033 #include <algorithm> 00034 #include <float.h> 00035 #include <assert.h> 00036 #include "pyra/tpimage.h" 00037 #include "belief.h" 00038 #include "timercpu.h" 00039 00040 template<int dim> BeliefProp<dim>::BeliefProp(int w, int h) : width(w), height(h) 00041 { 00042 int sz = w*h; 00043 for (int i=0;i<dim;i++) { 00044 msgl[i] = new float[sz]; 00045 msgr[i] = new float[sz]; 00046 msgu[i] = new float[sz]; 00047 msgd[i] = new float[sz]; 00048 prior[i] = new float[sz]; 00049 belief[i] = new float[sz]; 00050 } 00051 costh = new float[sz]; 00052 costv = new float[sz]; 00053 } 00054 00055 template<int dim> BeliefProp<dim>::~BeliefProp() 00056 { 00057 for (int i=0;i<dim;i++) { 00058 delete [] msgl[i]; 00059 delete [] msgr[i]; 00060 delete [] msgu[i]; 00061 delete [] msgd[i]; 00062 delete [] prior[i]; 00063 delete [] belief[i]; 00064 } 00065 delete [] costh; 00066 delete [] costv; 00067 } 00068 00069 template<int dim> float **BeliefProp<dim>::GetPriors() 00070 { 00071 return prior; 00072 } 00073 00074 template<int dim> float **BeliefProp<dim>::GetBeliefs() 00075 { 00076 return belief; 00077 } 00078 00079 template<int dim> void BeliefProp<dim>::SetGradientCosts(Image<unsigned char> &img, float gamma) 00080 { 00081 assert(img.GetWidth()==width && img.GetHeight()==height); 00082 unsigned char *imd = img.GetData(); 00083 int sum = 0; 00084 for (int y=0;y<height-1;y++) { 00085 for (int x=0;x<width-1;x++) { 00086 int p = y*width + x; 00087 int diff = imd[p] - imd[p+width]; 00088 sum += diff*diff; 00089 diff = imd[p] - imd[p+1]; 00090 sum += diff*diff; 00091 } 00092 } 00093 float sumdiff2 = (float)sum / (2*(width-1)*(height-1)); 00094 float beta = -1.0f/(2.0f*sumdiff2); 00095 for (int y=0;y<height;y++) { 00096 for (int x=0;x<width-1;x++) { 00097 int p = y*width + x; 00098 float diff = imd[p] - imd[p+1]; 00099 costh[p] = gamma*exp(beta*diff*diff); 00100 } 00101 costh[y*width+width-1] = 0; 00102 } 00103 for (int y=0;y<height-1;y++) { 00104 for (int x=0;x<width;x++) { 00105 int p = y*width + x; 00106 float diff = imd[p] - imd[p+width]; 00107 costv[p] = gamma*exp(beta*diff*diff); 00108 } 00109 } 00110 for (int x=0;x<width;x++) 00111 costv[(height-1)*width+x] = 0; 00112 } 00113 00114 template<int dim> void BeliefProp<dim>::Execute(int loops) 00115 { 00116 InitMessages(); 00117 for (int i=0;i<loops;i++) 00118 UpdateMessages(); 00119 ComputeBeliefs(); 00120 } 00121 00122 template<int dim> void BeliefProp<dim>::Execute(int loops, int depth) 00123 { 00124 if (depth>0) { 00125 int w2 = width/2; 00126 int h2 = height/2; 00127 BeliefProp<dim> belief2(w2, h2); 00128 float **prior2 = belief2.GetPriors(); 00129 for (int l=0;l<dim;l++) { 00130 for (int y2=0;y2<h2;y2++) { 00131 float *ptr = &prior[l][2*y2*width]; 00132 float *ptr2 = &prior2[l][y2*w2]; 00133 for (int x2=0;x2<w2;x2++,ptr+=2) 00134 ptr2[x2] = ptr[0] + ptr[1] + ptr[width] + ptr[width+1]; 00135 } 00136 } 00137 for (int y2=0;y2<h2;y2++) { 00138 float *ptr = &costh[2*y2*width]; 00139 float *ptr2 = &belief2.costh[y2*w2]; 00140 for (int x2=0;x2<w2;x2++,ptr+=2) 00141 ptr2[x2] = ptr[1] + ptr[width+1]; 00142 ptr = &costv[2*y2*width]; 00143 ptr2 = &belief2.costv[y2*w2]; 00144 for (int x2=0;x2<w2;x2++,ptr+=2) 00145 ptr2[x2] = ptr[width] + ptr[width+1]; 00146 } 00147 belief2.Execute(loops, depth-1); 00148 for (int l=0;l<dim;l++) { 00149 for (int y2=0;y2<h2;y2++) { 00150 float *ptr = &msgl[l][2*y2*width]; 00151 float *ptr2 = &belief2.msgl[l][y2*w2]; 00152 for (int x2=0;x2<w2;x2++,ptr+=2) 00153 ptr[0] = ptr[1] = ptr[width] = ptr[width+1] = ptr2[x2]; 00154 ptr = &msgr[l][2*y2*width]; 00155 ptr2 = &belief2.msgr[l][y2*w2]; 00156 for (int x2=0;x2<w2;x2++,ptr+=2) 00157 ptr[0] = ptr[1] = ptr[width] = ptr[width+1] = ptr2[x2]; 00158 ptr = &msgu[l][2*y2*width]; 00159 ptr2 = &belief2.msgu[l][y2*w2]; 00160 for (int x2=0;x2<w2;x2++,ptr+=2) 00161 ptr[0] = ptr[1] = ptr[width] = ptr[width+1] = ptr2[x2]; 00162 ptr = &msgd[l][2*y2*width]; 00163 ptr2 = &belief2.msgd[l][y2*w2]; 00164 for (int x2=0;x2<w2;x2++,ptr+=2) 00165 ptr[0] = ptr[1] = ptr[width] = ptr[width+1] = ptr2[x2]; 00166 } 00167 } 00168 } else 00169 InitMessages(); 00170 TimerCPU timer(2800); 00171 for (int i=0;i<loops;i++) //(depth?loops:height);i++) 00172 UpdateMessages(); 00173 ComputeBeliefs(); 00174 std::cout << "Belief Time: " << timer.read() << std::endl; 00175 } 00176 00177 template<int dim> void BeliefProp<dim>::InitMessages() 00178 { 00179 int size = sizeof(float)*width*height; 00180 for (int i=0;i<dim;i++) { 00181 memset(msgl[i], 0, size); 00182 memset(msgr[i], 0, size); 00183 memset(msgu[i], 0, size); 00184 memset(msgd[i], 0, size); 00185 } 00186 } 00187 00188 template<int dim> void BeliefProp<dim>::ComputeBeliefs() 00189 { 00190 for (int i=0;i<dim;i++) 00191 for (int p=0;p<width*height;p++) 00192 belief[i][p] = prior[i][p] + msgl[i][p] + msgr[i][p] + msgu[i][p] + msgd[i][p]; 00193 } 00194 00195 template<int dim> void BeliefProp<dim>::UpdateMessages() 00196 { 00197 float h[dim]; 00198 for (int phase=0;phase<2;phase++) { 00199 for (int y=0;y<height;y++) { 00200 int start = (y+phase) & 1; 00201 for (int x=start;x<width;x+=2) { 00202 int q = y*width + x; 00203 if (x>0) { // message from left 00204 int p = q - 1; 00205 float minh = FLT_MAX; 00206 for (int i=0;i<dim;i++) { 00207 h[i] = prior[i][p] + msgl[i][p] + msgu[i][p] + msgd[i][p]; 00208 minh = (h[i]<minh ? h[i] : minh); 00209 } 00210 float minc = minh + costh[p]; 00211 for (int i=0;i<dim;i++) 00212 msgl[i][q] = (h[i]<minc ? h[i] : minc) - minh; 00213 } 00214 if (x<width-1) { 00215 int p = q + 1; // message from right 00216 float minh = FLT_MAX; 00217 for (int i=0;i<dim;i++) { 00218 h[i] = prior[i][p] + msgr[i][p] + msgu[i][p] + msgd[i][p]; 00219 minh = (h[i]<minh ? h[i] : minh); 00220 } 00221 float minc = minh + costh[q]; 00222 for (int i=0;i<dim;i++) 00223 msgr[i][q] = (h[i]<minc ? h[i] : minc) - minh; 00224 } 00225 if (y>0) { // message from up 00226 int p = q - width; 00227 float minh = FLT_MAX; 00228 for (int i=0;i<dim;i++) { 00229 h[i] = prior[i][p] + msgl[i][p] + msgr[i][p] + msgu[i][p]; 00230 minh = (h[i]<minh ? h[i] : minh); 00231 } 00232 float minc = minh + costv[p]; 00233 for (int i=0;i<dim;i++) 00234 msgu[i][q] = (h[i]<minc ? h[i] : minc) - minh; 00235 } 00236 if (y<height-1) { 00237 int p = q + width; // message from down 00238 float minh = FLT_MAX; 00239 for (int i=0;i<dim;i++) { 00240 h[i] = prior[i][p] + msgl[i][p] + msgr[i][p] + msgd[i][p]; 00241 minh = (h[i]<minh ? h[i] : minh); 00242 } 00243 float minc = minh + costv[q]; 00244 for (int i=0;i<dim;i++) 00245 msgd[i][q] = (h[i]<minc ? h[i] : minc) - minh; 00246 } 00247 } 00248 } 00249 } 00250 } 00251 00252 #if 0 00253 00254 #include "GCoptimization.h" 00255 00256 template<int dim> void BeliefProp<dim>::ComputeMAP(Image<unsigned char> &mask) 00257 { 00258 MSR clk0, clk1; 00259 clk0.getTSC(); 00260 00261 int scale = 100; 00262 // stores result of optimization 00263 int *result = new int[width*height]; 00264 // first set up the array for data costs 00265 int *data = new int[width*height*dim]; 00266 for (int i=0;i<width*height;i++) 00267 for (int l=0;l<dim;l++) 00268 data[i*dim + l] = (int)(scale*prior[l][i]); 00269 00270 // next set up the array for smooth costs 00271 int smooth[dim*dim]; 00272 for (int l1=0;l1<dim;l1++) 00273 for (int l2=0;l2<dim;l2++) 00274 smooth[l2*dim + l1] = (l1 == l2 ? 0 : scale); 00275 00276 // next set up spatially varying arrays V and H 00277 int *V = new int[width*height]; 00278 int *H = new int[width*height]; 00279 for (int y=0;y<height;y++) { 00280 for (int x=0;x<width;x++) { 00281 int p = y*width + x; 00282 H[p] = (int)costv[p]; 00283 V[p] = (int)costh[p]; 00284 } 00285 } 00286 00287 try { 00288 GCoptimizationGridGraph *gc = new GCoptimizationGridGraph(width, height, dim); 00289 gc->setDataCost(data); 00290 gc->setSmoothCostVH(smooth, V, H); 00291 std::cout << "Before optimization energy is " << (int)gc->compute_energy() << std::endl; 00292 gc->expansion(10);// run expansion for 2 iterations. For swap use gc->swap(num_iterations); 00293 std::cout << "After optimization energy is " << (int)gc->compute_energy() << std::endl; 00294 00295 for (int i=0;i<width*height;i++) 00296 result[i] = gc->whatLabel(i); 00297 delete gc; 00298 } 00299 catch (GCException e) { 00300 e.Report(); 00301 } 00302 clk1.getTSC(); 00303 std::cout << "ComputeMAP Time: " << 256.0*clk1.diff(clk0, 8)/2670.0e3 << std::endl; 00304 00305 static int cnt = 0; 00306 Image<int> maski(width, height, result); 00307 char filename[80]; 00308 sprintf(filename, "mask%d.pgm", cnt++); 00309 maski.Store(filename, true, false); 00310 00311 delete [] result; 00312 delete [] V; 00313 delete [] H; 00314 delete [] data; 00315 } 00316 00317 #endif