kiss_fftr.c
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2003-2004, Mark Borgerding
00003 
00004 All rights reserved.
00005 
00006 Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
00007 
00008     * Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution.
00010     * Neither the author nor the names of any contributors may be used to endorse or promote products derived from this software without specific prior written permission.
00011 
00012 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00013 */
00014 
00015 #include "pcl/common/fft/kiss_fftr.h"
00016 #include "pcl/common/fft/_kiss_fft_guts.h"
00017 
00018 struct kiss_fftr_state{
00019     kiss_fft_cfg substate;
00020     kiss_fft_cpx * tmpbuf;
00021     kiss_fft_cpx * super_twiddles;
00022 #ifdef USE_SIMD    
00023     void * pad;
00024 #endif    
00025 };
00026 
00027 kiss_fftr_cfg kiss_fftr_alloc(int nfft,int inverse_fft,void * mem,size_t * lenmem)
00028 {
00029     int i;
00030     kiss_fftr_cfg st = NULL;
00031     size_t subsize, memneeded;
00032 
00033     if (nfft & 1) {
00034         fprintf(stderr,"Real FFT optimization must be even.\n");
00035         return NULL;
00036     }
00037     nfft >>= 1;
00038 
00039     kiss_fft_alloc (nfft, inverse_fft, NULL, &subsize);
00040     memneeded = sizeof(struct kiss_fftr_state) + subsize + sizeof(kiss_fft_cpx) * ( nfft * 3 / 2);
00041 
00042     if (lenmem == NULL) {
00043         st = (kiss_fftr_cfg) KISS_FFT_MALLOC (memneeded);
00044     } else {
00045         if (*lenmem >= memneeded)
00046             st = (kiss_fftr_cfg) mem;
00047         *lenmem = memneeded;
00048     }
00049     if (!st)
00050         return NULL;
00051 
00052     st->substate = (kiss_fft_cfg) (st + 1); /*just beyond kiss_fftr_state struct */
00053     st->tmpbuf = (kiss_fft_cpx *) (((char *) st->substate) + subsize);
00054     st->super_twiddles = st->tmpbuf + nfft;
00055     kiss_fft_alloc(nfft, inverse_fft, st->substate, &subsize);
00056 
00057     for (i = 0; i < nfft/2; ++i) {
00058         double phase =
00059             -3.14159265358979323846264338327 * ((double) (i+1) / nfft + .5);
00060         if (inverse_fft)
00061             phase *= -1;
00062         kf_cexp (st->super_twiddles+i,phase);
00063     }
00064     return st;
00065 }
00066 
00067 void kiss_fftr(kiss_fftr_cfg st,const kiss_fft_scalar *timedata,kiss_fft_cpx *freqdata)
00068 {
00069     /* input buffer timedata is stored row-wise */
00070     int k,ncfft;
00071     kiss_fft_cpx fpnk,fpk,f1k,f2k,tw,tdc;
00072 
00073     if ( st->substate->inverse) {
00074         fprintf(stderr,"kiss fft usage error: improper alloc\n");
00075         exit(1);
00076     }
00077 
00078     ncfft = st->substate->nfft;
00079 
00080     /*perform the parallel fft of two real signals packed in real,imag*/
00081     kiss_fft( st->substate , (const kiss_fft_cpx*)timedata, st->tmpbuf );
00082     /* The real part of the DC element of the frequency spectrum in st->tmpbuf
00083      * contains the sum of the even-numbered elements of the input time sequence
00084      * The imag part is the sum of the odd-numbered elements
00085      *
00086      * The sum of tdc.r and tdc.i is the sum of the input time sequence. 
00087      *      yielding DC of input time sequence
00088      * The difference of tdc.r - tdc.i is the sum of the input (dot product) [1,-1,1,-1... 
00089      *      yielding Nyquist bin of input time sequence
00090      */
00091  
00092     tdc.r = st->tmpbuf[0].r;
00093     tdc.i = st->tmpbuf[0].i;
00094     C_FIXDIV(tdc,2);
00095     CHECK_OVERFLOW_OP(tdc.r ,+, tdc.i);
00096     CHECK_OVERFLOW_OP(tdc.r ,-, tdc.i);
00097     freqdata[0].r = tdc.r + tdc.i;
00098     freqdata[ncfft].r = tdc.r - tdc.i;
00099 #ifdef USE_SIMD    
00100     freqdata[ncfft].i = freqdata[0].i = _mm_set1_ps(0);
00101 #else
00102     freqdata[ncfft].i = freqdata[0].i = 0;
00103 #endif
00104 
00105     for ( k=1;k <= ncfft/2 ; ++k ) {
00106         fpk    = st->tmpbuf[k]; 
00107         fpnk.r =   st->tmpbuf[ncfft-k].r;
00108         fpnk.i = - st->tmpbuf[ncfft-k].i;
00109         C_FIXDIV(fpk,2);
00110         C_FIXDIV(fpnk,2);
00111 
00112         C_ADD( f1k, fpk , fpnk );
00113         C_SUB( f2k, fpk , fpnk );
00114         C_MUL( tw , f2k , st->super_twiddles[k-1]);
00115 
00116         freqdata[k].r = HALF_OF(f1k.r + tw.r);
00117         freqdata[k].i = HALF_OF(f1k.i + tw.i);
00118         freqdata[ncfft-k].r = HALF_OF(f1k.r - tw.r);
00119         freqdata[ncfft-k].i = HALF_OF(tw.i - f1k.i);
00120     }
00121 }
00122 
00123 void kiss_fftri(kiss_fftr_cfg st,const kiss_fft_cpx *freqdata,kiss_fft_scalar *timedata)
00124 {
00125     /* input buffer timedata is stored row-wise */
00126     int k, ncfft;
00127 
00128     if (st->substate->inverse == 0) {
00129         fprintf (stderr, "kiss fft usage error: improper alloc\n");
00130         exit (1);
00131     }
00132 
00133     ncfft = st->substate->nfft;
00134 
00135     st->tmpbuf[0].r = freqdata[0].r + freqdata[ncfft].r;
00136     st->tmpbuf[0].i = freqdata[0].r - freqdata[ncfft].r;
00137     C_FIXDIV(st->tmpbuf[0],2);
00138 
00139     for (k = 1; k <= ncfft / 2; ++k) {
00140         kiss_fft_cpx fk, fnkc, fek, fok, tmp;
00141         fk = freqdata[k];
00142         fnkc.r = freqdata[ncfft - k].r;
00143         fnkc.i = -freqdata[ncfft - k].i;
00144         C_FIXDIV( fk , 2 );
00145         C_FIXDIV( fnkc , 2 );
00146 
00147         C_ADD (fek, fk, fnkc);
00148         C_SUB (tmp, fk, fnkc);
00149         C_MUL (fok, tmp, st->super_twiddles[k-1]);
00150         C_ADD (st->tmpbuf[k],     fek, fok);
00151         C_SUB (st->tmpbuf[ncfft - k], fek, fok);
00152 #ifdef USE_SIMD        
00153         st->tmpbuf[ncfft - k].i *= _mm_set1_ps(-1.0);
00154 #else
00155         st->tmpbuf[ncfft - k].i *= -1;
00156 #endif
00157     }
00158     kiss_fft (st->substate, st->tmpbuf, (kiss_fft_cpx *) timedata);
00159 }


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:25:07