hog.c
Go to the documentation of this file.
00001 
00006 /*
00007  Copyright (C) 2007-12 Andrea Vedaldi and Brian Fulkerson.
00008  All rights reserved.
00009 
00010  This file is part of the VLFeat library and is made available under
00011  the terms of the BSD license (see the COPYING file).
00012 */
00013 
00014 #include "hog.h"
00015 #include "mathop.h"
00016 #include <string.h>
00017 
00159 /* ---------------------------------------------------------------- */
00173 VlHog *
00174 vl_hog_new (VlHogVariant variant, vl_size numOrientations, vl_bool transposed)
00175 {
00176   vl_index o, k ;
00177   VlHog * self = vl_calloc(1, sizeof(VlHog)) ;
00178 
00179   assert(numOrientations >= 1) ;
00180 
00181   self->variant = variant ;
00182   self->numOrientations = numOrientations ;
00183   self->glyphSize = 21 ;
00184   self->transposed = transposed ;
00185   self->useBilinearOrientationAssigment = VL_FALSE ;
00186   self->orientationX = vl_malloc(sizeof(float) * self->numOrientations) ;
00187   self->orientationY = vl_malloc(sizeof(float) * self->numOrientations) ;
00188 
00189   /*
00190    Create a vector along the center of each orientation bin. These
00191    are used to map gradients to bins. If the image is transposed,
00192    then this can be adjusted here by swapping X and Y in these
00193    vectors.
00194    */
00195   for(o = 0 ; o < (signed)self->numOrientations ; ++o) {
00196     double angle = o * VL_PI / self->numOrientations ;
00197     if (!self->transposed) {
00198       self->orientationX[o] = (float) cos(angle) ;
00199       self->orientationY[o] = (float) sin(angle) ;
00200     } else {
00201       self->orientationX[o] = (float) sin(angle) ;
00202       self->orientationY[o] = (float) cos(angle) ;
00203     }
00204   }
00205 
00206   /*
00207    If the number of orientation is equal to 9, one gets:
00208 
00209    Uoccti:: 18 directed orientations + 9 undirected orientations + 4 texture
00210    DalalTriggs:: 9 undirected orientations x 4 blocks.
00211    */
00212   switch (self->variant) {
00213     case VlHogVariantUoctti:
00214       self->dimension = 3*self->numOrientations + 4 ;
00215       break ;
00216 
00217     case VlHogVariantDalalTriggs:
00218       self->dimension = 4*self->numOrientations ;
00219       break ;
00220 
00221     default:
00222       assert(0) ;
00223   }
00224 
00225   /*
00226    A permutation specifies how to permute elements in a HOG
00227    descriptor to flip it horizontally. Since the first orientation
00228    of index 0 points to the right, this must be swapped with orientation
00229    self->numOrientation that points to the left (for the directed case,
00230    and to itself for the undirected one).
00231    */
00232 
00233   self->permutation = vl_malloc(self->dimension * sizeof(vl_index)) ;
00234   switch (self->variant) {
00235     case VlHogVariantUoctti:
00236       for(o = 0 ; o < (signed)self->numOrientations ; ++o) {
00237         vl_index op = self->numOrientations - o ;
00238         self->permutation[o] = op ;
00239         self->permutation[o + self->numOrientations] = (op + self->numOrientations) % (2*self->numOrientations) ;
00240         self->permutation[o + 2*self->numOrientations] = (op % self->numOrientations) + 2*self->numOrientations ;
00241       }
00242       for (k = 0 ; k < 4 ; ++k) {
00243         /* The texture features correspond to four displaced block around
00244          a cell. These permute with a lr flip as for DalalTriggs. */
00245         vl_index blockx = k % 2 ;
00246         vl_index blocky = k / 2 ;
00247         vl_index q = (1 - blockx) + blocky * 2 ;
00248         self->permutation[k + self->numOrientations * 3] = q + self->numOrientations * 3 ;
00249       }
00250       break ;
00251 
00252     case VlHogVariantDalalTriggs:
00253       for(k = 0 ; k < 4 ; ++k) {
00254         /* Find the corresponding block. Blocks are listed in order 1,2,3,4,...
00255            from left to right and top to bottom */
00256         vl_index blockx = k % 2 ;
00257         vl_index blocky = k / 2 ;
00258         vl_index q = (1 - blockx) + blocky * 2 ;
00259         for(o = 0 ; o < (signed)self->numOrientations ; ++o) {
00260           vl_index op = self->numOrientations - o ;
00261           self->permutation[o + k*self->numOrientations] = (op % self->numOrientations) + q*self->numOrientations ;
00262         }
00263       }
00264       break ;
00265 
00266     default:
00267       assert(0) ;
00268   }
00269 
00270   /*
00271    Create glyphs for representing the HOG features/ filters. The glyphs
00272    are simple bars, oriented orthogonally to the gradients to represent
00273    image edges. If the object is configured to work on transposed image,
00274    the glyphs images are also stored in column-major.
00275    */
00276   self->glyphs = vl_calloc(self->glyphSize * self->glyphSize * self->numOrientations, sizeof(float)) ;
00277 #define atglyph(x,y,k) self->glyphs[(x) + self->glyphSize * (y) + self->glyphSize * self->glyphSize * (k)]
00278   for (o = 0 ; o < (signed)self->numOrientations ; ++o) {
00279     double angle = fmod(o * VL_PI / self->numOrientations + VL_PI/2, VL_PI) ;
00280     double x2 = self->glyphSize * cos(angle) / 2 ;
00281     double y2 = self->glyphSize * sin(angle) / 2 ;
00282 
00283     if (angle <= VL_PI / 4 || angle >= VL_PI * 3 / 4) {
00284       /* along horizontal direction */
00285       double slope = y2 / x2 ;
00286       double offset = (1 - slope) * (self->glyphSize - 1) / 2 ;
00287       vl_index skip = (1 - fabs(cos(angle))) / 2 * self->glyphSize ;
00288       vl_index i, j ;
00289       for (i = skip ; i < (signed)self->glyphSize - skip ; ++i) {
00290         j = vl_round_d(slope * i + offset) ;
00291         if (! self->transposed) {
00292           atglyph(i,j,o) = 1 ;
00293         } else {
00294           atglyph(j,i,o) = 1 ;
00295         }
00296       }
00297     } else {
00298       /* along vertical direction */
00299       double slope = x2 / y2 ;
00300       double offset = (1 - slope) * (self->glyphSize - 1) / 2 ;
00301       vl_index skip = (1 - sin(angle)) / 2 * self->glyphSize ;
00302       vl_index i, j ;
00303       for (j = skip ; j < (signed)self->glyphSize - skip; ++j) {
00304         i = vl_round_d(slope * j + offset) ;
00305         if (! self->transposed) {
00306           atglyph(i,j,o) = 1 ;
00307         } else {
00308           atglyph(j,i,o) = 1 ;
00309         }
00310       }
00311     }
00312   }
00313   return self ;
00314 }
00315 
00316 /* ---------------------------------------------------------------- */
00321 void
00322 vl_hog_delete (VlHog * self)
00323 {
00324   if (self->orientationX) {
00325     vl_free(self->orientationX) ;
00326     self->orientationX = NULL ;
00327   }
00328 
00329   if (self->orientationY) {
00330     vl_free(self->orientationY) ;
00331     self->orientationY = NULL ;
00332   }
00333 
00334   if (self->glyphs) {
00335     vl_free(self->glyphs) ;
00336     self->glyphs = NULL ;
00337   }
00338 
00339   if (self->permutation) {
00340     vl_free(self->permutation) ;
00341     self->permutation = NULL ;
00342   }
00343 
00344   if (self->hog) {
00345     vl_free(self->hog) ;
00346     self->hog = NULL ;
00347   }
00348 
00349   if (self->hogNorm) {
00350     vl_free(self->hogNorm) ;
00351     self->hogNorm = NULL ;
00352   }
00353 
00354   vl_free(self) ;
00355 }
00356 
00357 
00358 /* ---------------------------------------------------------------- */
00364 vl_size
00365 vl_hog_get_glyph_size (VlHog const * self)
00366 {
00367   return self->glyphSize ;
00368 }
00369 
00370 /* ---------------------------------------------------------------- */
00382 vl_index const *
00383 vl_hog_get_permutation (VlHog const * self)
00384 {
00385   return self->permutation ;
00386 }
00387 
00388 /* ---------------------------------------------------------------- */
00394 void
00395 vl_hog_set_use_bilinear_orientation_assignments (VlHog * self, vl_bool x) {
00396   self->useBilinearOrientationAssigment = x ;
00397 }
00398 
00404 vl_bool
00405 vl_hog_get_use_bilinear_orientation_assignments (VlHog const * self) {
00406   return self->useBilinearOrientationAssigment ;
00407 }
00408 
00409 /* ---------------------------------------------------------------- */
00427 void
00428 vl_hog_render (VlHog const * self,
00429                float * image,
00430                float const * descriptor,
00431                vl_size width,
00432                vl_size height)
00433 {
00434   vl_index x, y, k, cx, cy ;
00435   vl_size hogStride = width * height ;
00436 
00437   assert(self) ;
00438   assert(image) ;
00439   assert(descriptor) ;
00440   assert(width > 0) ;
00441   assert(height > 0) ;
00442 
00443   for (y = 0 ; y < (signed)height ; ++y) {
00444     for (x = 0 ; x < (signed)width ; ++x) {
00445       float minWeight = 0 ;
00446       float maxWeight = 0 ;
00447 
00448       for (k = 0 ; k < (signed)self->numOrientations ; ++k) {
00449         float weight ;
00450         float const * glyph = self->glyphs + k * (self->glyphSize*self->glyphSize) ;
00451         float * glyphImage = image + self->glyphSize * x + y * width * (self->glyphSize*self->glyphSize) ;
00452 
00453         switch (self->variant) {
00454           case VlHogVariantUoctti:
00455             weight =
00456             descriptor[k * hogStride] +
00457             descriptor[(k + self->numOrientations) * hogStride] +
00458             descriptor[(k + 2 * self->numOrientations) * hogStride] ;
00459             break ;
00460           case VlHogVariantDalalTriggs:
00461             weight =
00462             descriptor[k * hogStride] +
00463             descriptor[(k + self->numOrientations) * hogStride] +
00464             descriptor[(k + 2 * self->numOrientations) * hogStride] +
00465             descriptor[(k + 3 * self->numOrientations) * hogStride] ;
00466             break ;
00467           default:
00468             abort() ;
00469         }
00470         maxWeight = VL_MAX(weight, maxWeight) ;
00471         minWeight = VL_MIN(weight, minWeight);
00472 
00473         for (cy = 0 ; cy < (signed)self->glyphSize ; ++cy) {
00474           for (cx = 0 ; cx < (signed)self->glyphSize ; ++cx) {
00475             *glyphImage++ += weight * (*glyph++) ;
00476           }
00477           glyphImage += (width - 1) * self->glyphSize  ;
00478         }
00479       } /* next orientation */
00480 
00481       {
00482         float * glyphImage = image + self->glyphSize * x + y * width * (self->glyphSize*self->glyphSize) ;
00483         for (cy = 0 ; cy < (signed)self->glyphSize ; ++cy) {
00484           for (cx = 0 ; cx < (signed)self->glyphSize ; ++cx) {
00485             float value = *glyphImage ;
00486             *glyphImage++ = VL_MAX(minWeight, VL_MIN(maxWeight, value)) ;
00487           }
00488           glyphImage += (width - 1) * self->glyphSize  ;
00489         }
00490       }
00491 
00492       ++ descriptor ;
00493     } /* next column of cells (x) */
00494   } /* next row of cells (y) */
00495 }
00496 
00497 /* ---------------------------------------------------------------- */
00503 vl_size
00504 vl_hog_get_dimension (VlHog const * self)
00505 {
00506   return self->dimension ;
00507 }
00508 
00514 vl_size
00515 vl_hog_get_width (VlHog * self)
00516 {
00517   return self->hogWidth ;
00518 }
00519 
00525 vl_size
00526 vl_hog_get_height (VlHog * self)
00527 {
00528   return self->hogHeight ;
00529 }
00530 
00531 /* ---------------------------------------------------------------- */
00539 static void
00540 vl_hog_prepare_buffers (VlHog * self, vl_size width, vl_size height, vl_size cellSize)
00541 {
00542   vl_size hogWidth = (width + cellSize/2) / cellSize ;
00543   vl_size hogHeight = (height + cellSize/2) / cellSize ;
00544 
00545   assert(width > 3) ;
00546   assert(height > 3) ;
00547   assert(hogWidth > 0) ;
00548   assert(hogHeight > 0) ;
00549 
00550   if (self->hog &&
00551       self->hogWidth == hogWidth &&
00552       self->hogHeight == hogHeight) {
00553     /* a suitable buffer is already allocated */
00554     memset(self->hog, 0, sizeof(float) * hogWidth * hogHeight * self->numOrientations * 2) ;
00555     memset(self->hogNorm, 0, sizeof(float) * hogWidth * hogHeight) ;
00556     return ;
00557   }
00558 
00559   if (self->hog) {
00560     vl_free(self->hog) ;
00561     self->hog = NULL ;
00562   }
00563 
00564   if (self->hogNorm) {
00565     vl_free(self->hogNorm) ;
00566     self->hogNorm = NULL ;
00567   }
00568 
00569   self->hog = vl_calloc(hogWidth * hogHeight * self->numOrientations * 2, sizeof(float)) ;
00570   self->hogNorm = vl_calloc(hogWidth * hogHeight, sizeof(float)) ;
00571   self->hogWidth = hogWidth ;
00572   self->hogHeight = hogHeight ;
00573 }
00574 
00575 /* ---------------------------------------------------------------- */
00595 void
00596 vl_hog_put_image (VlHog * self,
00597                   float const * image,
00598                   vl_size width, vl_size height, vl_size numChannels,
00599                   vl_size cellSize)
00600 {
00601   vl_size hogStride ;
00602   vl_size channelStride = width * height ;
00603   vl_index x, y ;
00604   vl_uindex k ;
00605 
00606   assert(self) ;
00607   assert(image) ;
00608 
00609   /* clear features */
00610   vl_hog_prepare_buffers(self, width, height, cellSize) ;
00611   hogStride = self->hogWidth * self->hogHeight ;
00612 
00613 #define at(x,y,k) (self->hog[(x) + (y) * self->hogWidth + (k) * hogStride])
00614 
00615   /* compute gradients and map the to HOG cells by bilinear interpolation */
00616   for (y = 1 ; y < (signed)height - 1 ; ++y) {
00617     for (x = 1 ; x < (signed)width - 1 ; ++x) {
00618       float gradx = 0 ;
00619       float grady = 0 ;
00620       float gradNorm ;
00621       float orientationWeights [2] = {-1, -1} ;
00622       vl_index orientationBins [2] = {-1, -1} ;
00623       vl_index orientation = 0 ;
00624       float hx, hy, wx1, wx2, wy1, wy2 ;
00625       vl_index binx, biny, o ;
00626 
00627       /*
00628        Compute the gradient at (x,y). The image channel with
00629        the maximum gradient at each location is selected.
00630        */
00631       {
00632         float const * iter = image + y * width + x ;
00633         float gradNorm2 = 0 ;
00634         for (k = 0 ; k < numChannels ; ++k) {
00635           float gradx_ = *(iter + 1) - *(iter - 1) ;
00636           float grady_ = *(iter + width)  - *(iter - width) ;
00637           float gradNorm2_ = gradx_ * gradx_ + grady_ * grady_ ;
00638           if (gradNorm2_ > gradNorm2) {
00639             gradx = gradx_ ;
00640             grady = grady_ ;
00641             gradNorm2 = gradNorm2_ ;
00642           }
00643           iter += channelStride ;
00644         }
00645         gradNorm = sqrtf(gradNorm2) ;
00646       }
00647 
00648       /*
00649        Map the gradient to the closest and second closets orientation bins.
00650        There are numOrientations orientation in the interval [0,pi).
00651        The next numOriantations are the symmetric ones, for a total
00652        of 2*numOrientation directed orientations.
00653        */
00654       for (k = 0 ; k < self->numOrientations ; ++k) {
00655         float orientationScore_ = gradx * self->orientationX[k] +  grady * self->orientationY[k] ;
00656         vl_index orientationBin_ = k ;
00657         if (orientationScore_ < 0) {
00658           orientationScore_ = - orientationScore_ ;
00659           orientationBin_ += self->numOrientations ;
00660         }
00661         if (orientationScore_ > orientationWeights[0]) {
00662           orientationBins[1] = orientationBins[0] ;
00663           orientationWeights[1] = orientationWeights[0] ;
00664           orientationBins[0] = orientationBin_ ; ;
00665           orientationWeights[0] = orientationScore_ ;
00666         } else if (orientationScore_ > orientationWeights[1]) {
00667           orientationBins[1] = orientationBin_ ;
00668           orientationWeights[1] = orientationScore_ ;
00669         }
00670       }
00671 
00672       if (self->useBilinearOrientationAssigment) {
00673         /* min(1.0,...) guards against small overflows causing NaNs */
00674         float angle0 = acosf(VL_MIN(orientationWeights[0] / VL_MAX(gradNorm, 1e-10),1.0)) ;
00675         orientationWeights[1] = angle0 / (VL_PI / self->numOrientations) ;
00676         orientationWeights[0] = 1 - orientationWeights[1] ;
00677       } else {
00678         orientationWeights[0] = 1 ;
00679         orientationBins[1] = -1 ;
00680       }
00681 
00682       for (o = 0 ; o < 2 ; ++o) {
00683         float ow ;
00684         /*
00685          Accumulate the gradient. hx is the distance of the
00686          pixel x to the cell center at its left, in units of cellSize.
00687          With this parametrixation, a pixel on the cell center
00688          has hx = 0, which gradually increases to 1 moving to the next
00689          center.
00690          */
00691 
00692         orientation = orientationBins[o] ;
00693         if (orientation < 0) continue ;
00694 
00695         /*  (x - (w-1)/2) / w = (x + 0.5)/w - 0.5 */
00696         hx = (x + 0.5) / cellSize - 0.5 ;
00697         hy = (y + 0.5) / cellSize - 0.5 ;
00698         binx = vl_floor_f(hx) ;
00699         biny = vl_floor_f(hy) ;
00700         wx2 = hx - binx ;
00701         wy2 = hy - biny ;
00702         wx1 = 1.0 - wx2 ;
00703         wy1 = 1.0 - wy2 ;
00704 
00705         ow = orientationWeights[o] ;
00706 
00707         /*VL_PRINTF("%d %d - %d %d %f %f - %f %f %f %f - %d \n ",x,y,binx,biny,hx,hy,wx1,wx2,wy1,wy2,o);*/
00708 
00709         if (binx >= 0 && biny >=0) {
00710           at(binx,biny,orientation) += gradNorm * ow * wx1 * wy1 ;
00711         }
00712         if (binx < (signed)self->hogWidth - 1 && biny >=0) {
00713           at(binx+1,biny,orientation) += gradNorm * ow * wx2 * wy1 ;
00714         }
00715         if (binx < (signed)self->hogWidth - 1 && biny < (signed)self->hogHeight - 1) {
00716           at(binx+1,biny+1,orientation) += gradNorm * ow * wx2 * wy2 ;
00717         }
00718         if (binx >= 0 && biny < (signed)self->hogHeight - 1) {
00719           at(binx,biny+1,orientation) += gradNorm * ow * wx1 * wy2 ;
00720         }
00721       } /* next o */
00722     } /* next x */
00723   } /* next y */
00724 }
00725 
00726 /* ---------------------------------------------------------------- */
00742 void vl_hog_put_polar_field (VlHog * self,
00743                              float const * modulus,
00744                              float const * angle,
00745                              vl_bool directed,
00746                              vl_size width, vl_size height,
00747                              vl_size cellSize)
00748 {
00749   vl_size hogStride ;
00750   vl_index x, y, o ;
00751   vl_index period = self->numOrientations * (directed ? 2 : 1) ;
00752   double angleStep = VL_PI / self->numOrientations ;
00753 
00754   assert(self) ;
00755   assert(modulus) ;
00756   assert(angle) ;
00757 
00758   /* clear features */
00759   vl_hog_prepare_buffers(self, width, height, cellSize) ;
00760   hogStride = self->hogWidth * self->hogHeight ;
00761 
00762 #define at(x,y,k) (self->hog[(x) + (y) * self->hogWidth + (k) * hogStride])
00763 #define atNorm(x,y) (self->hogNorm[(x) + (y) * self->hogWidth])
00764 
00765   /* fill HOG cells from gradient field */
00766   for (y = 0 ; y < (signed)height ; ++y) {
00767     for (x = 0 ; x < (signed)width ; ++x) {
00768       float ho, hx, hy, wo1, wo2, wx1, wx2, wy1, wy2 ;
00769       vl_index bino, binx, biny ;
00770       float orientationWeights [2] = {0,0} ;
00771       vl_index orientationBins [2] = {-1,-1} ;
00772       vl_index orientation = 0 ;
00773       float thisAngle = *angle++ ;
00774       float thisModulus = *modulus++ ;
00775 
00776       if (thisModulus <= 0.0f) continue ;
00777 
00778       /*  (x - (w-1)/2) / w = (x + 0.5)/w - 0.5 */
00779 
00780       ho = (float)thisAngle / angleStep ;
00781       bino = vl_floor_f(ho) ;
00782       wo2 = ho - bino ;
00783       wo1 = 1.0f - wo2 ;
00784 
00785       while (bino < 0) { bino += self->numOrientations * 2 ; }
00786 
00787       if (self->useBilinearOrientationAssigment) {
00788         orientationBins[0] = bino % period ;
00789         orientationBins[1] = (bino + 1) % period ;
00790         orientationWeights[0] = wo1 ;
00791         orientationWeights[1] = wo2 ;
00792       } else {
00793         orientationBins[0] = (bino + ((wo1 > wo2) ? 0 : 1)) % period ;
00794         orientationWeights[0] = 1 ;
00795         orientationBins[1] = -1 ;
00796       }
00797 
00798       for (o = 0 ; o < 2 ; ++o) {
00799         /*
00800          Accumulate the gradient. hx is the distance of the
00801          pixel x to the cell center at its left, in units of cellSize.
00802          With this parametrixation, a pixel on the cell center
00803          has hx = 0, which gradually increases to 1 moving to the next
00804          center.
00805          */
00806 
00807         orientation = orientationBins[o] ;
00808         if (orientation < 0) continue ;
00809 
00810         hx = (x + 0.5) / cellSize - 0.5 ;
00811         hy = (y + 0.5) / cellSize - 0.5 ;
00812         binx = vl_floor_f(hx) ;
00813         biny = vl_floor_f(hy) ;
00814         wx2 = hx - binx ;
00815         wy2 = hy - biny ;
00816         wx1 = 1.0 - wx2 ;
00817         wy1 = 1.0 - wy2 ;
00818 
00819         wx1 *= orientationWeights[o] ;
00820         wx2 *= orientationWeights[o] ;
00821         wy1 *= orientationWeights[o] ;
00822         wy2 *= orientationWeights[o] ;
00823 
00824         /*VL_PRINTF("%d %d - %d %d %f %f - %f %f %f %f - %d \n ",x,y,binx,biny,hx,hy,wx1,wx2,wy1,wy2,o);*/
00825 
00826         if (binx >= 0 && biny >=0) {
00827           at(binx,biny,orientation) += thisModulus * wx1 * wy1 ;
00828         }
00829         if (binx < (signed)self->hogWidth - 1 && biny >=0) {
00830           at(binx+1,biny,orientation) += thisModulus * wx2 * wy1 ;
00831         }
00832         if (binx < (signed)self->hogWidth - 1 && biny < (signed)self->hogHeight - 1) {
00833           at(binx+1,biny+1,orientation) += thisModulus * wx2 * wy2 ;
00834         }
00835         if (binx >= 0 && biny < (signed)self->hogHeight - 1) {
00836           at(binx,biny+1,orientation) += thisModulus * wx1 * wy2 ;
00837         }
00838       } /* next o */
00839     } /* next x */
00840   } /* next y */
00841 }
00842 
00843 /* ---------------------------------------------------------------- */
00853 void
00854 vl_hog_extract (VlHog * self, float * features)
00855 {
00856   vl_index x, y ;
00857   vl_uindex k ;
00858   vl_size hogStride = self->hogWidth * self->hogHeight ;
00859 
00860   assert(features) ;
00861 
00862 #define at(x,y,k) (self->hog[(x) + (y) * self->hogWidth + (k) * hogStride])
00863 #define atNorm(x,y) (self->hogNorm[(x) + (y) * self->hogWidth])
00864 
00865   /*
00866    Compute the squared L2 norm of the unoriented version of each HOG
00867    cell histogram. The unoriented version is obtained by folding
00868    the 2*numOrientations compotnent into numOrientations only.
00869    */
00870   {
00871     float const * iter = self->hog ;
00872     for (k = 0 ; k < self->numOrientations ; ++k) {
00873       float * niter = self->hogNorm ;
00874       float * niterEnd = self->hogNorm + self->hogWidth * self->hogHeight ;
00875       vl_size stride = self->hogWidth*self->hogHeight*self->numOrientations ;
00876       while (niter != niterEnd) {
00877         float h1 = *iter ;
00878         float h2 = *(iter + stride) ;
00879         float h = h1 + h2 ;
00880         *niter += h * h ;
00881         niter++ ;
00882         iter++ ;
00883       }
00884     }
00885   }
00886 
00887   /*
00888    HOG block-normalisation.
00889 
00890    The Dalal-Triggs implementation computes a normalized descriptor for
00891    each block of 2x2 cells, by stacking the histograms of each cell
00892    into a vector and L2-normalizing and truncating the result.
00893    
00894    Each block-level descriptor is then decomposed back into cells
00895    and corresponding parts are stacked into cell-level descritpors.
00896    Each HOG cell is contained in exactly
00897    four 2x2 cell blocks. For example, the cell number 5 in the following
00898    figure is contained in blocks 1245, 2356, 4578, 5689:
00899 
00900    +---+---+---+
00901    | 1 | 2 | 3 |
00902    +---+---+---+
00903    | 4 | 5 | 6 |
00904    +---+---+---+
00905    | 7 | 8 | 9 |
00906    +---+---+---+
00907 
00908    Hence, when block-level descriptors are decomposed back
00909    into cells, each cell receives contributions from four blocks. So,
00910    if each cell started with a D-dimensional histogram, it
00911    ends up with a 4D dimesional descriptor vector.
00912 
00913    Note however that this is just a convenient way of rewriting the 
00914    blocks as per-cell contributions, but the block information
00915    is unchanged. In particular, barring boundary effects,
00916    in an array of H x W cells there are approximately HW blocks;
00917    hence the L2 norm of all the blocks stacked is approximately HW
00918    (because individual blocks are L2-normalized). Since this does
00919    not change in the final HOG descriptor,
00920    the L2 norm of the HOG descriptor of an image should be approximately
00921    the same as the area of the image divided by the
00922    area of a HOG cell. This can be used as a sanity check.
00923 
00924    The UoCTTI variant differs in some non-negligible ways. First, 
00925    it includes both oriented and unoriented histograms, as well
00926    as four components capturing texture. Second, and most importantly, 
00927    it merges the four chunks of block-level descirptors landing in
00928    each cell into one by taking their average. This makes sense
00929    because, ultimately, these four sub-descriptors are identical
00930    to the original cell histogram, just with four different normalisations
00931    applied.
00932    */
00933   {
00934     float const * iter = self->hog ;
00935     for (y = 0 ; y < (signed)self->hogHeight ; ++y) {
00936       for (x = 0 ; x < (signed)self->hogWidth ; ++x) {
00937 
00938         /* norm of upper-left, upper-right, ... cells */
00939         vl_index xm = VL_MAX(x - 1, 0) ;
00940         vl_index xp = VL_MIN(x + 1, (signed)self->hogWidth - 1) ;
00941         vl_index ym = VL_MAX(y - 1, 0) ;
00942         vl_index yp = VL_MIN(y + 1, (signed)self->hogHeight - 1) ;
00943 
00944         double norm1 = atNorm(xm,ym) ;
00945         double norm2 = atNorm(x,ym) ;
00946         double norm3 = atNorm(xp,ym) ;
00947         double norm4 = atNorm(xm,y) ;
00948         double norm5 = atNorm(x,y) ;
00949         double norm6 = atNorm(xp,y) ;
00950         double norm7 = atNorm(xm,yp) ;
00951         double norm8 = atNorm(x,yp) ;
00952         double norm9 = atNorm(xp,yp) ;
00953 
00954         double factor1, factor2, factor3, factor4 ;
00955 
00956         double t1 = 0 ;
00957         double t2 = 0 ;
00958         double t3 = 0 ;
00959         double t4 = 0 ;
00960 
00961         float * oiter = features + x + self->hogWidth * y ;
00962 
00963         /* each factor is the inverse of the l2 norm of one of the 2x2 blocks surrounding
00964            cell x,y */
00965 #if 0
00966         if (self->transposed) {
00967           /* if the image is transposed, y and x are swapped */
00968           factor1 = 1.0 / VL_MAX(sqrt(norm1 + norm2 + norm4 + norm5), 1e-10) ;
00969           factor3 = 1.0 / VL_MAX(sqrt(norm2 + norm3 + norm5 + norm6), 1e-10) ;
00970           factor2 = 1.0 / VL_MAX(sqrt(norm4 + norm5 + norm7 + norm8), 1e-10) ;
00971           factor4 = 1.0 / VL_MAX(sqrt(norm5 + norm6 + norm8 + norm9), 1e-10) ;
00972         } else {
00973           factor1 = 1.0 / VL_MAX(sqrt(norm1 + norm2 + norm4 + norm5), 1e-10) ;
00974           factor2 = 1.0 / VL_MAX(sqrt(norm2 + norm3 + norm5 + norm6), 1e-10) ;
00975           factor3 = 1.0 / VL_MAX(sqrt(norm4 + norm5 + norm7 + norm8), 1e-10) ;
00976           factor4 = 1.0 / VL_MAX(sqrt(norm5 + norm6 + norm8 + norm9), 1e-10) ;
00977         }
00978 #else
00979         /* as implemented in UOCTTI code */
00980         if (self->transposed) {
00981           /* if the image is transposed, y and x are swapped */
00982           factor1 = 1.0 / sqrt(norm1 + norm2 + norm4 + norm5 + 1e-4) ;
00983           factor3 = 1.0 / sqrt(norm2 + norm3 + norm5 + norm6 + 1e-4) ;
00984           factor2 = 1.0 / sqrt(norm4 + norm5 + norm7 + norm8 + 1e-4) ;
00985           factor4 = 1.0 / sqrt(norm5 + norm6 + norm8 + norm9 + 1e-4) ;
00986         } else {
00987           factor1 = 1.0 / sqrt(norm1 + norm2 + norm4 + norm5 + 1e-4) ;
00988           factor2 = 1.0 / sqrt(norm2 + norm3 + norm5 + norm6 + 1e-4) ;
00989           factor3 = 1.0 / sqrt(norm4 + norm5 + norm7 + norm8 + 1e-4) ;
00990           factor4 = 1.0 / sqrt(norm5 + norm6 + norm8 + norm9 + 1e-4) ;
00991         }
00992 #endif
00993 
00994         for (k = 0 ; k < self->numOrientations ; ++k) {
00995           double ha = iter[hogStride * k] ;
00996           double hb = iter[hogStride * (k + self->numOrientations)] ;
00997           double hc ;
00998 
00999           double ha1 = factor1 * ha ;
01000           double ha2 = factor2 * ha ;
01001           double ha3 = factor3 * ha ;
01002           double ha4 = factor4 * ha ;
01003 
01004           double hb1 = factor1 * hb ;
01005           double hb2 = factor2 * hb ;
01006           double hb3 = factor3 * hb ;
01007           double hb4 = factor4 * hb ;
01008 
01009           double hc1 = ha1 + hb1 ;
01010           double hc2 = ha2 + hb2 ;
01011           double hc3 = ha3 + hb3 ;
01012           double hc4 = ha4 + hb4 ;
01013 
01014           ha1 = VL_MIN(0.2, ha1) ;
01015           ha2 = VL_MIN(0.2, ha2) ;
01016           ha3 = VL_MIN(0.2, ha3) ;
01017           ha4 = VL_MIN(0.2, ha4) ;
01018 
01019           hb1 = VL_MIN(0.2, hb1) ;
01020           hb2 = VL_MIN(0.2, hb2) ;
01021           hb3 = VL_MIN(0.2, hb3) ;
01022           hb4 = VL_MIN(0.2, hb4) ;
01023 
01024           hc1 = VL_MIN(0.2, hc1) ;
01025           hc2 = VL_MIN(0.2, hc2) ;
01026           hc3 = VL_MIN(0.2, hc3) ;
01027           hc4 = VL_MIN(0.2, hc4) ;
01028 
01029           t1 += hc1 ;
01030           t2 += hc2 ;
01031           t3 += hc3 ;
01032           t4 += hc4 ;
01033 
01034           switch (self->variant) {
01035             case VlHogVariantUoctti :
01036               ha = 0.5 * (ha1 + ha2 + ha3 + ha4) ;
01037               hb = 0.5 * (hb1 + hb2 + hb3 + hb4) ;
01038               hc = 0.5 * (hc1 + hc2 + hc3 + hc4) ;
01039               *oiter = ha ;
01040               *(oiter + hogStride * self->numOrientations) = hb ;
01041               *(oiter + 2 * hogStride * self->numOrientations) = hc ;
01042               break ;
01043 
01044             case VlHogVariantDalalTriggs :
01045               *oiter = hc1 ;
01046               *(oiter + hogStride * self->numOrientations) = hc2 ;
01047               *(oiter + 2 * hogStride * self->numOrientations) = hc3 ;
01048               *(oiter + 3 * hogStride * self->numOrientations) = hc4 ;
01049               break ;
01050           }
01051           oiter += hogStride ;
01052 
01053         } /* next orientation */
01054 
01055         switch (self->variant) {
01056           case VlHogVariantUoctti :
01057             oiter += 2 * hogStride * self->numOrientations ;
01058             *oiter = (1.0f/sqrtf(18.0f)) * t1 ; oiter += hogStride ;
01059             *oiter = (1.0f/sqrtf(18.0f)) * t2 ; oiter += hogStride ;
01060             *oiter = (1.0f/sqrtf(18.0f)) * t3 ; oiter += hogStride ;
01061             *oiter = (1.0f/sqrtf(18.0f)) * t4 ; oiter += hogStride ;
01062             break ;
01063 
01064           case VlHogVariantDalalTriggs :
01065             break ;
01066         }
01067         ++iter ;
01068       } /* next x */
01069     } /* next y */
01070   } /* block normalization */
01071 }
01072 


libvlfeat
Author(s): Andrea Vedaldi
autogenerated on Thu Jun 6 2019 20:25:51