libfreedv: use in FreeDV demod

This commit is contained in:
f4exb 2019-03-05 01:01:38 +01:00
parent 5178ef6a31
commit 3a24bdf1da
32 changed files with 10581 additions and 52 deletions

View File

@ -1,7 +1,16 @@
project(freedv)
set(freedv_SOURCES
codec2_fft.cpp
cohpsk.cpp
fdmdv.cpp
freedv_api.cpp
freedv_data_channel.cpp
freedv_filter.cpp
freedv_vhf_framing.cpp
fsk.cpp
kiss_fft.cpp
linreg.cpp
)
set(freedv_HEADERS
@ -9,24 +18,39 @@ set(freedv_HEADERS
codec2_fdmdv.h
codec2_fft.h
codec2_ofdm.h
cohpsk_defs.h
cohpsk_internal.h
defines.h
fdmdv_internal.h
fdv_arm_math.h
fmfsk.h
freedv_api_internal.h
freedv_data_channel.h
freedv_filter_coef.h
freedv_filter.h
freedv_vhf_framing.h
fsk.h
gp_interleaver.h
hanning.h
interldpc.h
_kiss_fft_guts.h
kiss_fft.h
kiss_fftr.h
libfreedv.h
linreg.h
machdep.h
modem_probe.h
modem_stats.h
mpdecode_core.h
ofdm_internal.h
os.h
pilot_coeff.h
pilots_coh.h
rn_coh.h
rn.h
rxdec_coeff.h
test_bits_coh.h
test_bits.h
)
include_directories(

159
libfreedv/_kiss_fft_guts.h Normal file
View File

@ -0,0 +1,159 @@
/*
Copyright (c) 2003-2010, Mark Borgerding
All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
* Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.
* 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.
* 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.
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.
*/
/* kiss_fft.h
defines kiss_fft_scalar as either short or a float type
and defines
typedef struct { kiss_fft_scalar r; kiss_fft_scalar i; }kiss_fft_cpx; */
#include "kiss_fft.h"
#include <limits.h>
#define MAXFACTORS 32
/* e.g. an fft of length 128 has 4 factors
as far as kissfft is concerned
4*4*4*2
*/
namespace FreeDV
{
struct kiss_fft_state{
int nfft;
int inverse;
int factors[2*MAXFACTORS];
kiss_fft_cpx twiddles[1];
};
/*
Explanation of macros dealing with complex math:
C_MUL(m,a,b) : m = a*b
C_FIXDIV( c , div ) : if a fixed point impl., c /= div. noop otherwise
C_SUB( res, a,b) : res = a - b
C_SUBFROM( res , a) : res -= a
C_ADDTO( res , a) : res += a
* */
#ifdef FIXED_POINT
#if (FIXED_POINT==32)
# define FRACBITS 31
# define SAMPPROD int64_t
#define SAMP_MAX 2147483647
#else
# define FRACBITS 15
# define SAMPPROD int32_t
#define SAMP_MAX 32767
#endif
#define SAMP_MIN -SAMP_MAX
#if defined(CHECK_OVERFLOW)
# define CHECK_OVERFLOW_OP(a,op,b) \
if ( (SAMPPROD)(a) op (SAMPPROD)(b) > SAMP_MAX || (SAMPPROD)(a) op (SAMPPROD)(b) < SAMP_MIN ) { \
fprintf(stderr,"WARNING:overflow @ " __FILE__ "(%d): (%d " #op" %d) = %ld\n",__LINE__,(a),(b),(SAMPPROD)(a) op (SAMPPROD)(b) ); }
#endif
# define smul(a,b) ( (SAMPPROD)(a)*(b) )
# define sround( x ) (kiss_fft_scalar)( ( (x) + (1<<(FRACBITS-1)) ) >> FRACBITS )
# define S_MUL(a,b) sround( smul(a,b) )
# define C_MUL(m,a,b) \
do{ (m).r = sround( smul((a).r,(b).r) - smul((a).i,(b).i) ); \
(m).i = sround( smul((a).r,(b).i) + smul((a).i,(b).r) ); }while(0)
# define DIVSCALAR(x,k) \
(x) = sround( smul( x, SAMP_MAX/k ) )
# define C_FIXDIV(c,div) \
do { DIVSCALAR( (c).r , div); \
DIVSCALAR( (c).i , div); }while (0)
# define C_MULBYSCALAR( c, s ) \
do{ (c).r = sround( smul( (c).r , s ) ) ;\
(c).i = sround( smul( (c).i , s ) ) ; }while(0)
#else /* not FIXED_POINT*/
# define S_MUL(a,b) ( (a)*(b) )
#define C_MUL(m,a,b) \
do{ (m).r = (a).r*(b).r - (a).i*(b).i;\
(m).i = (a).r*(b).i + (a).i*(b).r; }while(0)
# define C_FIXDIV(c,div) /* NOOP */
# define C_MULBYSCALAR( c, s ) \
do{ (c).r *= (s);\
(c).i *= (s); }while(0)
#endif
#ifndef CHECK_OVERFLOW_OP
# define CHECK_OVERFLOW_OP(a,op,b) /* noop */
#endif
#define C_ADD( res, a,b)\
do { \
CHECK_OVERFLOW_OP((a).r,+,(b).r)\
CHECK_OVERFLOW_OP((a).i,+,(b).i)\
(res).r=(a).r+(b).r; (res).i=(a).i+(b).i; \
}while(0)
#define C_SUB( res, a,b)\
do { \
CHECK_OVERFLOW_OP((a).r,-,(b).r)\
CHECK_OVERFLOW_OP((a).i,-,(b).i)\
(res).r=(a).r-(b).r; (res).i=(a).i-(b).i; \
}while(0)
#define C_ADDTO( res , a)\
do { \
CHECK_OVERFLOW_OP((res).r,+,(a).r)\
CHECK_OVERFLOW_OP((res).i,+,(a).i)\
(res).r += (a).r; (res).i += (a).i;\
}while(0)
#define C_SUBFROM( res , a)\
do {\
CHECK_OVERFLOW_OP((res).r,-,(a).r)\
CHECK_OVERFLOW_OP((res).i,-,(a).i)\
(res).r -= (a).r; (res).i -= (a).i; \
}while(0)
#ifdef FIXED_POINT
# define KISS_FFT_COS(phase) floorf(.5+SAMP_MAX * cosf (phase))
# define KISS_FFT_SIN(phase) floorf(.5+SAMP_MAX * sinf (phase))
# define HALF_OF(x) ((x)>>1)
#elif defined(USE_SIMD)
# define KISS_FFT_COS(phase) _mm_set1_ps( cosf(phase) )
# define KISS_FFT_SIN(phase) _mm_set1_ps( sinf(phase) )
# define HALF_OF(x) ((x)*_mm_set1_ps(.5))
#else
# define KISS_FFT_COS(phase) (kiss_fft_scalar) cosf(phase)
# define KISS_FFT_SIN(phase) (kiss_fft_scalar) sinf(phase)
# define HALF_OF(x) ((x)*.5)
#endif
#define kf_cexp(x,phase) \
do{ \
(x)->r = KISS_FFT_COS(phase);\
(x)->i = KISS_FFT_SIN(phase);\
}while(0)
/* a debugging function */
#define pcpx(c)\
fprintf(stderr,"%g + %gi\n",(double)((c)->r),(double)((c)->i) )
#define KISS_FFT_TMP_ALLOC(nbytes) KISS_FFT_MALLOC(nbytes)
#define KISS_FFT_TMP_FREE(ptr) KISS_FFT_FREE(ptr)
} // FreeDV

163
libfreedv/codec2_fft.cpp Normal file
View File

@ -0,0 +1,163 @@
/*
* codec2_fft.c
*
* Created on: 24.09.2016
* Author: danilo
*/
#include "codec2_fft.h"
#ifdef USE_KISS_FFT
#include "_kiss_fft_guts.h"
#endif
namespace FreeDV
{
#ifdef USE_KISS_FFT
#else
#if 0
// caching constants in RAM did not seem to have an effect on performance
// TODO: Decide what to with this code
#define FFT_INIT_CACHE_SIZE 4
const arm_cfft_instance_f32* fft_init_cache[FFT_INIT_CACHE_SIZE];
static const arm_cfft_instance_f32* arm_fft_instance2ram(const arm_cfft_instance_f32* in)
{
arm_cfft_instance_f32* out = malloc(sizeof(arm_cfft_instance_f32));
if (out) {
memcpy(out,in,sizeof(arm_cfft_instance_f32));
out->pBitRevTable = malloc(out->bitRevLength * sizeof(uint16_t));
out->pTwiddle = malloc(out->fftLen * sizeof(float32_t));
memcpy((void*)out->pBitRevTable,in->pBitRevTable,out->bitRevLength * sizeof(uint16_t));
memcpy((void*)out->pTwiddle,in->pTwiddle,out->fftLen * sizeof(float32_t));
}
return out;
}
static const arm_cfft_instance_f32* arm_fft_cache_get(const arm_cfft_instance_f32* romfft)
{
const arm_cfft_instance_f32* retval = NULL;
static int used = 0;
for (int i = 0; fft_init_cache[i] != NULL && i < used; i++)
{
if (romfft->fftLen == fft_init_cache[i]->fftLen)
{
retval = fft_init_cache[i];
break;
}
}
if (retval == NULL && used < FFT_INIT_CACHE_SIZE)
{
retval = arm_fft_instance2ram(romfft);
fft_init_cache[used++] = retval;
}
if (retval == NULL)
{
retval = romfft;
}
return retval;
}
#endif
#endif
void codec2_fft_free(codec2_fft_cfg cfg)
{
#ifdef USE_KISS_FFT
KISS_FFT_FREE(cfg);
#else
FREE(cfg);
#endif
}
codec2_fft_cfg codec2_fft_alloc(int nfft, int inverse_fft, void* mem, std::size_t* lenmem)
{
codec2_fft_cfg retval;
#ifdef USE_KISS_FFT
retval = kiss_fft_alloc(nfft, inverse_fft, mem, lenmem);
#else
retval = MALLOC(sizeof(codec2_fft_struct));
retval->inverse = inverse_fft;
switch(nfft)
{
case 128:
retval->instance = &arm_cfft_sR_f32_len128;
break;
case 256:
retval->instance = &arm_cfft_sR_f32_len256;
break;
case 512:
retval->instance = &arm_cfft_sR_f32_len512;
break;
// case 1024:
// retval->instance = &arm_cfft_sR_f32_len1024;
// break;
default:
abort();
}
// retval->instance = arm_fft_cache_get(retval->instance);
#endif
return retval;
}
codec2_fftr_cfg codec2_fftr_alloc(int nfft, int inverse_fft, void* mem, std::size_t* lenmem)
{
codec2_fftr_cfg retval;
#ifdef USE_KISS_FFT
retval = kiss_fftr_alloc(nfft, inverse_fft, mem, lenmem);
#else
retval = MALLOC(sizeof(codec2_fftr_struct));
retval->inverse = inverse_fft;
retval->instance = MALLOC(sizeof(arm_rfft_fast_instance_f32));
arm_rfft_fast_init_f32(retval->instance,nfft);
// memcpy(&retval->instance->Sint,arm_fft_cache_get(&retval->instance->Sint),sizeof(arm_cfft_instance_f32));
#endif
return retval;
}
void codec2_fftr_free(codec2_fftr_cfg cfg)
{
#ifdef USE_KISS_FFT
KISS_FFT_FREE(cfg);
#else
FREE(cfg->instance);
FREE(cfg);
#endif
}
// there is a little overhead for inplace kiss_fft but this is
// on the powerful platforms like the Raspberry or even x86 PC based ones
// not noticeable
// the reduced usage of RAM and increased performance on STM32 platforms
// should be worth it.
void codec2_fft_inplace(codec2_fft_cfg cfg, codec2_fft_cpx* inout)
{
#ifdef USE_KISS_FFT
kiss_fft_cpx in[512];
// decide whether to use the local stack based buffer for in
// or to allow kiss_fft to allocate RAM
// second part is just to play safe since first method
// is much faster and uses less RAM
if (cfg->nfft <= 512)
{
memcpy(in,inout,cfg->nfft*sizeof(kiss_fft_cpx));
kiss_fft(cfg, in, (kiss_fft_cpx*)inout);
}
else
{
kiss_fft(cfg, (kiss_fft_cpx*)inout, (kiss_fft_cpx*)inout);
}
#else
arm_cfft_f32(cfg->instance,(float*)inout,cfg->inverse,1);
if (cfg->inverse)
{
arm_scale_f32((float*)inout,cfg->instance->fftLen,(float*)inout,cfg->instance->fftLen*2);
}
#endif
}
} // FreeDV

View File

@ -14,8 +14,9 @@
#include <string.h>
#include <math.h>
namespace FreeDV
{
#include "codec2/comp.h"
#include "defines.h"
#include "kiss_fftr.h"
#ifdef FDV_ARM_MATH
#include "fdv_arm_math.h"
@ -23,15 +24,16 @@ namespace FreeDV
#define USE_KISS_FFT
#endif
#include "defines.h"
#include "codec2/comp.h"
typedef COMP codec2_fft_cpx;
#include "kiss_fftr.h"
#ifdef USE_KISS_FFT
#include "kiss_fft.h"
#endif
namespace FreeDV
{
typedef COMP codec2_fft_cpx;
#ifdef USE_KISS_FFT
typedef kiss_fftr_cfg codec2_fftr_cfg;
typedef kiss_fft_cfg codec2_fft_cfg;
typedef kiss_fft_scalar codec2_fft_scalar;
@ -51,11 +53,8 @@ typedef COMP codec2_fft_cpx;
typedef codec2_fft_struct* codec2_fft_cfg;
#endif
static inline void codec2_fftr(codec2_fftr_cfg cfg, codec2_fft_scalar* in, codec2_fft_cpx* out)
{
#ifdef USE_KISS_FFT
kiss_fftr(cfg, in, (kiss_fft_cpx*)out);
#else
@ -75,8 +74,8 @@ static inline void codec2_fftri(codec2_fftr_cfg cfg, codec2_fft_cpx* in, codec2_
}
codec2_fft_cfg codec2_fft_alloc(int nfft, int inverse_fft, void* mem, size_t* lenmem);
codec2_fftr_cfg codec2_fftr_alloc(int nfft, int inverse_fft, void* mem, size_t* lenmem);
codec2_fft_cfg codec2_fft_alloc(int nfft, int inverse_fft, void* mem, std::size_t* lenmem);
codec2_fftr_cfg codec2_fftr_alloc(int nfft, int inverse_fft, void* mem, std::size_t* lenmem);
void codec2_fft_free(codec2_fft_cfg cfg);
void codec2_fftr_free(codec2_fftr_cfg cfg);

1394
libfreedv/cohpsk.cpp Normal file

File diff suppressed because it is too large Load Diff

9
libfreedv/cohpsk_defs.h Normal file
View File

@ -0,0 +1,9 @@
/* Generated by write_pilot_file() Octave function */
#define NSYMROW 4 /* number of data symbols per carrier (number of rows) */
#define NS 4 /* number of data symbols between pilots */
#define NPILOTSFRAME 2 /* number of pilot symbols per carrier */
#define PILOTS_NC 7 /* number of carriers */
#define NSYMROWPILOT 6 /* number of rows after pilots inserted */

131
libfreedv/cohpsk_internal.h Normal file
View File

@ -0,0 +1,131 @@
/*---------------------------------------------------------------------------*\
FILE........: cohpsk_internal.h
AUTHOR......: David Rowe
DATE CREATED: March 2015
Functions that implement a coherent PSK FDM modem.
\*---------------------------------------------------------------------------*/
/*
Copyright (C) 2015 David Rowe
All rights reserved.
This program is free software; you can redistribute it and/or modify
it under the terms of the GNU Lesser General Public License version 2.1, as
published by the Free Software Foundation. This program is
distributed in the hope that it will be useful, but WITHOUT ANY
WARRANTY; without even the implied warranty of MERCHANTABILITY or
FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public
License for more details.
You should have received a copy of the GNU Lesser General Public License
along with this program; if not, see <http://www.gnu.org/licenses/>.
*/
#ifndef __COHPSK_INTERNAL__
#define __COHPSK_INTERNAL__
#define NCT_SYMB_BUF (2*NSYMROWPILOT+2)
#define ND 2 /* diversity factor ND 1 is no diveristy, ND we have orginal plus
one copy */
#define NSW 4 /* number of sync window frames */
#define COHPSK_ND 2 /* diversity factor */
#define COHPSK_M 100 /* oversampling rate */
#define COHPSK_NSYM 6
#define COHPSK_NFILTER (COHPSK_NSYM*COHPSK_M)
#define COHPSK_EXCESS_BW 0.5 /* excess BW factor of root nyq filter */
#define COHPSK_NT 5 /* number of symbols we estimate timing over */
#include "fdmdv_internal.h"
#include "kiss_fft.h"
namespace FreeDV
{
struct COHPSK {
COMP ch_fdm_frame_buf[NSW*NSYMROWPILOT*COHPSK_M]; /* buffer of several frames of symbols from channel */
float pilot2[2*NPILOTSFRAME][COHPSK_NC];
float phi_[NSYMROWPILOT][COHPSK_NC*ND]; /* phase estimates for this frame of rx data symbols */
float amp_[NSYMROW][COHPSK_NC*ND]; /* amplitude estimates for this frame of rx data symbols */
COMP rx_symb[NSYMROWPILOT][COHPSK_NC*ND]; /* demodulated symbols */
float f_est;
COMP rx_filter_memory[COHPSK_NC*ND][COHPSK_NFILTER];
COMP ct_symb_buf[NCT_SYMB_BUF][COHPSK_NC*ND];
int ct; /* coarse timing offset in symbols */
float rx_timing; /* fine timing for last symbol in frame */
int nin; /* number of samples to input for next symbol */
float f_fine_est;
COMP ff_rect;
COMP ff_phase;
COMP ct_symb_ff_buf[NSYMROWPILOT+2][COHPSK_NC*ND];
int sync;
int sync_timer;
int frame;
float ratio;
float sig_rms;
float noise_rms;
struct FDMDV *fdmdv;
int verbose;
int *ptest_bits_coh_tx;
int *ptest_bits_coh_rx[2];
int *ptest_bits_coh_end;
/* counting bit errors using pilots */
int npilotbits;
int npilotbiterrors;
/* optional log variables used for testing Octave to C port */
COMP *rx_baseband_log;
int rx_baseband_log_col_index;
int rx_baseband_log_col_sz;
COMP *rx_filt_log;
int rx_filt_log_col_index;
int rx_filt_log_col_sz;
COMP *ch_symb_log;
int ch_symb_log_r;
int ch_symb_log_col_sz;
float *rx_timing_log;
int rx_timing_log_index;
/* demodulated bits before diversity combination for test/instrumentation purposes */
float rx_bits_lower[COHPSK_BITS_PER_FRAME];
float rx_bits_upper[COHPSK_BITS_PER_FRAME];
/* tx amplitude weights for each carrier for test/instrumentation */
float carrier_ampl[COHPSK_NC*ND];
/* Flag enabling simple freq est mode */
int freq_est_mode_reduced;
};
void bits_to_qpsk_symbols(COMP tx_symb[][COHPSK_NC*COHPSK_ND], int tx_bits[], int nbits);
void qpsk_symbols_to_bits(struct COHPSK *coh, float rx_bits[], COMP ct_symb_buf[][COHPSK_NC*COHPSK_ND]);
void tx_filter_and_upconvert_coh(COMP tx_fdm[], int Nc, const COMP tx_symbols[],
COMP tx_filter_memory[COHPSK_NC][COHPSK_NSYM],
COMP phase_tx[], COMP freq[],
COMP *fbb_phase, COMP fbb_rect);
void fdm_downconvert_coh(COMP rx_baseband[COHPSK_NC][COHPSK_M+COHPSK_M/P], int Nc, COMP rx_fdm[], COMP phase_rx[], COMP freq[], int nin);
void rx_filter_coh(COMP rx_filt[COHPSK_NC+1][P+1], int Nc, COMP rx_baseband[COHPSK_NC+1][COHPSK_M+COHPSK_M/P], COMP rx_filter_memory[COHPSK_NC+1][COHPSK_NFILTER], int nin);
void frame_sync_fine_freq_est(struct COHPSK *coh, COMP ch_symb[][COHPSK_NC*COHPSK_ND], int sync, int *next_sync);
void fine_freq_correct(struct COHPSK *coh, int sync, int next_sync);
int sync_state_machine(struct COHPSK *coh, int sync, int next_sync);
int cohpsk_fs_offset(COMP out[], COMP in[], int n, float sample_rate_ppm);
} // FreeDV
#endif

1995
libfreedv/fdmdv.cpp Normal file

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,320 @@
/*---------------------------------------------------------------------------*\
FILE........: freedv_data_channel.c
AUTHOR......: Jeroen Vreeken
DATE CREATED: 03 March 2016
Data channel for ethernet like packets in freedv VHF frames.
Currently designed for-
* 2 control bits per frame
* 4 byte counter bits per frame
* 64 bits of data per frame
\*---------------------------------------------------------------------------*/
/*
Copyright (C) 2016 Jeroen Vreeken
All rights reserved.
This program is free software; you can redistribute it and/or modify
it under the terms of the GNU Lesser General Public License version 2.1, as
published by the Free Software Foundation. This program is
distributed in the hope that it will be useful, but WITHOUT ANY
WARRANTY; without even the implied warranty of MERCHANTABILITY or
FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public
License for more details.
You should have received a copy of the GNU Lesser General Public License
along with this program; if not, see <http://www.gnu.org/licenses/>.
*/
#include "freedv_data_channel.h"
#include <stdlib.h>
#include <string.h>
#include <cstddef>
namespace FreeDV
{
static unsigned char fdc_header_bcast[6] = { 0xff, 0xff, 0xff, 0xff, 0xff, 0xff };
/* CCIT CRC table (0x1201 polynomal) */
static unsigned short fdc_crc_table[256] = {
0x0000, 0x1189, 0x2312, 0x329b, 0x4624, 0x57ad, 0x6536, 0x74bf,
0x8c48, 0x9dc1, 0xaf5a, 0xbed3, 0xca6c, 0xdbe5, 0xe97e, 0xf8f7,
0x1081, 0x0108, 0x3393, 0x221a, 0x56a5, 0x472c, 0x75b7, 0x643e,
0x9cc9, 0x8d40, 0xbfdb, 0xae52, 0xdaed, 0xcb64, 0xf9ff, 0xe876,
0x2102, 0x308b, 0x0210, 0x1399, 0x6726, 0x76af, 0x4434, 0x55bd,
0xad4a, 0xbcc3, 0x8e58, 0x9fd1, 0xeb6e, 0xfae7, 0xc87c, 0xd9f5,
0x3183, 0x200a, 0x1291, 0x0318, 0x77a7, 0x662e, 0x54b5, 0x453c,
0xbdcb, 0xac42, 0x9ed9, 0x8f50, 0xfbef, 0xea66, 0xd8fd, 0xc974,
0x4204, 0x538d, 0x6116, 0x709f, 0x0420, 0x15a9, 0x2732, 0x36bb,
0xce4c, 0xdfc5, 0xed5e, 0xfcd7, 0x8868, 0x99e1, 0xab7a, 0xbaf3,
0x5285, 0x430c, 0x7197, 0x601e, 0x14a1, 0x0528, 0x37b3, 0x263a,
0xdecd, 0xcf44, 0xfddf, 0xec56, 0x98e9, 0x8960, 0xbbfb, 0xaa72,
0x6306, 0x728f, 0x4014, 0x519d, 0x2522, 0x34ab, 0x0630, 0x17b9,
0xef4e, 0xfec7, 0xcc5c, 0xddd5, 0xa96a, 0xb8e3, 0x8a78, 0x9bf1,
0x7387, 0x620e, 0x5095, 0x411c, 0x35a3, 0x242a, 0x16b1, 0x0738,
0xffcf, 0xee46, 0xdcdd, 0xcd54, 0xb9eb, 0xa862, 0x9af9, 0x8b70,
0x8408, 0x9581, 0xa71a, 0xb693, 0xc22c, 0xd3a5, 0xe13e, 0xf0b7,
0x0840, 0x19c9, 0x2b52, 0x3adb, 0x4e64, 0x5fed, 0x6d76, 0x7cff,
0x9489, 0x8500, 0xb79b, 0xa612, 0xd2ad, 0xc324, 0xf1bf, 0xe036,
0x18c1, 0x0948, 0x3bd3, 0x2a5a, 0x5ee5, 0x4f6c, 0x7df7, 0x6c7e,
0xa50a, 0xb483, 0x8618, 0x9791, 0xe32e, 0xf2a7, 0xc03c, 0xd1b5,
0x2942, 0x38cb, 0x0a50, 0x1bd9, 0x6f66, 0x7eef, 0x4c74, 0x5dfd,
0xb58b, 0xa402, 0x9699, 0x8710, 0xf3af, 0xe226, 0xd0bd, 0xc134,
0x39c3, 0x284a, 0x1ad1, 0x0b58, 0x7fe7, 0x6e6e, 0x5cf5, 0x4d7c,
0xc60c, 0xd785, 0xe51e, 0xf497, 0x8028, 0x91a1, 0xa33a, 0xb2b3,
0x4a44, 0x5bcd, 0x6956, 0x78df, 0x0c60, 0x1de9, 0x2f72, 0x3efb,
0xd68d, 0xc704, 0xf59f, 0xe416, 0x90a9, 0x8120, 0xb3bb, 0xa232,
0x5ac5, 0x4b4c, 0x79d7, 0x685e, 0x1ce1, 0x0d68, 0x3ff3, 0x2e7a,
0xe70e, 0xf687, 0xc41c, 0xd595, 0xa12a, 0xb0a3, 0x8238, 0x93b1,
0x6b46, 0x7acf, 0x4854, 0x59dd, 0x2d62, 0x3ceb, 0x0e70, 0x1ff9,
0xf78f, 0xe606, 0xd49d, 0xc514, 0xb1ab, 0xa022, 0x92b9, 0x8330,
0x7bc7, 0x6a4e, 0x58d5, 0x495c, 0x3de3, 0x2c6a, 0x1ef1, 0x0f78
};
static unsigned short fdc_crc(unsigned char *buffer, std::size_t len)
{
unsigned short crc = 0xffff;
std::size_t i;
for (i = 0; i < len; i++, buffer++) {
crc = (crc >> 8) ^ fdc_crc_table[(crc ^ *buffer) & 0xff];
}
return crc ^ 0xffff;
}
/* CRC4 0x03 polynomal */
static unsigned char fdc_crc4(unsigned char *buffer, std::size_t len)
{
unsigned char crc = 0x0f;
std::size_t i;
for (i = 0; i < len; i++, buffer++) {
int shift;
for (shift = 7; shift <= 0; shift--) {
crc <<= 1;
if ((*buffer >> shift) & 0x1)
crc |= 1;
if (crc & 0x10)
crc ^= 0x03;
}
}
return crc & 0x0f;
}
struct freedv_data_channel *freedv_data_channel_create(void)
{
struct freedv_data_channel *fdc;
fdc = (freedv_data_channel*) malloc(sizeof(struct freedv_data_channel));
if (!fdc)
return nullptr;
fdc->cb_rx = nullptr;
fdc->cb_tx = nullptr;
fdc->packet_tx_size = 0;
freedv_data_set_header(fdc, fdc_header_bcast);
memcpy(fdc->rx_header, fdc->tx_header, 8);
return fdc;
}
void freedv_data_channel_destroy(struct freedv_data_channel *fdc)
{
free(fdc);
}
void freedv_data_set_cb_rx(struct freedv_data_channel *fdc, freedv_data_callback_rx cb, void *state)
{
fdc->cb_rx = cb;
fdc->cb_rx_state = state;
}
void freedv_data_set_cb_tx(struct freedv_data_channel *fdc, freedv_data_callback_tx cb, void *state)
{
fdc->cb_tx = cb;
fdc->cb_tx_state = state;
}
void freedv_data_channel_rx_frame(struct freedv_data_channel *fdc, unsigned char *data, std::size_t size, int from_bit, int bcast_bit, int crc_bit, int end_bits)
{
int copy_bits;
if (end_bits) {
copy_bits = end_bits;
} else {
copy_bits = size;
}
/* New packet? */
if (fdc->packet_rx_cnt == 0) {
/* Does the packet have a compressed from field? */
if (from_bit) {
/* Compressed from: take the previously received header */
memcpy(fdc->packet_rx + fdc->packet_rx_cnt, fdc->rx_header, 6);
fdc->packet_rx_cnt += 6;
}
if (bcast_bit) {
if (!from_bit) {
/* Copy from header and modify size and end_bits accordingly */
memcpy(fdc->packet_rx + fdc->packet_rx_cnt, data, 6);
fdc->packet_rx_cnt += 6;
copy_bits -= 6;
if (copy_bits < 0)
copy_bits = 0;
data += 6;
}
/* Compressed to: fill in broadcast address */
memcpy(fdc->packet_rx + fdc->packet_rx_cnt, fdc_header_bcast, sizeof(fdc_header_bcast));
fdc->packet_rx_cnt += 6;
}
if (crc_bit) {
unsigned char calc_crc = fdc_crc4(data, size);
if (calc_crc == end_bits) {
/* It is a single header field, remember it for later */
memcpy(fdc->packet_rx + 6, data, 6);
memcpy(fdc->packet_rx, fdc_header_bcast, 6);
if (fdc->cb_rx) {
fdc->cb_rx(fdc->cb_rx_state, fdc->packet_rx, 12);
}
}
fdc->packet_rx_cnt = 0;
return;
}
}
if (fdc->packet_rx_cnt + copy_bits >= FREEDV_DATA_CHANNEL_PACKET_MAX) {
/* Something went wrong... this can not be a real packet */
fdc->packet_rx_cnt = 0;
return;
}
memcpy(fdc->packet_rx + fdc->packet_rx_cnt, data, copy_bits);
fdc->packet_rx_cnt += copy_bits;
if (end_bits != 0 && fdc->packet_rx_cnt >= 2) {
unsigned short calc_crc = fdc_crc(fdc->packet_rx, fdc->packet_rx_cnt - 2);
unsigned short rx_crc;
rx_crc = fdc->packet_rx[fdc->packet_rx_cnt - 1] << 8;
rx_crc |= fdc->packet_rx[fdc->packet_rx_cnt - 2];
if (rx_crc == calc_crc) {
if ((std::size_t) fdc->packet_rx_cnt == size) {
/* It is a single header field, remember it for later */
memcpy(fdc->rx_header, fdc->packet_rx, 6);
}
/* callback */
if (fdc->cb_rx) {
unsigned char tmp[6];
memcpy(tmp, fdc->packet_rx, 6);
memcpy(fdc->packet_rx, fdc->packet_rx + 6, 6);
memcpy(fdc->packet_rx + 6, tmp, 6);
std::size_t size = fdc->packet_rx_cnt - 2;
if (size < 12)
size = 12;
fdc->cb_rx(fdc->cb_rx_state, fdc->packet_rx, size);
}
}
fdc->packet_rx_cnt = 0;
}
}
void freedv_data_channel_tx_frame(struct freedv_data_channel *fdc, unsigned char *data, std::size_t size, int *from_bit, int *bcast_bit, int *crc_bit, int *end_bits)
{
*from_bit = 0;
*bcast_bit = 0;
*crc_bit = 0;
if (!fdc->packet_tx_size) {
fdc->packet_tx_cnt = 0;
if (fdc->cb_tx) {
fdc->packet_tx_size = FREEDV_DATA_CHANNEL_PACKET_MAX;
fdc->cb_tx(fdc->cb_tx_state, fdc->packet_tx, &fdc->packet_tx_size);
}
if (!fdc->packet_tx_size) {
/* Nothing to send, insert a header frame */
memcpy(fdc->packet_tx, fdc->tx_header, size);
if (size < 8) {
*end_bits = fdc_crc4(fdc->tx_header, size);
*crc_bit = 1;
memcpy(data, fdc->tx_header, size);
return;
} else {
fdc->packet_tx_size = size;
}
} else {
/* new packet */
unsigned short crc;
unsigned char tmp[6];
*from_bit = !memcmp(fdc->packet_tx + 6, fdc->tx_header, 6);
*bcast_bit = !memcmp(fdc->packet_tx, fdc_header_bcast, 6);
memcpy(tmp, fdc->packet_tx, 6);
memcpy(fdc->packet_tx, fdc->packet_tx + 6, 6);
memcpy(fdc->packet_tx + 6, tmp, 6);
crc = fdc_crc(fdc->packet_tx, fdc->packet_tx_size);
fdc->packet_tx[fdc->packet_tx_size] = crc & 0xff;
fdc->packet_tx_size++;
fdc->packet_tx[fdc->packet_tx_size] = (crc >> 8) & 0xff;
fdc->packet_tx_size++;
if (*from_bit) {
fdc->packet_tx_cnt = 6;
} else {
if (*bcast_bit) {
memcpy(fdc->packet_tx + 6, fdc->packet_tx, 6);
}
}
if (*bcast_bit) {
fdc->packet_tx_cnt += 6;
}
}
}
if (fdc->packet_tx_size) {
std::size_t copy = fdc->packet_tx_size - fdc->packet_tx_cnt;
if (copy > size) {
copy = size;
*end_bits = 0;
} else {
*end_bits = copy;
fdc->packet_tx_size = 0;
}
memcpy(data, fdc->packet_tx + fdc->packet_tx_cnt, copy);
fdc->packet_tx_cnt += copy;
}
}
void freedv_data_set_header(struct freedv_data_channel *fdc, unsigned char *header)
{
unsigned short crc = fdc_crc(header, 6);
memcpy(fdc->tx_header, header, 6);
fdc->tx_header[6] = crc & 0xff;
fdc->tx_header[7] = (crc >> 8) & 0xff;
}
int freedv_data_get_n_tx_frames(struct freedv_data_channel *fdc, std::size_t size)
{
if (fdc->packet_tx_size == 0)
return 0;
/* packet will be send in 'size' byte frames */
return (fdc->packet_tx_size - fdc->packet_tx_cnt + size-1) / size;
}
} // FreeDV

286
libfreedv/freedv_filter.cpp Normal file
View File

@ -0,0 +1,286 @@
/*
Copyright (C) 2018 James C. Ahlstrom
All rights reserved.
This program is free software; you can redistribute it and/or modify
it under the terms of the GNU Lesser General Public License version 2.1, as
published by the Free Software Foundation. This program is
distributed in the hope that it will be useful, but WITHOUT ANY
WARRANTY; without even the implied warranty of MERCHANTABILITY or
FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public
License for more details.
You should have received a copy of the GNU Lesser General Public License
along with this program; if not, see <http://www.gnu.org/licenses/>.
*/
#include <stdlib.h>
#include <string.h>
#include <math.h>
#include <complex.h>
#include "freedv_filter.h"
#include "freedv_filter_coef.h"
#include "fdv_arm_math.h"
#define cmplx(value) (COSF(value) + SINF(value) * I)
namespace FreeDV
{
/*
* This is a library of filter functions. They were copied from Quisk and converted to single precision.
*/
/*---------------------------------------------------------------------------*\
FUNCTIONS...: quisk_filt_cfInit
AUTHOR......: Jim Ahlstrom
DATE CREATED: 27 August 2015
MODIFIED: 4 June 2018
Initialize a FIR filter that has complex samples, and either real or complex coefficients.
\*---------------------------------------------------------------------------*/
void quisk_filt_cfInit(struct quisk_cfFilter * filter, float * coefs, int taps) {
// Prepare a new filter using coefs and taps. Samples are complex. Coefficients can
// be real or complex.
filter->dCoefs = coefs;
filter->cpxCoefs = NULL;
filter->cSamples = (std::complex<float> *) malloc(taps * sizeof(std::complex<float>));
memset(filter->cSamples, 0, taps * sizeof(std::complex<float>));
filter->ptcSamp = filter->cSamples;
filter->nTaps = taps;
filter->cBuf = NULL;
filter->nBuf = 0;
filter->decim_index = 0;
}
/*---------------------------------------------------------------------------*\
FUNCTIONS...: quisk_filt_destroy
AUTHOR......: Jim Ahlstrom
DATE CREATED: 27 August 2015
MODIFIED: 4 June 2018
Destroy the FIR filter and free all resources.
\*---------------------------------------------------------------------------*/
void quisk_filt_destroy(struct quisk_cfFilter * filter) {
if (filter->cSamples) {
free(filter->cSamples);
filter->cSamples = NULL;
}
if (filter->cBuf) {
free(filter->cBuf);
filter->cBuf = NULL;
}
if (filter->cpxCoefs) {
free(filter->cpxCoefs);
filter->cpxCoefs = NULL;
}
}
/*---------------------------------------------------------------------------*\
FUNCTIONS...: quisk_cfInterpDecim
AUTHOR......: Jim Ahlstrom
DATE CREATED: 27 August 2015
MODIFIED: 4 June 2018
Take an array of samples cSamples of length count, multiply the sample rate
by interp, and then divide the sample rate by decim. Return the new number
of samples. Each specific interp and decim will require its own custom
low pass FIR filter with real coefficients.
\*---------------------------------------------------------------------------*/
int quisk_cfInterpDecim(std::complex<float> * cSamples, int count, struct quisk_cfFilter * filter, int interp, int decim) {
// Interpolate by interp, and then decimate by decim.
// This uses the float coefficients of filter (not the complex). Samples are complex.
int i, k, nOut;
float * ptCoef;
std::complex<float> *ptSample;
std::complex<float> csample;
if (count > filter->nBuf) { // increase size of sample buffer
filter->nBuf = count * 2;
if (filter->cBuf)
free(filter->cBuf);
filter->cBuf = (std::complex<float> *) malloc(filter->nBuf * sizeof(std::complex<float>));
}
memcpy(filter->cBuf, cSamples, count * sizeof(std::complex<float>));
nOut = 0;
for (i = 0; i < count; i++) {
// Put samples into buffer left to right. Use samples right to left.
*filter->ptcSamp = filter->cBuf[i];
while (filter->decim_index < interp) {
ptSample = filter->ptcSamp;
ptCoef = filter->dCoefs + filter->decim_index;
csample = 0;
for (k = 0; k < filter->nTaps / interp; k++, ptCoef += interp) {
csample += *ptSample * *ptCoef;
if (--ptSample < filter->cSamples)
ptSample = filter->cSamples + filter->nTaps - 1;
}
cSamples[nOut] = csample * (float) interp;
nOut++;
filter->decim_index += decim;
}
if (++filter->ptcSamp >= filter->cSamples + filter->nTaps)
filter->ptcSamp = filter->cSamples;
filter->decim_index = filter->decim_index - interp;
}
return nOut;
}
/*---------------------------------------------------------------------------*\
FUNCTIONS...: quisk_ccfInterpDecim
AUTHOR......: Jim Ahlstrom
DATE CREATED: 7 June 2018
Take an array of samples cSamples of length count, multiply the sample rate
by interp, and then divide the sample rate by decim. Return the new number
of samples. Each specific interp and decim will require its own custom
low pass FIR filter with complex coefficients. This filter can be tuned.
This filter is not currently used.
\*---------------------------------------------------------------------------*/
#if 0
int quisk_ccfInterpDecim(complex float * cSamples, int count, struct quisk_cfFilter * filter, int interp, int decim) {
// Interpolate by interp, and then decimate by decim.
// This uses the complex coefficients of filter (not the real). Samples are complex.
int i, k, nOut;
complex float * ptCoef;
complex float * ptSample;
complex float csample;
if (count > filter->nBuf) { // increase size of sample buffer
filter->nBuf = count * 2;
if (filter->cBuf)
FREE(filter->cBuf);
filter->cBuf = (complex float *)MALLOC(filter->nBuf * sizeof(complex float));
}
memcpy(filter->cBuf, cSamples, count * sizeof(complex float));
nOut = 0;
for (i = 0; i < count; i++) {
// Put samples into buffer left to right. Use samples right to left.
*filter->ptcSamp = filter->cBuf[i];
while (filter->decim_index < interp) {
ptSample = filter->ptcSamp;
ptCoef = filter->cpxCoefs + filter->decim_index;
csample = 0;
for (k = 0; k < filter->nTaps / interp; k++, ptCoef += interp) {
csample += *ptSample * *ptCoef;
if (--ptSample < filter->cSamples)
ptSample = filter->cSamples + filter->nTaps - 1;
}
cSamples[nOut] = csample * interp;
nOut++;
filter->decim_index += decim;
}
if (++filter->ptcSamp >= filter->cSamples + filter->nTaps)
filter->ptcSamp = filter->cSamples;
filter->decim_index = filter->decim_index - interp;
}
return nOut;
}
#endif
/*---------------------------------------------------------------------------*\
FUNCTIONS...: quisk_cfTune
AUTHOR......: Jim Ahlstrom
DATE CREATED: 4 June 2018
Tune a low pass filter with float coefficients into an analytic I/Q bandpass filter
with complex coefficients. The "freq" is the center frequency / sample rate.
If the float coefs represent a low pass filter with bandwidth 1 kHz, the new bandpass
filter has width 2 kHz. The filter can be re-tuned repeatedly.
\*---------------------------------------------------------------------------*/
void quisk_cfTune(struct quisk_cfFilter * filter, float freq) {
float D, tune;
int i;
if ( ! filter->cpxCoefs)
filter->cpxCoefs = (std::complex<float> *) malloc(filter->nTaps * sizeof(std::complex<float>));
tune = 2.0 * M_PI * freq;
D = (filter->nTaps - 1.0) / 2.0;
for (i = 0; i < filter->nTaps; i++) {
float tval = tune * (i - D);
filter->cpxCoefs[i] = cmplx(tval) * filter->dCoefs[i];
}
}
/*---------------------------------------------------------------------------*\
FUNCTIONS...: quisk_ccfFilter
AUTHOR......: Jim Ahlstrom
DATE CREATED: 4 June 2018
Filter complex samples using complex coefficients. The inSamples and outSamples may be
the same array. The loop runs forward over coefficients but backwards over samples.
Therefore, the coefficients must be reversed unless they are created by quisk_cfTune.
Low pass filter coefficients are symmetrical, so this does not usually matter.
\*---------------------------------------------------------------------------*/
void quisk_ccfFilter(std::complex<float> *inSamples, std::complex<float> *outSamples, int count, struct quisk_cfFilter * filter) {
int i, k;
std::complex<float> *ptSample;
std::complex<float> *ptCoef;
std::complex<float> accum;
for (i = 0; i < count; i++) {
*filter->ptcSamp = inSamples[i];
accum = 0;
ptSample = filter->ptcSamp;
ptCoef = filter->cpxCoefs;
for (k = 0; k < filter->nTaps; k++, ptCoef++) {
accum += *ptSample * *ptCoef;
if (--ptSample < filter->cSamples)
ptSample = filter->cSamples + filter->nTaps - 1;
}
outSamples[i] = accum;
if (++filter->ptcSamp >= filter->cSamples + filter->nTaps)
filter->ptcSamp = filter->cSamples;
}
}
} // freeDV

View File

@ -0,0 +1,166 @@
/*
Copyright (C) 2018 James C. Ahlstrom
All rights reserved.
This program is free software; you can redistribute it and/or modify
it under the terms of the GNU Lesser General Public License version 2.1, as
published by the Free Software Foundation. This program is
distributed in the hope that it will be useful, but WITHOUT ANY
WARRANTY; without even the implied warranty of MERCHANTABILITY or
FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public
License for more details.
You should have received a copy of the GNU Lesser General Public License
along with this program; if not, see <http://www.gnu.org/licenses/>.
*/
/*
These are the coefficients for various FIR filters. A declaration of these filter coefficients is in filter.h.
Multiple filters can use these coefficients because they are read-only.
Although a sample rate is specified, the filters may be used at other sample rates. For example, if
filtP750S1040 is used at 48000 sps, the pass and stop frequencies are 4500 and 6240 hz.
*/
namespace FreeDV
{
// Low pass filter, sample rate 8000 hz, 0.2 dB ripple, 100 dB atten, pass 550 hz, stop 750 hz.
float filtP550S750[160]={
0.000001500540125945, 0.000020553368071006, 0.000052842049763802, 0.000112071233638701,
0.000202565299657164, 0.000325476960438197, 0.000474396686568771, 0.000633746562372497, 0.000778858561033731,
0.000878592697224500, 0.000900611877226272, 0.000818750000130019, 0.000621157718914443, 0.000317269738067462,
-0.000058614729046822, -0.000448959090901751, -0.000780751290682747, -0.000978953969922609, -0.000983534965413392,
-0.000766540799920385, -0.000344938705664714, 0.000214927788687815, 0.000804118320944653, 0.001289527679116282,
0.001541598437149897, 0.001466078039230554, 0.001032493743140772, 0.000291727467744814, -0.000623607913580581,
-0.001518948630011706, -0.002175907515711935, -0.002402252989524116, -0.002082876981631170, -0.001219318501019004,
0.000053915753894017, 0.001483599323867600, 0.002743518309691092, 0.003504691193108974, 0.003515993126242027,
0.002676486805582815, 0.001080325423865147, -0.000980649349095093, -0.003062866925046052, -0.004660487490214220,
-0.005321805637618908, -0.004767235761853469, -0.002979877569160189, -0.000242864453416682, 0.002892365745006815,
0.005707645107750651, 0.007473145256589892, 0.007624527169837005, 0.005921569713871673, 0.002547381438730890,
-0.001883079571618079, -0.006418195698900790, -0.009958090016198632, -0.011502199858687428, -0.010403943660694560,
-0.006572745274759415, -0.000569370325758693, 0.006440667006225166, 0.012881777376768124, 0.017083918451421990,
0.017661533458054445, 0.013877952730549446, 0.005912685575826365, -0.005037640104142052, -0.016864250576905999,
-0.026855876467499887, -0.032168177048912679, -0.030370760878632559, -0.019967289813872333, -0.000782327027950076,
0.025871098651626040, 0.057290144048617792, 0.089743290905422241, 0.119038289777397190, 0.141198609990722840,
0.153125933205703250, 0.153125933205703250, 0.141198609990722840, 0.119038289777397190, 0.089743290905422241,
0.057290144048617792, 0.025871098651626040, -0.000782327027950076, -0.019967289813872333, -0.030370760878632559,
-0.032168177048912679, -0.026855876467499887, -0.016864250576905999, -0.005037640104142052, 0.005912685575826365,
0.013877952730549446, 0.017661533458054445, 0.017083918451421990, 0.012881777376768124, 0.006440667006225166,
-0.000569370325758693, -0.006572745274759415, -0.010403943660694560, -0.011502199858687428, -0.009958090016198632,
-0.006418195698900790, -0.001883079571618079, 0.002547381438730890, 0.005921569713871673, 0.007624527169837005,
0.007473145256589892, 0.005707645107750651, 0.002892365745006815, -0.000242864453416682, -0.002979877569160189,
-0.004767235761853469, -0.005321805637618908, -0.004660487490214220, -0.003062866925046052, -0.000980649349095093,
0.001080325423865147, 0.002676486805582815, 0.003515993126242027, 0.003504691193108974, 0.002743518309691092,
0.001483599323867600, 0.000053915753894017, -0.001219318501019004, -0.002082876981631170, -0.002402252989524116,
-0.002175907515711935, -0.001518948630011706, -0.000623607913580581, 0.000291727467744814, 0.001032493743140772,
0.001466078039230554, 0.001541598437149897, 0.001289527679116282, 0.000804118320944653, 0.000214927788687815,
-0.000344938705664714, -0.000766540799920385, -0.000983534965413392, -0.000978953969922609, -0.000780751290682747,
-0.000448959090901751, -0.000058614729046822, 0.000317269738067462, 0.000621157718914443, 0.000818750000130019,
0.000900611877226272, 0.000878592697224500, 0.000778858561033731, 0.000633746562372497, 0.000474396686568771,
0.000325476960438197, 0.000202565299657164, 0.000112071233638701, 0.000052842049763802, 0.000020553368071006,
0.000001500540125945
};
// FIR filter suitable for changing rates 7500 to/from 8000
// Sample 120000 Hz, pass 2700, stop 3730, ripple 0.1dB, atten 100 dB. Stop 0.03108.
float quiskFilt120t480[480] = { -0.000005050567303837, -0.000000267011791999, 0.000000197734700398, 0.000001038946634000,
0.000002322193058869, 0.000004115682735322, 0.000006499942123311, 0.000009551098482930, 0.000013350669444763,
0.000017966192635412, 0.000023463361155584, 0.000029885221425020, 0.000037271082107518, 0.000045630720487935,
0.000054970017069384, 0.000065233162392019, 0.000076360900545177, 0.000088271373315159, 0.000100818605854714,
0.000113853476544409, 0.000127174196746337, 0.000140558396336177, 0.000153744508371709, 0.000166450784469067,
0.000178368313347299, 0.000189176709991702, 0.000198541881389953, 0.000206128795372885, 0.000211604878787747,
0.000214655997661182, 0.000214994859281552, 0.000212358734245594, 0.000206539880117977, 0.000197379393194548,
0.000184780318878738, 0.000168719942655099, 0.000149250512353807, 0.000126511346757621, 0.000100726393185629,
0.000072210925236429, 0.000041365841965015, 0.000008680571408025, -0.000025277165852799, -0.000059865389594949,
-0.000094384355854646, -0.000128080670195777, -0.000160170174848483, -0.000189854272533545, -0.000216333899003825,
-0.000238836419299503, -0.000256632149501508, -0.000269058714331757, -0.000275541485292432, -0.000275614059005332,
-0.000268937472718753, -0.000255317038867589, -0.000234717772155001, -0.000207273956099563, -0.000173297342436372,
-0.000133280012107173, -0.000087895370243821, -0.000037986085678081, 0.000015440388211825, 0.000071232572821451,
0.000128114399130489, 0.000184710477990398, 0.000239577162514028, 0.000291234779803098, 0.000338204791740229,
0.000379047713684221, 0.000412403761615261, 0.000437031818051652, 0.000451848709179591, 0.000455966225408344,
0.000448726371643413, 0.000429729020814434, 0.000398857326863837, 0.000356297600912998, 0.000302547334727027,
0.000238422248479072, 0.000165048886226905, 0.000083853091464077, -0.000003462782744354, -0.000094949813106744,
-0.000188451833293202, -0.000281651282503015, -0.000372121907291206, -0.000457387566635848, -0.000534985542936898,
-0.000602532044011899, -0.000657788245032425, -0.000698728981427767, -0.000723604675185869, -0.000731002305621048,
-0.000719899536922384, -0.000689709694056092, -0.000640319946685634, -0.000572115873292030, -0.000485996080304965,
-0.000383371840261246, -0.000266155252511831, -0.000136731311264191, 0.000002082667095075, 0.000147092077716480,
0.000294790953130229, 0.000441441918072383, 0.000583164190168290, 0.000716029226064227, 0.000836164238172957,
0.000939856052624227, 0.001023657909064450, 0.001084492755093968, 0.001119751426837743, 0.001127383039339373,
0.001105974243787613, 0.001054815583369999, 0.000973950761085690, 0.000864209315714227, 0.000727219011746881,
0.000565398080608305, 0.000381924396468366, 0.000180685902835315, -0.000033793183292569, -0.000256444114966522,
-0.000481764526566339, -0.000703946352348464, -0.000917016099829735, -0.001114986581270253, -0.001292014799874503,
-0.001442563411804926, -0.001561559957317790, -0.001644551048567398, -0.001687846581475964, -0.001688649703502788,
-0.001645167889846890, -0.001556702802350076, -0.001423714708648073, -0.001247857669697092, -0.001031986722557201,
-0.000780131048444402, -0.000497436825078657, -0.000190077210351809, 0.000134868279325909, 0.000469563533327739,
0.000805591531546815, 0.001134152328775355, 0.001446279849797673, 0.001733071409562941, 0.001985924997799762,
0.002196778054604388, 0.002358342626407065, 0.002464328098407475, 0.002509648218888532, 0.002490604086803692,
0.002405037734357425, 0.002252452724297770, 0.002034094661603120, 0.001752990365583534, 0.001413941154886139,
0.001023470495638453, 0.000589723521647734, 0.000122320866350319, -0.000367832138027160, -0.000868777013398284,
-0.001367771151677059, -0.001851587344265625, -0.002306838088978190, -0.002720317947026380, -0.003079353614002113,
-0.003372155891804708, -0.003588162376578369, -0.003718362558663737, -0.003755596511143005, -0.003694818131674599,
-0.003533315298404129, -0.003270878754553819, -0.002909914962857412, -0.002455496391464944, -0.001915346645364514,
-0.001299757227227888, -0.000621437066532776, 0.000104706515738248, 0.000861849931067767, 0.001631595707499856,
0.002394368911341672, 0.003129858565588139, 0.003817496679992245, 0.004436963307209760, 0.004968707287606522,
0.005394469536085115, 0.005697797543539088, 0.005864537618023589, 0.005883292537600076, 0.005745832319314692,
0.005447447099071761, 0.004987231255534477, 0.004368289529377007, 0.003597859022418248, 0.002687338851256991,
0.001652226293162047, 0.000511956075882180, -0.000710356149138656, -0.001988263330091648, -0.003292424566049982,
-0.004591123342747130, -0.005850857852106148, -0.007036991266043732, -0.008114450164977267, -0.009048456200082230,
-0.009805276478965942, -0.010352975302354198, -0.010662152577592631, -0.010706650669328861, -0.010464214075017983,
-0.009917087295446811, -0.009052534679222271, -0.007863270920348924, -0.006347789704693751, -0.004510582323649121,
-0.002362238055733795, 0.000080576968834213, 0.002795265196543707, 0.005753566158586979, 0.008921944932552510,
0.012262093950265378, 0.015731539846483594, 0.019284344624007944, 0.022871886384520687, 0.026443706729191677,
0.029948406200633094, 0.033334570666910354, 0.036551709955124537, 0.039551189200810140, 0.042287133974308874,
0.044717290029466283, 0.046803820535016104, 0.048514022996355009, 0.049820951883635139, 0.050703932928426454,
0.051148959210315710, 0.051148959210315710, 0.050703932928426454, 0.049820951883635139, 0.048514022996355009,
0.046803820535016104, 0.044717290029466283, 0.042287133974308874, 0.039551189200810140, 0.036551709955124537,
0.033334570666910354, 0.029948406200633094, 0.026443706729191677, 0.022871886384520687, 0.019284344624007944,
0.015731539846483594, 0.012262093950265378, 0.008921944932552510, 0.005753566158586979, 0.002795265196543707,
0.000080576968834213, -0.002362238055733795, -0.004510582323649121, -0.006347789704693751, -0.007863270920348924,
-0.009052534679222271, -0.009917087295446811, -0.010464214075017983, -0.010706650669328861, -0.010662152577592631,
-0.010352975302354198, -0.009805276478965942, -0.009048456200082230, -0.008114450164977267, -0.007036991266043732,
-0.005850857852106148, -0.004591123342747130, -0.003292424566049982, -0.001988263330091648, -0.000710356149138656,
0.000511956075882180, 0.001652226293162047, 0.002687338851256991, 0.003597859022418248, 0.004368289529377007,
0.004987231255534477, 0.005447447099071761, 0.005745832319314692, 0.005883292537600076, 0.005864537618023589,
0.005697797543539088, 0.005394469536085115, 0.004968707287606522, 0.004436963307209760, 0.003817496679992245,
0.003129858565588139, 0.002394368911341672, 0.001631595707499856, 0.000861849931067767, 0.000104706515738248,
-0.000621437066532776, -0.001299757227227888, -0.001915346645364514, -0.002455496391464944, -0.002909914962857412,
-0.003270878754553819, -0.003533315298404129, -0.003694818131674599, -0.003755596511143005, -0.003718362558663737,
-0.003588162376578369, -0.003372155891804708, -0.003079353614002113, -0.002720317947026380, -0.002306838088978190,
-0.001851587344265625, -0.001367771151677059, -0.000868777013398284, -0.000367832138027160, 0.000122320866350319,
0.000589723521647734, 0.001023470495638453, 0.001413941154886139, 0.001752990365583534, 0.002034094661603120,
0.002252452724297770, 0.002405037734357425, 0.002490604086803692, 0.002509648218888532, 0.002464328098407475,
0.002358342626407065, 0.002196778054604388, 0.001985924997799762, 0.001733071409562941, 0.001446279849797673,
0.001134152328775355, 0.000805591531546815, 0.000469563533327739, 0.000134868279325909, -0.000190077210351809,
-0.000497436825078657, -0.000780131048444402, -0.001031986722557201, -0.001247857669697092, -0.001423714708648073,
-0.001556702802350076, -0.001645167889846890, -0.001688649703502788, -0.001687846581475964, -0.001644551048567398,
-0.001561559957317790, -0.001442563411804926, -0.001292014799874503, -0.001114986581270253, -0.000917016099829735,
-0.000703946352348464, -0.000481764526566339, -0.000256444114966522, -0.000033793183292569, 0.000180685902835315,
0.000381924396468366, 0.000565398080608305, 0.000727219011746881, 0.000864209315714227, 0.000973950761085690,
0.001054815583369999, 0.001105974243787613, 0.001127383039339373, 0.001119751426837743, 0.001084492755093968,
0.001023657909064450, 0.000939856052624227, 0.000836164238172957, 0.000716029226064227, 0.000583164190168290,
0.000441441918072383, 0.000294790953130229, 0.000147092077716480, 0.000002082667095075, -0.000136731311264191,
-0.000266155252511831, -0.000383371840261246, -0.000485996080304965, -0.000572115873292030, -0.000640319946685634,
-0.000689709694056092, -0.000719899536922384, -0.000731002305621048, -0.000723604675185869, -0.000698728981427767,
-0.000657788245032425, -0.000602532044011899, -0.000534985542936898, -0.000457387566635848, -0.000372121907291206,
-0.000281651282503015, -0.000188451833293202, -0.000094949813106744, -0.000003462782744354, 0.000083853091464077,
0.000165048886226905, 0.000238422248479072, 0.000302547334727027, 0.000356297600912998, 0.000398857326863837,
0.000429729020814434, 0.000448726371643413, 0.000455966225408344, 0.000451848709179591, 0.000437031818051652,
0.000412403761615261, 0.000379047713684221, 0.000338204791740229, 0.000291234779803098, 0.000239577162514028,
0.000184710477990398, 0.000128114399130489, 0.000071232572821451, 0.000015440388211825, -0.000037986085678081,
-0.000087895370243821, -0.000133280012107173, -0.000173297342436372, -0.000207273956099563, -0.000234717772155001,
-0.000255317038867589, -0.000268937472718753, -0.000275614059005332, -0.000275541485292432, -0.000269058714331757,
-0.000256632149501508, -0.000238836419299503, -0.000216333899003825, -0.000189854272533545, -0.000160170174848483,
-0.000128080670195777, -0.000094384355854646, -0.000059865389594949, -0.000025277165852799, 0.000008680571408025,
0.000041365841965015, 0.000072210925236429, 0.000100726393185629, 0.000126511346757621, 0.000149250512353807,
0.000168719942655099, 0.000184780318878738, 0.000197379393194548, 0.000206539880117977, 0.000212358734245594,
0.000214994859281552, 0.000214655997661182, 0.000211604878787747, 0.000206128795372885, 0.000198541881389953,
0.000189176709991702, 0.000178368313347299, 0.000166450784469067, 0.000153744508371709, 0.000140558396336177,
0.000127174196746337, 0.000113853476544409, 0.000100818605854714, 0.000088271373315159, 0.000076360900545177,
0.000065233162392019, 0.000054970017069384, 0.000045630720487935, 0.000037271082107518, 0.000029885221425020,
0.000023463361155584, 0.000017966192635412, 0.000013350669444763, 0.000009551098482930, 0.000006499942123311,
0.000004115682735322, 0.000002322193058869, 0.000001038946634000, 0.000000197734700398, -0.000000267011791999,
-0.000005050567303837 };
} // FreeDV

View File

@ -0,0 +1,867 @@
/*---------------------------------------------------------------------------*\
FILE........: fsk.c
AUTHOR......: Brady O'Brien
DATE CREATED: 11 February 2016
Framer and deframer for VHF FreeDV modes 'A' and 'B'
Currently designed for-
* 40ms ota modem frames
* 40ms Codec2 1300 frames
* 52 bits of Codec2 per frame
* 16 bits of unique word per frame
* 28 'spare' bits per frame
* - 4 spare bits at front and end of frame (8 total) for padding
* - 20 'protocol' bits, either for higher layers of 'protocol' or
* - 18 'protocol' bits and 2 vericode sidechannel bits
\*---------------------------------------------------------------------------*/
/*
Copyright (C) 2016 David Rowe
All rights reserved.
This program is free software; you can redistribute it and/or modify
it under the terms of the GNU Lesser General Public License version 2.1, as
published by the Free Software Foundation. This program is
distributed in the hope that it will be useful, but WITHOUT ANY
WARRANTY; without even the implied warranty of MERCHANTABILITY or
FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public
License for more details.
You should have received a copy of the GNU Lesser General Public License
along with this program; if not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include <stdlib.h>
#include <stdio.h>
#include <string.h>
#include <assert.h>
#include "freedv_vhf_framing.h"
namespace FreeDV
{
/* The voice UW of the VHF type A frame */
static const uint8_t A_uw_v[] = {0,1,1,0,0,1,1,1,
1,0,1,0,1,1,0,1};
/* The data UW of the VHF type A frame */
static const uint8_t A_uw_d[] = {1,1,1,1,0,0,0,1,
1,1,1,1,1,1,0,0};
/* Blank VHF type A frame */
static const uint8_t A_blank[] = {1,0,1,0,0,1,1,1, /* Padding[0:3] Proto[0:3] */
1,0,1,0,0,1,1,1, /* Proto[4:11] */
0,0,0,0,0,0,0,0, /* Voice[0:7] */
0,0,0,0,0,0,0,0, /* Voice[8:15] */
0,0,0,0,0,0,0,0, /* Voice[16:23] */
0,1,1,0,0,1,1,1, /* UW[0:7] */
1,0,1,0,1,1,0,1, /* UW[8:15] */
0,0,0,0,0,0,0,0, /* Voice[24:31] */
0,0,0,0,0,0,0,0, /* Voice[32:39] */
0,0,0,0,0,0,0,0, /* Voice[40:47] */
0,0,0,0,0,0,1,0, /* Voice[48:51] Proto[12:15] */
0,1,1,1,0,0,1,0};/* Proto[16:19] Padding[4:7] */
/* Blank VHF type AT (A for TDMA; padding bits not transmitted) frame */
static const uint8_t AT_blank[] = { 0,1,1,1, /* Proto[0:3] */
1,0,1,0,0,1,1,1, /* Proto[4:11] */
0,0,0,0,0,0,0,0, /* Voice[0:7] */
0,0,0,0,0,0,0,0, /* Voice[8:15] */
0,0,0,0,0,0,0,0, /* Voice[16:23] */
0,1,1,0,0,1,1,1, /* UW[0:7] */
1,0,1,0,1,1,0,1, /* UW[8:15] */
0,0,0,0,0,0,0,0, /* Voice[24:31] */
0,0,0,0,0,0,0,0, /* Voice[32:39] */
0,0,0,0,0,0,0,0, /* Voice[40:47] */
0,0,0,0,0,0,1,0, /* Voice[48:51] Proto[12:15] */
0,1,1,1 };/* Proto[16:19] */
/* HF Type B voice UW */
static const uint8_t B_uw_v[] = {0,1,1,0,0,1,1,1};
/* HF Type B data UW */
static const uint8_t B_uw_d[] = {1,1,1,1,0,0,1,0};
/* Blank HF type B frame */
static const uint8_t B_blank[] = {0,1,1,0,0,1,1,1, /* UW[0:7] */
0,0,0,0,0,0,0,0, /* Voice1[0:7] */
0,0,0,0,0,0,0,0, /* Voice1[8:15] */
0,0,0,0,0,0,0,0, /* Voice1[16:23] */
0,0,0,0,0,0,0,0, /* Voice1[24:28] Voice2[0:3] */
0,0,0,0,0,0,0,0, /* Voice2[4:11] */
0,0,0,0,0,0,0,0, /* Voice2[12:19] */
0,0,0,0,0,0,0,0};/* Voice2[20:28] */
/* States */
#define ST_NOSYNC 0 /* Not synchronized */
#define ST_SYNC 1 /* Synchronized */
/* Get a single bit out of an MSB-first packed byte array */
#define UNPACK_BIT_MSBFIRST(bytes,bitidx) ((bytes)[(bitidx)>>3]>>(7-((bitidx)&0x7)))&0x1
enum frame_payload_type {
FRAME_PAYLOAD_TYPE_VOICE,
FRAME_PAYLOAD_TYPE_DATA,
};
/* Place codec and other bits into a frame */
void fvhff_frame_bits( int frame_type,
uint8_t bits_out[],
uint8_t codec2_in[],
uint8_t proto_in[],
uint8_t vc_in[]){
int i,ibit;
if(frame_type == FREEDV_VHF_FRAME_A){
/* Fill out frame with blank frame prototype */
for(i=0; i<96; i++)
bits_out[i] = A_blank[i];
/* Fill in protocol bits, if present */
if(proto_in!=NULL){
ibit = 0;
/* First half of protocol bits */
/* Extract and place in frame, MSB first */
for(i=4 ; i<16; i++){
bits_out[i] = UNPACK_BIT_MSBFIRST(proto_in,ibit);
ibit++;
}
/* Last set of protocol bits */
for(i=84; i<92; i++){
bits_out[i] = UNPACK_BIT_MSBFIRST(proto_in,ibit);
ibit++;
}
}
/* Fill in varicode bits, if present */
if(vc_in!=NULL){
bits_out[90] = vc_in[0];
bits_out[91] = vc_in[1];
}
/* Fill in codec2 bits, present or not */
ibit = 0;
for(i=16; i<40; i++){ /* First half */
bits_out[i] = UNPACK_BIT_MSBFIRST(codec2_in,ibit);
ibit++;
}
for(i=56; i<84; i++){ /* Second half */
bits_out[i] = UNPACK_BIT_MSBFIRST(codec2_in,ibit);
ibit++;
}
}else if(frame_type == FREEDV_HF_FRAME_B){
/* Pointers to both c2 frames so the bit unpack macro works */
uint8_t * codec2_in1 = &codec2_in[0];
uint8_t * codec2_in2 = &codec2_in[4];
/* Fill out frame with blank prototype */
for(i=0; i<64; i++)
bits_out[i] = B_blank[i];
/* Fill out first codec2 block */
ibit=0;
for(i=8; i<36; i++){
bits_out[i] = UNPACK_BIT_MSBFIRST(codec2_in1,ibit);
ibit++;
}
/* Fill out second codec2 block */
ibit=0;
for(i=36; i<64; i++){
bits_out[i] = UNPACK_BIT_MSBFIRST(codec2_in2,ibit);
ibit++;
}
}else if(frame_type == FREEDV_VHF_FRAME_AT){
/* Fill out frame with blank frame prototype */
for(i=0; i<88; i++)
bits_out[i] = AT_blank[i];
/* Fill in protocol bits, if present */
if(proto_in!=NULL){
ibit = 0;
/* First half of protocol bits */
/* Extract and place in frame, MSB first */
for(i=0 ; i<12; i++){
bits_out[i] = UNPACK_BIT_MSBFIRST(proto_in,ibit);
ibit++;
}
/* Last set of protocol bits */
for(i=80; i<88; i++){
bits_out[i] = UNPACK_BIT_MSBFIRST(proto_in,ibit);
ibit++;
}
}
/* Fill in varicode bits, if present */
if(vc_in!=NULL){
bits_out[86] = vc_in[0];
bits_out[87] = vc_in[1];
}
/* Fill in codec2 bits, present or not */
ibit = 0;
for(i=12; i<36; i++){ /* First half */
bits_out[i] = UNPACK_BIT_MSBFIRST(codec2_in,ibit);
ibit++;
}
for(i=52; i<80; i++){ /* Second half */
bits_out[i] = UNPACK_BIT_MSBFIRST(codec2_in,ibit);
ibit++;
}
}
}
/* Place data and other bits into a frame */
void fvhff_frame_data_bits(struct freedv_vhf_deframer * def, int frame_type,
uint8_t bits_out[]){
int i,ibit;
if(frame_type == FREEDV_VHF_FRAME_A){
uint8_t data[8];
int end_bits;
int from_bit;
int bcast_bit;
int crc_bit;
/* Fill out frame with blank frame prototype */
for(i=0; i<4; i++)
bits_out[i] = A_blank[i];
for(i=92; i<96; i++)
bits_out[i] = A_blank[i];
/* UW data */
for (i=0; i < 16; i++)
bits_out[40 + i] = A_uw_d[i];
if (def->fdc)
freedv_data_channel_tx_frame(def->fdc, data, 8, &from_bit, &bcast_bit, &crc_bit, &end_bits);
else
return;
bits_out[4] = from_bit;
bits_out[5] = bcast_bit;
bits_out[6] = 0; /* unused */
bits_out[7] = 0; /* unused */
/* Fill in data bits */
ibit = 0;
for(i=8; i<40; i++){ /* First half */
bits_out[i] = UNPACK_BIT_MSBFIRST(data,ibit);
ibit++;
}
for(i=56; i<88; i++){ /* Second half */
bits_out[i] = UNPACK_BIT_MSBFIRST(data,ibit);
ibit++;
}
for (i = 0; i < 4; i++)
bits_out[88 + i] = (end_bits >> (3-i)) & 0x1;
} else if (frame_type == FREEDV_HF_FRAME_B){
uint8_t data[6];
int end_bits;
int from_bit;
int bcast_bit;
int crc_bit;
/* Fill out frame with blank prototype */
for(i=0; i<64; i++)
bits_out[i] = B_blank[i];
/* UW data */
for (i=0; i < 8; i++)
bits_out[0 + i] = B_uw_d[i];
if (def->fdc)
freedv_data_channel_tx_frame(def->fdc, data, 6, &from_bit, &bcast_bit, &crc_bit, &end_bits);
else
return;
bits_out[56] = from_bit;
bits_out[57] = bcast_bit;
bits_out[58] = crc_bit;
bits_out[59] = 0; /* unused */
/* Fill in data bits */
ibit = 0;
for(i=8; i<56; i++){ /* First half */
bits_out[i] = UNPACK_BIT_MSBFIRST(data,ibit);
ibit++;
}
for (i = 0; i < 4; i++)
bits_out[60 + i] = (end_bits >> (3-i)) & 0x1;
}
}
/* Init and allocate memory for a freedv-vhf framer/deframer */
struct freedv_vhf_deframer * fvhff_create_deframer(uint8_t frame_type, int enable_bit_flip){
struct freedv_vhf_deframer * deframer;
uint8_t *bits,*invbits;
int frame_size;
int uw_size;
assert( (frame_type == FREEDV_VHF_FRAME_A) || (frame_type == FREEDV_HF_FRAME_B) );
/* It's a Type A frame */
if(frame_type == FREEDV_VHF_FRAME_A){
frame_size = 96;
uw_size = 16;
}else if(frame_type == FREEDV_HF_FRAME_B){
frame_size = 64;
uw_size = 8;
}else{
return NULL;
}
/* Allocate memory for the thing */
deframer = (freedv_vhf_deframer*) malloc(sizeof(struct freedv_vhf_deframer));
if(deframer == NULL)
return NULL;
/* Allocate the not-bit buffer */
if(enable_bit_flip){
invbits = (uint8_t*) malloc(sizeof(uint8_t)*frame_size);
if(invbits == NULL) {
free(deframer);
return NULL;
}
}else{
invbits = NULL;
}
/* Allocate the bit buffer */
bits = (uint8_t*) malloc(sizeof(uint8_t)*frame_size);
if(bits == NULL) {
free(deframer);
return NULL;
}
deframer->bits = bits;
deframer->invbits = invbits;
deframer->ftype = frame_type;
deframer->state = ST_NOSYNC;
deframer->bitptr = 0;
deframer->last_uw = 0;
deframer->miss_cnt = 0;
deframer->frame_size = frame_size;
deframer->uw_size = uw_size;
deframer->on_inv_bits = 0;
deframer->sym_size = 1;
deframer->ber_est = 0;
deframer->total_uw_bits = 0;
deframer->total_uw_err = 0;
deframer->fdc = NULL;
return deframer;
}
/* Get size of frame in bits */
int fvhff_get_frame_size(struct freedv_vhf_deframer * def){
return def->frame_size;
}
/* Codec2 size in bytes */
int fvhff_get_codec2_size(struct freedv_vhf_deframer * def){
if(def->ftype == FREEDV_VHF_FRAME_A){
return 7;
} else if(def->ftype == FREEDV_HF_FRAME_B){
return 8;
} else{
return 0;
}
}
/* Protocol bits in bits */
int fvhff_get_proto_size(struct freedv_vhf_deframer * def){
if(def->ftype == FREEDV_VHF_FRAME_A){
return 20;
} else if(def->ftype == FREEDV_HF_FRAME_B){
return 0;
} else{
return 0;
}
}
/* Varicode bits in bits */
int fvhff_get_varicode_size(struct freedv_vhf_deframer * def){
if(def->ftype == FREEDV_VHF_FRAME_A){
return 2;
} else if(def->ftype == FREEDV_HF_FRAME_B){
return 0;
} else{
return 0;
}
}
void fvhff_destroy_deframer(struct freedv_vhf_deframer * def){
freedv_data_channel_destroy(def->fdc);
free(def->bits);
free(def);
}
int fvhff_synchronized(struct freedv_vhf_deframer * def){
return (def->state) == ST_SYNC;
}
/* Search for a complete UW in a buffer of bits */
std::size_t fvhff_search_uw(const uint8_t bits[], std::size_t nbits,
const uint8_t uw[], std::size_t uw_len,
std::size_t * delta_out, std::size_t bits_per_sym){
std::size_t ibits,iuw;
std::size_t delta_min = uw_len;
std::size_t delta;
std::size_t offset_min = 0;
/* Walk through buffer bits */
for(ibits = 0; ibits < nbits-uw_len; ibits+=bits_per_sym){
delta = 0;
for(iuw = 0; iuw < uw_len; iuw++){
if(bits[ibits+iuw] != uw[iuw]) delta++;
}
if( delta < delta_min ){
delta_min = delta;
offset_min = ibits;
}
}
if(delta_out != NULL) *delta_out = delta_min;
return offset_min;
}
/* See if the UW is where it should be, to within a tolerance, in a bit buffer */
static int fvhff_match_uw(struct freedv_vhf_deframer * def,uint8_t bits[],int tol,int *rdiff, enum frame_payload_type *pt){
int frame_type = def->ftype;
int bitptr = def->bitptr;
int frame_size = def->frame_size;
int uw_len = def->uw_size;
int iuw,ibit;
const uint8_t * uw[2];
int uw_offset;
int diff[2] = { 0, 0 };
int i;
int match[2];
int r;
/* defaults to make compiler happy on -O3 */
*pt = FRAME_PAYLOAD_TYPE_VOICE;
*rdiff = 0;
/* Set up parameters for the standard type of frame */
if(frame_type == FREEDV_VHF_FRAME_A){
uw[0] = A_uw_v;
uw[1] = A_uw_d;
uw_len = 16;
uw_offset = 40;
} else if(frame_type == FREEDV_HF_FRAME_B){
uw[0] = B_uw_v;
uw[1] = B_uw_d;
uw_len = 8;
uw_offset = 0;
} else {
return 0;
}
/* Check both the voice and data UWs */
for (i = 0; i < 2; i++) {
/* Start bit pointer where UW should be */
ibit = bitptr + uw_offset;
if(ibit >= frame_size) ibit -= frame_size;
/* Walk through and match bits in frame with bits of UW */
for(iuw=0; iuw<uw_len; iuw++){
if(bits[ibit] != uw[i][iuw]) diff[i]++;
ibit++;
if(ibit >= frame_size) ibit = 0;
}
match[i] = diff[i] <= tol;
}
/* Pick the best matching UW */
if (diff[0] < diff[1]) {
r = match[0];
*rdiff = diff[0];
*pt = FRAME_PAYLOAD_TYPE_VOICE;
} else {
r = match[1];
*rdiff = diff[1];
*pt = FRAME_PAYLOAD_TYPE_DATA;
}
return r;
}
static void fvhff_extract_frame_voice(struct freedv_vhf_deframer * def,uint8_t bits[],
uint8_t codec2_out[],uint8_t proto_out[],uint8_t vc_out[]){
int frame_type = def->ftype;
int bitptr = def->bitptr;
int frame_size = def->frame_size;
int iframe,ibit;
if(frame_type == FREEDV_VHF_FRAME_A){
/* Extract codec2 bits */
memset(codec2_out,0,7);
ibit = 0;
/* Extract and pack first half, MSB first */
iframe = bitptr+16;
if(iframe >= frame_size) iframe-=frame_size;
for(;ibit<24;ibit++){
codec2_out[ibit>>3] |= (bits[iframe]&0x1)<<(7-(ibit&0x7));
iframe++;
if(iframe >= frame_size) iframe=0;
}
/* Extract and pack last half, MSB first */
iframe = bitptr+56;
if(iframe >= frame_size) iframe-=frame_size;
for(;ibit<52;ibit++){
codec2_out[ibit>>3] |= (bits[iframe]&0x1)<<(7-(ibit&0x7));
iframe++;
if(iframe >= frame_size) iframe=0;
}
/* Extract varicode bits, if wanted */
if(vc_out!=NULL){
iframe = bitptr+90;
if(iframe >= frame_size) iframe-=frame_size;
vc_out[0] = bits[iframe];
iframe++;
vc_out[1] = bits[iframe];
}
/* Extract protocol bits, if proto is passed through */
if(proto_out!=NULL){
/* Clear protocol bit array */
memset(proto_out,0,3);
ibit = 0;
/* Extract and pack first half, MSB first */
iframe = bitptr+4;
if(iframe >= frame_size) iframe-=frame_size;
for(;ibit<12;ibit++){
proto_out[ibit>>3] |= (bits[iframe]&0x1)<<(7-(ibit&0x7));
iframe++;
if(iframe >= frame_size) iframe=0;
}
/* Extract and pack last half, MSB first */
iframe = bitptr+84;
if(iframe >= frame_size) iframe-=frame_size;
for(;ibit<20;ibit++){
proto_out[ibit>>3] |= (bits[iframe]&0x1)<<(7-(ibit&0x7));
iframe++;
if(iframe >= frame_size) iframe=0;
}
}
}else if(frame_type == FREEDV_HF_FRAME_B){
/* Pointers to both c2 frames */
uint8_t * codec2_out1 = &codec2_out[0];
uint8_t * codec2_out2 = &codec2_out[4];
/* Extract codec2 bits */
memset(codec2_out,0,8);
ibit = 0;
/* Extract and pack first c2 frame, MSB first */
iframe = bitptr+8;
if(iframe >= frame_size) iframe-=frame_size;
for(;ibit<28;ibit++){
codec2_out1[ibit>>3] |= (bits[iframe]&0x1)<<(7-(ibit&0x7));
iframe++;
if(iframe >= frame_size) iframe=0;
}
/* Extract and pack second c2 frame, MSB first */
iframe = bitptr+36;
ibit = 0;
if(iframe >= frame_size) iframe-=frame_size;
for(;ibit<28;ibit++){
codec2_out2[ibit>>3] |= (bits[iframe]&0x1)<<(7-(ibit&0x7));
iframe++;
if(iframe >= frame_size) iframe=0;
}
}else if(frame_type == FREEDV_VHF_FRAME_AT){
/* Extract codec2 bits */
memset(codec2_out,0,7);
ibit = 0;
/* Extract and pack first half, MSB first */
iframe = bitptr+12;
if(iframe >= frame_size) iframe-=frame_size;
for(;ibit<24;ibit++){
codec2_out[ibit>>3] |= (bits[iframe]&0x1)<<(7-(ibit&0x7));
iframe++;
if(iframe >= frame_size) iframe=0;
}
/* Extract and pack last half, MSB first */
iframe = bitptr+52;
if(iframe >= frame_size) iframe-=frame_size;
for(;ibit<52;ibit++){
codec2_out[ibit>>3] |= (bits[iframe]&0x1)<<(7-(ibit&0x7));
iframe++;
if(iframe >= frame_size) iframe=0;
}
/* Extract varicode bits, if wanted */
if(vc_out!=NULL){
iframe = bitptr+86;
if(iframe >= frame_size) iframe-=frame_size;
vc_out[0] = bits[iframe];
iframe++;
vc_out[1] = bits[iframe];
}
/* Extract protocol bits, if proto is passed through */
if(proto_out!=NULL){
/* Clear protocol bit array */
memset(proto_out,0,3);
ibit = 0;
/* Extract and pack first half, MSB first */
iframe = bitptr+4;
if(iframe >= frame_size) iframe-=frame_size;
for(;ibit<12;ibit++){
proto_out[ibit>>3] |= (bits[iframe]&0x1)<<(7-(ibit&0x7));
iframe++;
if(iframe >= frame_size) iframe=0;
}
/* Extract and pack last half, MSB first */
iframe = bitptr+84;
if(iframe >= frame_size) iframe-=frame_size;
for(;ibit<20;ibit++){
proto_out[ibit>>3] |= (bits[iframe]&0x1)<<(7-(ibit&0x7));
iframe++;
if(iframe >= frame_size) iframe=0;
}
}
}
}
static void fvhff_extract_frame_data(struct freedv_vhf_deframer * def,uint8_t bits[]){
int frame_type = def->ftype;
int bitptr = def->bitptr;
int frame_size = def->frame_size;
int iframe,ibit;
if(frame_type == FREEDV_VHF_FRAME_A){
uint8_t data[8];
int end_bits = 0;
int from_bit;
int bcast_bit;
iframe = bitptr+4;
if(iframe >= frame_size) iframe-=frame_size;
from_bit = bits[iframe];
iframe++;
if(iframe >= frame_size) iframe-=frame_size;
bcast_bit = bits[iframe];
/* Extract data bits */
memset(data,0,8);
ibit = 0;
/* Extract and pack first half, MSB first */
iframe = bitptr+8;
if(iframe >= frame_size) iframe-=frame_size;
for(;ibit<32;ibit++){
data[ibit>>3] |= (bits[iframe]&0x1)<<(7-(ibit&0x7));
iframe++;
if(iframe >= frame_size) iframe=0;
}
/* Extract and pack last half, MSB first */
iframe = bitptr+56;
if(iframe >= frame_size) iframe-=frame_size;
for(;ibit<64;ibit++){
data[ibit>>3] |= (bits[iframe]&0x1)<<(7-(ibit&0x7));
iframe++;
if(iframe >= frame_size) iframe=0;
}
/* Extract endbits value, MSB first*/
iframe = bitptr+88;
ibit = 0;
if(iframe >= frame_size) iframe-=frame_size;
for(;ibit<4;ibit++){
end_bits |= (bits[iframe]&0x1)<<(3-(ibit));
iframe++;
if(iframe >= frame_size) iframe=0;
}
if (def->fdc) {
freedv_data_channel_rx_frame(def->fdc, data, 8, from_bit, bcast_bit, 0, end_bits);
}
} else if(frame_type == FREEDV_HF_FRAME_B){
uint8_t data[6];
int end_bits = 0;
int from_bit;
int bcast_bit;
int crc_bit;
ibit = 0;
memset(data,0,6);
/* Extract and pack first c2 frame, MSB first */
iframe = bitptr+8;
if(iframe >= frame_size) iframe-=frame_size;
for(;ibit<48;ibit++){
data[ibit>>3] |= (bits[iframe]&0x1)<<(7-(ibit&0x7));
iframe++;
if(iframe >= frame_size) iframe=0;
}
iframe = bitptr+56;
if(iframe >= frame_size) iframe-=frame_size;
from_bit = bits[iframe];
iframe++;
if(iframe >= frame_size) iframe-=frame_size;
bcast_bit = bits[iframe];
iframe++;
if(iframe >= frame_size) iframe-=frame_size;
crc_bit = bits[iframe];
/* Extract endbits value, MSB first*/
iframe = bitptr+60;
ibit = 0;
if(iframe >= frame_size) iframe-=frame_size;
for(;ibit<4;ibit++){
end_bits |= (bits[iframe]&0x1)<<(3-(ibit));
iframe++;
if(iframe >= frame_size) iframe=0;
}
if (def->fdc) {
freedv_data_channel_rx_frame(def->fdc, data, 6, from_bit, bcast_bit, crc_bit, end_bits);
}
}
}
static void fvhff_extract_frame(struct freedv_vhf_deframer * def,uint8_t bits[],uint8_t codec2_out[],
uint8_t proto_out[],uint8_t vc_out[],enum frame_payload_type pt){
switch (pt) {
case FRAME_PAYLOAD_TYPE_VOICE:
fvhff_extract_frame_voice(def, bits, codec2_out, proto_out, vc_out);
break;
case FRAME_PAYLOAD_TYPE_DATA:
fvhff_extract_frame_data(def, bits);
break;
}
}
/*
* Try to find the UW and extract codec/proto/vc bits in def->frame_size bits
*/
int fvhff_deframe_bits(struct freedv_vhf_deframer * def,uint8_t codec2_out[],uint8_t proto_out[],
uint8_t vc_out[],uint8_t bits_in[]){
uint8_t * strbits = def->bits;
uint8_t * invbits = def->invbits;
uint8_t * bits;
int on_inv_bits = def->on_inv_bits;
int frame_type = def->ftype;
int state = def->state;
int bitptr = def->bitptr;
int last_uw = def->last_uw;
int miss_cnt = def->miss_cnt;
int frame_size = def->frame_size;
int uw_size = def->uw_size;
int uw_diff;
int i;
int uw_first_tol;
int uw_sync_tol;
int miss_tol;
int extracted_frame = 0;
enum frame_payload_type pt = FRAME_PAYLOAD_TYPE_VOICE;
/* Possibly set up frame-specific params here */
if(frame_type == FREEDV_VHF_FRAME_A){
uw_first_tol = 1; /* The UW bit-error tolerance for the first frame */
uw_sync_tol = 3; /* The UW bit error tolerance for frames after sync */
miss_tol = 4; /* How many UWs may be missed before going into the de-synced state */
}else if(frame_type == FREEDV_HF_FRAME_B){
uw_first_tol = 0; /* The UW bit-error tolerance for the first frame */
uw_sync_tol = 1; /* The UW bit error tolerance for frames after sync */
miss_tol = 3; /* How many UWs may be missed before going into the de-synced state */
}else{
return 0;
}
/* Skip N bits for multi-bit symbol modems */
for(i=0; i<frame_size; i++){
/* Put a bit in the buffer */
strbits[bitptr] = bits_in[i];
/* If we're checking the inverted bitstream, put a bit in it */
if(invbits!=NULL)
invbits[bitptr] = bits_in[i]?0:1;
bitptr++;
if(bitptr >= frame_size) bitptr -= frame_size;
def->bitptr = bitptr;
/* Enter state machine */
if(state==ST_SYNC){
/* Already synchronized, just wait till UW is back where it should be */
last_uw++;
if(invbits!=NULL){
if(on_inv_bits)
bits = invbits;
else
bits = strbits;
}else{
bits=strbits;
}
/* UW should be here. We're sunk, so deframe anyway */
if(last_uw == frame_size){
last_uw = 0;
if(!fvhff_match_uw(def,bits,uw_sync_tol,&uw_diff, &pt))
miss_cnt++;
else
miss_cnt=0;
/* If we go over the miss tolerance, go into no-sync */
if(miss_cnt>miss_tol){
state = ST_NOSYNC;
}
/* Extract the bits */
extracted_frame = 1;
fvhff_extract_frame(def,bits,codec2_out,proto_out,vc_out,pt);
/* Update BER estimate */
def->ber_est = (.995*def->ber_est) + (.005*((float)uw_diff)/((float)uw_size));
def->total_uw_bits += uw_size;
def->total_uw_err += uw_diff;
}
/* Not yet sunk */
}else{
/* It's a sync!*/
if(invbits!=NULL){
if(fvhff_match_uw(def,invbits,uw_first_tol, &uw_diff, &pt)){
state = ST_SYNC;
last_uw = 0;
miss_cnt = 0;
extracted_frame = 1;
on_inv_bits = 1;
fvhff_extract_frame(def,invbits,codec2_out,proto_out,vc_out,pt);
/* Update BER estimate */
def->ber_est = (.995*def->ber_est) + (.005*((float)uw_diff)/((float)uw_size));
def->total_uw_bits += uw_size;
def->total_uw_err += uw_diff;
}
}
if(fvhff_match_uw(def,strbits,uw_first_tol, &uw_diff, &pt)){
state = ST_SYNC;
last_uw = 0;
miss_cnt = 0;
extracted_frame = 1;
on_inv_bits = 0;
fvhff_extract_frame(def,strbits,codec2_out,proto_out,vc_out,pt);
/* Update BER estimate */
def->ber_est = (.995*def->ber_est) + (.005*((float)uw_diff)/((float)uw_size));
def->total_uw_bits += uw_size;
def->total_uw_err += uw_diff;
}
}
}
def->state = state;
def->last_uw = last_uw;
def->miss_cnt = miss_cnt;
def->on_inv_bits = on_inv_bits;
/* return zero for data frames, they are already handled by callback */
return extracted_frame && pt == FRAME_PAYLOAD_TYPE_VOICE;
}
} // FreeDV

1251
libfreedv/fsk.cpp Normal file

File diff suppressed because it is too large Load Diff

649
libfreedv/hanning.h Normal file
View File

@ -0,0 +1,649 @@
/* Generated by hanning_file() Octave function */
namespace FreeDV
{
const float hanning[]={
0,
2.4171e-05,
9.66816e-05,
0.000217525,
0.000386689,
0.000604158,
0.00086991,
0.00118392,
0.00154616,
0.00195659,
0.00241517,
0.00292186,
0.00347661,
0.00407937,
0.00473008,
0.00542867,
0.00617507,
0.00696922,
0.00781104,
0.00870045,
0.00963736,
0.0106217,
0.0116533,
0.0127322,
0.0138581,
0.0150311,
0.0162509,
0.0175175,
0.0188308,
0.0201906,
0.0215968,
0.0230492,
0.0245478,
0.0260923,
0.0276826,
0.0293186,
0.0310001,
0.032727,
0.034499,
0.036316,
0.0381779,
0.0400844,
0.0420354,
0.0440307,
0.04607,
0.0481533,
0.0502802,
0.0524506,
0.0546643,
0.056921,
0.0592206,
0.0615627,
0.0639473,
0.0663741,
0.0688427,
0.0713531,
0.0739048,
0.0764978,
0.0791318,
0.0818064,
0.0845214,
0.0872767,
0.0900718,
0.0929066,
0.0957807,
0.0986939,
0.101646,
0.104636,
0.107665,
0.110732,
0.113836,
0.116978,
0.120156,
0.123372,
0.126624,
0.129912,
0.133235,
0.136594,
0.139989,
0.143418,
0.146881,
0.150379,
0.153911,
0.157476,
0.161074,
0.164705,
0.168368,
0.172063,
0.17579,
0.179549,
0.183338,
0.187158,
0.191008,
0.194888,
0.198798,
0.202737,
0.206704,
0.2107,
0.214724,
0.218775,
0.222854,
0.226959,
0.231091,
0.235249,
0.239432,
0.243641,
0.247874,
0.252132,
0.256414,
0.260719,
0.265047,
0.269398,
0.273772,
0.278167,
0.282584,
0.287021,
0.29148,
0.295958,
0.300456,
0.304974,
0.30951,
0.314065,
0.318638,
0.323228,
0.327835,
0.332459,
0.3371,
0.341756,
0.346427,
0.351113,
0.355814,
0.360528,
0.365256,
0.369997,
0.374751,
0.379516,
0.384293,
0.389082,
0.393881,
0.398691,
0.40351,
0.408338,
0.413176,
0.418022,
0.422876,
0.427737,
0.432605,
0.43748,
0.44236,
0.447247,
0.452138,
0.457034,
0.461935,
0.466839,
0.471746,
0.476655,
0.481568,
0.486481,
0.491397,
0.496313,
0.501229,
0.506145,
0.511061,
0.515976,
0.520889,
0.5258,
0.530708,
0.535614,
0.540516,
0.545414,
0.550308,
0.555197,
0.560081,
0.564958,
0.56983,
0.574695,
0.579552,
0.584402,
0.589244,
0.594077,
0.598901,
0.603715,
0.60852,
0.613314,
0.618097,
0.622868,
0.627628,
0.632375,
0.63711,
0.641831,
0.646538,
0.651232,
0.655911,
0.660574,
0.665222,
0.669855,
0.67447,
0.679069,
0.683651,
0.688215,
0.69276,
0.697287,
0.701795,
0.706284,
0.710752,
0.7152,
0.719627,
0.724033,
0.728418,
0.73278,
0.73712,
0.741437,
0.74573,
0.75,
0.754246,
0.758467,
0.762663,
0.766833,
0.770978,
0.775097,
0.779189,
0.783254,
0.787291,
0.791301,
0.795283,
0.799236,
0.80316,
0.807055,
0.810921,
0.814756,
0.81856,
0.822334,
0.826077,
0.829788,
0.833468,
0.837115,
0.840729,
0.844311,
0.847859,
0.851374,
0.854855,
0.858301,
0.861713,
0.86509,
0.868431,
0.871737,
0.875007,
0.87824,
0.881437,
0.884598,
0.887721,
0.890806,
0.893854,
0.896864,
0.899835,
0.902768,
0.905661,
0.908516,
0.911331,
0.914106,
0.916841,
0.919536,
0.92219,
0.924804,
0.927376,
0.929907,
0.932397,
0.934845,
0.93725,
0.939614,
0.941935,
0.944213,
0.946448,
0.94864,
0.950789,
0.952894,
0.954955,
0.956972,
0.958946,
0.960874,
0.962759,
0.964598,
0.966393,
0.968142,
0.969846,
0.971505,
0.973118,
0.974686,
0.976207,
0.977683,
0.979112,
0.980495,
0.981832,
0.983122,
0.984365,
0.985561,
0.986711,
0.987813,
0.988868,
0.989876,
0.990837,
0.99175,
0.992616,
0.993434,
0.994204,
0.994927,
0.995601,
0.996228,
0.996807,
0.997337,
0.99782,
0.998255,
0.998641,
0.998979,
0.999269,
0.999511,
0.999704,
0.999849,
0.999946,
0.999994,
0.999994,
0.999946,
0.999849,
0.999704,
0.999511,
0.999269,
0.998979,
0.998641,
0.998255,
0.99782,
0.997337,
0.996807,
0.996228,
0.995601,
0.994927,
0.994204,
0.993434,
0.992616,
0.99175,
0.990837,
0.989876,
0.988868,
0.987813,
0.986711,
0.985561,
0.984365,
0.983122,
0.981832,
0.980495,
0.979112,
0.977683,
0.976207,
0.974686,
0.973118,
0.971505,
0.969846,
0.968142,
0.966393,
0.964598,
0.962759,
0.960874,
0.958946,
0.956972,
0.954955,
0.952894,
0.950789,
0.94864,
0.946448,
0.944213,
0.941935,
0.939614,
0.93725,
0.934845,
0.932397,
0.929907,
0.927376,
0.924804,
0.92219,
0.919536,
0.916841,
0.914106,
0.911331,
0.908516,
0.905661,
0.902768,
0.899835,
0.896864,
0.893854,
0.890806,
0.887721,
0.884598,
0.881437,
0.87824,
0.875007,
0.871737,
0.868431,
0.86509,
0.861713,
0.858301,
0.854855,
0.851374,
0.847859,
0.844311,
0.840729,
0.837115,
0.833468,
0.829788,
0.826077,
0.822334,
0.81856,
0.814756,
0.810921,
0.807055,
0.80316,
0.799236,
0.795283,
0.791301,
0.787291,
0.783254,
0.779189,
0.775097,
0.770978,
0.766833,
0.762663,
0.758467,
0.754246,
0.75,
0.74573,
0.741437,
0.73712,
0.73278,
0.728418,
0.724033,
0.719627,
0.7152,
0.710752,
0.706284,
0.701795,
0.697287,
0.69276,
0.688215,
0.683651,
0.679069,
0.67447,
0.669855,
0.665222,
0.660574,
0.655911,
0.651232,
0.646538,
0.641831,
0.63711,
0.632375,
0.627628,
0.622868,
0.618097,
0.613314,
0.60852,
0.603715,
0.598901,
0.594077,
0.589244,
0.584402,
0.579552,
0.574695,
0.56983,
0.564958,
0.560081,
0.555197,
0.550308,
0.545414,
0.540516,
0.535614,
0.530708,
0.5258,
0.520889,
0.515976,
0.511061,
0.506145,
0.501229,
0.496313,
0.491397,
0.486481,
0.481568,
0.476655,
0.471746,
0.466839,
0.461935,
0.457034,
0.452138,
0.447247,
0.44236,
0.43748,
0.432605,
0.427737,
0.422876,
0.418022,
0.413176,
0.408338,
0.40351,
0.398691,
0.393881,
0.389082,
0.384293,
0.379516,
0.374751,
0.369997,
0.365256,
0.360528,
0.355814,
0.351113,
0.346427,
0.341756,
0.3371,
0.332459,
0.327835,
0.323228,
0.318638,
0.314065,
0.30951,
0.304974,
0.300456,
0.295958,
0.29148,
0.287021,
0.282584,
0.278167,
0.273772,
0.269398,
0.265047,
0.260719,
0.256414,
0.252132,
0.247874,
0.243641,
0.239432,
0.235249,
0.231091,
0.226959,
0.222854,
0.218775,
0.214724,
0.2107,
0.206704,
0.202737,
0.198798,
0.194888,
0.191008,
0.187158,
0.183338,
0.179549,
0.17579,
0.172063,
0.168368,
0.164705,
0.161074,
0.157476,
0.153911,
0.150379,
0.146881,
0.143418,
0.139989,
0.136594,
0.133235,
0.129912,
0.126624,
0.123372,
0.120156,
0.116978,
0.113836,
0.110732,
0.107665,
0.104636,
0.101646,
0.0986939,
0.0957807,
0.0929066,
0.0900718,
0.0872767,
0.0845214,
0.0818064,
0.0791318,
0.0764978,
0.0739048,
0.0713531,
0.0688427,
0.0663741,
0.0639473,
0.0615627,
0.0592206,
0.056921,
0.0546643,
0.0524506,
0.0502802,
0.0481533,
0.04607,
0.0440307,
0.0420354,
0.0400844,
0.0381779,
0.036316,
0.034499,
0.032727,
0.0310001,
0.0293186,
0.0276826,
0.0260923,
0.0245478,
0.0230492,
0.0215968,
0.0201906,
0.0188308,
0.0175175,
0.0162509,
0.0150311,
0.0138581,
0.0127322,
0.0116533,
0.0106217,
0.00963736,
0.00870045,
0.00781104,
0.00696922,
0.00617507,
0.00542867,
0.00473008,
0.00407937,
0.00347661,
0.00292186,
0.00241517,
0.00195659,
0.00154616,
0.00118392,
0.00086991,
0.000604158,
0.000386689,
0.000217525,
9.66816e-05,
2.4171e-05,
0
};
} // FreeDV

413
libfreedv/kiss_fft.cpp Normal file
View File

@ -0,0 +1,413 @@
/*
Copyright (c) 2003-2010, Mark Borgerding
All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
* Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.
* 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.
* 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.
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.
*/
#include "_kiss_fft_guts.h"
/* The guts header contains all the multiplication and addition macros that are defined for
fixed or floating point complex numbers. It also delares the kf_ internal functions.
*/
namespace FreeDV
{
static void kf_bfly2(
kiss_fft_cpx * Fout,
const std::size_t fstride,
const kiss_fft_cfg st,
int m
)
{
kiss_fft_cpx * Fout2;
kiss_fft_cpx * tw1 = st->twiddles;
kiss_fft_cpx t;
Fout2 = Fout + m;
do{
C_FIXDIV(*Fout,2); C_FIXDIV(*Fout2,2);
C_MUL (t, *Fout2 , *tw1);
tw1 += fstride;
C_SUB( *Fout2 , *Fout , t );
C_ADDTO( *Fout , t );
++Fout2;
++Fout;
}while (--m);
}
static void kf_bfly4(
kiss_fft_cpx * Fout,
const std::size_t fstride,
const kiss_fft_cfg st,
const std::size_t m
)
{
kiss_fft_cpx *tw1,*tw2,*tw3;
kiss_fft_cpx scratch[6];
std::size_t k=m;
const std::size_t m2=2*m;
const std::size_t m3=3*m;
tw3 = tw2 = tw1 = st->twiddles;
do {
C_FIXDIV(*Fout,4); C_FIXDIV(Fout[m],4); C_FIXDIV(Fout[m2],4); C_FIXDIV(Fout[m3],4);
C_MUL(scratch[0],Fout[m] , *tw1 );
C_MUL(scratch[1],Fout[m2] , *tw2 );
C_MUL(scratch[2],Fout[m3] , *tw3 );
C_SUB( scratch[5] , *Fout, scratch[1] );
C_ADDTO(*Fout, scratch[1]);
C_ADD( scratch[3] , scratch[0] , scratch[2] );
C_SUB( scratch[4] , scratch[0] , scratch[2] );
C_SUB( Fout[m2], *Fout, scratch[3] );
tw1 += fstride;
tw2 += fstride*2;
tw3 += fstride*3;
C_ADDTO( *Fout , scratch[3] );
if(st->inverse) {
Fout[m].r = scratch[5].r - scratch[4].i;
Fout[m].i = scratch[5].i + scratch[4].r;
Fout[m3].r = scratch[5].r + scratch[4].i;
Fout[m3].i = scratch[5].i - scratch[4].r;
}else{
Fout[m].r = scratch[5].r + scratch[4].i;
Fout[m].i = scratch[5].i - scratch[4].r;
Fout[m3].r = scratch[5].r - scratch[4].i;
Fout[m3].i = scratch[5].i + scratch[4].r;
}
++Fout;
}while(--k);
}
static void kf_bfly3(
kiss_fft_cpx * Fout,
const std::size_t fstride,
const kiss_fft_cfg st,
std::size_t m
)
{
std::size_t k=m;
const std::size_t m2 = 2*m;
kiss_fft_cpx *tw1,*tw2;
kiss_fft_cpx scratch[5];
kiss_fft_cpx epi3;
epi3 = st->twiddles[fstride*m];
tw1=tw2=st->twiddles;
do{
C_FIXDIV(*Fout,3); C_FIXDIV(Fout[m],3); C_FIXDIV(Fout[m2],3);
C_MUL(scratch[1],Fout[m] , *tw1);
C_MUL(scratch[2],Fout[m2] , *tw2);
C_ADD(scratch[3],scratch[1],scratch[2]);
C_SUB(scratch[0],scratch[1],scratch[2]);
tw1 += fstride;
tw2 += fstride*2;
Fout[m].r = Fout->r - HALF_OF(scratch[3].r);
Fout[m].i = Fout->i - HALF_OF(scratch[3].i);
C_MULBYSCALAR( scratch[0] , epi3.i );
C_ADDTO(*Fout,scratch[3]);
Fout[m2].r = Fout[m].r + scratch[0].i;
Fout[m2].i = Fout[m].i - scratch[0].r;
Fout[m].r -= scratch[0].i;
Fout[m].i += scratch[0].r;
++Fout;
}while(--k);
}
static void kf_bfly5(
kiss_fft_cpx * Fout,
const std::size_t fstride,
const kiss_fft_cfg st,
int m
)
{
kiss_fft_cpx *Fout0,*Fout1,*Fout2,*Fout3,*Fout4;
int u;
kiss_fft_cpx scratch[13];
kiss_fft_cpx * twiddles = st->twiddles;
kiss_fft_cpx *tw;
kiss_fft_cpx ya,yb;
ya = twiddles[fstride*m];
yb = twiddles[fstride*2*m];
Fout0=Fout;
Fout1=Fout0+m;
Fout2=Fout0+2*m;
Fout3=Fout0+3*m;
Fout4=Fout0+4*m;
tw=st->twiddles;
for ( u=0; u<m; ++u ) {
C_FIXDIV( *Fout0,5); C_FIXDIV( *Fout1,5); C_FIXDIV( *Fout2,5); C_FIXDIV( *Fout3,5); C_FIXDIV( *Fout4,5);
scratch[0] = *Fout0;
C_MUL(scratch[1] ,*Fout1, tw[u*fstride]);
C_MUL(scratch[2] ,*Fout2, tw[2*u*fstride]);
C_MUL(scratch[3] ,*Fout3, tw[3*u*fstride]);
C_MUL(scratch[4] ,*Fout4, tw[4*u*fstride]);
C_ADD( scratch[7],scratch[1],scratch[4]);
C_SUB( scratch[10],scratch[1],scratch[4]);
C_ADD( scratch[8],scratch[2],scratch[3]);
C_SUB( scratch[9],scratch[2],scratch[3]);
Fout0->r += scratch[7].r + scratch[8].r;
Fout0->i += scratch[7].i + scratch[8].i;
scratch[5].r = scratch[0].r + S_MUL(scratch[7].r,ya.r) + S_MUL(scratch[8].r,yb.r);
scratch[5].i = scratch[0].i + S_MUL(scratch[7].i,ya.r) + S_MUL(scratch[8].i,yb.r);
scratch[6].r = S_MUL(scratch[10].i,ya.i) + S_MUL(scratch[9].i,yb.i);
scratch[6].i = -S_MUL(scratch[10].r,ya.i) - S_MUL(scratch[9].r,yb.i);
C_SUB(*Fout1,scratch[5],scratch[6]);
C_ADD(*Fout4,scratch[5],scratch[6]);
scratch[11].r = scratch[0].r + S_MUL(scratch[7].r,yb.r) + S_MUL(scratch[8].r,ya.r);
scratch[11].i = scratch[0].i + S_MUL(scratch[7].i,yb.r) + S_MUL(scratch[8].i,ya.r);
scratch[12].r = - S_MUL(scratch[10].i,yb.i) + S_MUL(scratch[9].i,ya.i);
scratch[12].i = S_MUL(scratch[10].r,yb.i) - S_MUL(scratch[9].r,ya.i);
C_ADD(*Fout2,scratch[11],scratch[12]);
C_SUB(*Fout3,scratch[11],scratch[12]);
++Fout0;++Fout1;++Fout2;++Fout3;++Fout4;
}
}
/* perform the butterfly for one stage of a mixed radix FFT */
static void kf_bfly_generic(
kiss_fft_cpx * Fout,
const std::size_t fstride,
const kiss_fft_cfg st,
int m,
int p
)
{
int u,k,q1,q;
kiss_fft_cpx * twiddles = st->twiddles;
kiss_fft_cpx t;
int Norig = st->nfft;
kiss_fft_cpx * scratch = (kiss_fft_cpx*)KISS_FFT_TMP_ALLOC(sizeof(kiss_fft_cpx)*p);
for ( u=0; u<m; ++u ) {
k=u;
for ( q1=0 ; q1<p ; ++q1 ) {
scratch[q1] = Fout[ k ];
C_FIXDIV(scratch[q1],p);
k += m;
}
k=u;
for ( q1=0 ; q1<p ; ++q1 ) {
int twidx=0;
Fout[ k ] = scratch[0];
for (q=1;q<p;++q ) {
twidx += fstride * k;
if (twidx>=Norig) twidx-=Norig;
C_MUL(t,scratch[q] , twiddles[twidx] );
C_ADDTO( Fout[ k ] ,t);
}
k += m;
}
}
KISS_FFT_TMP_FREE(scratch);
}
static
void kf_work(
kiss_fft_cpx * Fout,
const kiss_fft_cpx * f,
const std::size_t fstride,
int in_stride,
int * factors,
const kiss_fft_cfg st
)
{
kiss_fft_cpx * Fout_beg=Fout;
const int p=*factors++; /* the radix */
const int m=*factors++; /* stage's fft length/p */
const kiss_fft_cpx * Fout_end = Fout + p*m;
#ifdef _OPENMP
// use openmp extensions at the
// top-level (not recursive)
if (fstride==1 && p<=5)
{
int k;
// execute the p different work units in different threads
# pragma omp parallel for
for (k=0;k<p;++k)
kf_work( Fout +k*m, f+ fstride*in_stride*k,fstride*p,in_stride,factors,st);
// all threads have joined by this point
switch (p) {
case 2: kf_bfly2(Fout,fstride,st,m); break;
case 3: kf_bfly3(Fout,fstride,st,m); break;
case 4: kf_bfly4(Fout,fstride,st,m); break;
case 5: kf_bfly5(Fout,fstride,st,m); break;
default: kf_bfly_generic(Fout,fstride,st,m,p); break;
}
return;
}
#endif
if (m==1) {
do{
*Fout = *f;
f += fstride*in_stride;
}while(++Fout != Fout_end );
}else{
do{
// recursive call:
// DFT of size m*p performed by doing
// p instances of smaller DFTs of size m,
// each one takes a decimated version of the input
kf_work( Fout , f, fstride*p, in_stride, factors,st);
f += fstride*in_stride;
}while( (Fout += m) != Fout_end );
}
Fout=Fout_beg;
// recombine the p smaller DFTs
switch (p) {
case 2: kf_bfly2(Fout,fstride,st,m); break;
case 3: kf_bfly3(Fout,fstride,st,m); break;
case 4: kf_bfly4(Fout,fstride,st,m); break;
case 5: kf_bfly5(Fout,fstride,st,m); break;
default: kf_bfly_generic(Fout,fstride,st,m,p); break;
}
}
/* facbuf is populated by p1,m1,p2,m2, ...
where
p[i] * m[i] = m[i-1]
m0 = n */
static
void kf_factor(int n,int * facbuf)
{
int p=4;
double floor_sqrt;
floor_sqrt = floorf( sqrtf((double)n) );
/*factor out powers of 4, powers of 2, then any remaining primes */
do {
while (n % p) {
switch (p) {
case 4: p = 2; break;
case 2: p = 3; break;
default: p += 2; break;
}
if (p > floor_sqrt)
p = n; /* no more factors, skip to end */
}
n /= p;
*facbuf++ = p;
*facbuf++ = n;
} while (n > 1);
}
/*
*
* User-callable function to allocate all necessary storage space for the fft.
*
* The return value is a contiguous block of memory, allocated with malloc. As such,
* It can be freed with free(), rather than a kiss_fft-specific function.
* */
kiss_fft_cfg kiss_fft_alloc(int nfft,int inverse_fft,void * mem, std::size_t * lenmem )
{
kiss_fft_cfg st=NULL;
std::size_t memneeded = sizeof(struct kiss_fft_state)
+ sizeof(kiss_fft_cpx)*(nfft-1); /* twiddle factors*/
if ( lenmem==NULL ) {
st = ( kiss_fft_cfg)KISS_FFT_MALLOC( memneeded );
}else{
if (mem != NULL && *lenmem >= memneeded)
st = (kiss_fft_cfg)mem;
*lenmem = memneeded;
}
if (st) {
int i;
st->nfft=nfft;
st->inverse = inverse_fft;
for (i=0;i<nfft;++i) {
const double pi=3.141592653589793238462643383279502884197169399375105820974944;
double phase = -2*pi*i / nfft;
if (st->inverse)
phase *= -1;
kf_cexp(st->twiddles+i, phase );
}
kf_factor(nfft,st->factors);
}
return st;
}
void kiss_fft_stride(kiss_fft_cfg st,const kiss_fft_cpx *fin,kiss_fft_cpx *fout,int in_stride)
{
if (fin == fout) {
//NOTE: this is not really an in-place FFT algorithm.
//It just performs an out-of-place FFT into a temp buffer
kiss_fft_cpx * tmpbuf = (kiss_fft_cpx*)KISS_FFT_TMP_ALLOC( sizeof(kiss_fft_cpx)*st->nfft);
kf_work(tmpbuf,fin,1,in_stride, st->factors,st);
memcpy(fout,tmpbuf,sizeof(kiss_fft_cpx)*st->nfft);
KISS_FFT_TMP_FREE(tmpbuf);
}else{
kf_work( fout, fin, 1,in_stride, st->factors,st );
}
}
void kiss_fft(kiss_fft_cfg cfg,const kiss_fft_cpx *fin,kiss_fft_cpx *fout)
{
kiss_fft_stride(cfg,fin,fout,1);
}
void kiss_fft_cleanup(void)
{
// nothing needed any more
}
int kiss_fft_next_fast_size(int n)
{
while(1) {
int m=n;
while ( (m%2) == 0 ) m/=2;
while ( (m%3) == 0 ) m/=3;
while ( (m%5) == 0 ) m/=5;
if (m<=1)
break; /* n is completely factorable by twos, threes, and fives */
n++;
}
return n;
}
} // FreeDV

View File

@ -20,6 +20,9 @@
in the tools/ directory.
*/
namespace FreeDV
{
#ifdef USE_SIMD
# include <xmmintrin.h>
# define kiss_fft_scalar __m128
@ -45,8 +48,6 @@
# endif
#endif
namespace FreeDV
{
typedef struct {
kiss_fft_scalar r;

View File

@ -39,6 +39,6 @@ void kiss_fftri(kiss_fftr_cfg cfg,const kiss_fft_cpx *freqdata,kiss_fft_scalar *
} // FreeDV
#define kiss_fftr_free free
//#define kiss_fftr_free free
#endif

110
libfreedv/linreg.cpp Normal file
View File

@ -0,0 +1,110 @@
/*---------------------------------------------------------------------------*\
FILE........: linreg.c
AUTHOR......: David Rowe
DATE CREATED: April 2015
Linear regression C module based on:
http://stackoverflow.com/questions/5083465/fast-efficient-least-squares-fit-algorithm-in-c
Use:
$ gcc linreg.c -o linreg -D__UNITTEST__ -Wall
$ ./linreg
Then compare yfit results with octave/tlinreg.m
\*---------------------------------------------------------------------------*/
/*
Copyright (C) 2015 David Rowe
All rights reserved.
This program is free software; you can redistribute it and/or modify
it under the terms of the GNU Lesser General Public License version 2.1, as
published by the Free Software Foundation. This program is
distributed in the hope that it will be useful, but WITHOUT ANY
WARRANTY; without even the implied warranty of MERCHANTABILITY or
FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public
License for more details.
You should have received a copy of the GNU Lesser General Public License
along with this program; if not, see <http://www.gnu.org/licenses/>.
*/
#include <stdio.h>
#include <stdlib.h>
#include <math.h>
#include "linreg.h"
#include "codec2/comp_prim.h"
namespace FreeDV
{
void linreg(COMP *m, COMP *b, float x[], COMP y[], int n)
{
float sumx = 0.0; /* sum of x */
float sumx2 = 0.0; /* sum of x^2 */
COMP sumxy = {0.0,0.0}; /* sum of x * y */
COMP sumy = {0.0,0.0}; /* sum of y */
COMP sumy2 = {0.0,0.0}; /* sum of y**2 */
float denom;
COMP zero;
int i;
for (i=0; i<n; i++) {
sumx += x[i];
sumx2 += x[i]*x[i];
sumxy = cadd(sumxy, fcmult(x[i], y[i]));
sumy = cadd(sumy, y[i]);
sumy2 = cadd(sumy2, cmult(y[i],y[i]));
}
denom = (n * sumx2 - sumx*sumx);
if (denom == 0) {
/* singular matrix. can't solve the problem */
zero.real = 0.0; zero.imag = 0.0;
*m = zero;
*b = zero;
} else {
*m = fcmult(1.0/denom, cadd(fcmult(n, sumxy), cneg(fcmult(sumx,sumy))));
*b = fcmult(1.0/denom, cadd(fcmult(sumx2,sumy), cneg(fcmult(sumx, sumxy))));
}
}
#ifdef __UNITTEST__
static float x[] = {1, 2, 7, 8};
static COMP y[] = {
{-0.70702, 0.70708},
{-0.77314, 0.63442},
{-0.98083, 0.19511},
{-0.99508, 0.09799}
};
int main(void) {
float x1;
COMP m,b,yfit;
linreg(&m, &b, x, y, sizeof(x)/sizeof(float));
for (x1=1; x1<=8; x1++) {
yfit = cadd(fcmult(x1, m),b);
printf("%f %f\n", yfit.real, yfit.imag);
}
return 0;
}
#endif
} // FreeDV

40
libfreedv/linreg.h Normal file
View File

@ -0,0 +1,40 @@
/*---------------------------------------------------------------------------*\
FILE........: linreg.h
AUTHOR......: David Rowe
DATE CREATED: April 2015
Linear regression C module based
\*---------------------------------------------------------------------------*/
/*
Copyright (C) 2015 David Rowe
All rights reserved.
This program is free software; you can redistribute it and/or modify
it under the terms of the GNU Lesser General Public License version 2.1, as
published by the Free Software Foundation. This program is
distributed in the hope that it will be useful, but WITHOUT ANY
WARRANTY; without even the implied warranty of MERCHANTABILITY or
FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public
License for more details.
You should have received a copy of the GNU Lesser General Public License
along with this program; if not, see <http://www.gnu.org/licenses/>.
*/
#ifndef __LINREG__
#define __LINREG__
#include "codec2/comp.h"
namespace FreeDV
{
void linreg(COMP *m, COMP *b, float x[], COMP y[], int n);
} // FreeDV
#endif

57
libfreedv/machdep.h Normal file
View File

@ -0,0 +1,57 @@
/*---------------------------------------------------------------------------*\
FILE........: machdep.h
AUTHOR......: David Rowe
DATE CREATED: May 2 2013
Machine dependant functions, e.g. profiling that requires access to a clock
counter register.
\*---------------------------------------------------------------------------*/
/*
Copyright (C) 2013 David Rowe
All rights reserved.
This program is free software; you can redistribute it and/or modify
it under the terms of the GNU Lesser General Public License version 2.1, as
published by the Free Software Foundation. This program is
distributed in the hope that it will be useful, but WITHOUT ANY
WARRANTY; without even the implied warranty of MERCHANTABILITY or
FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public
License for more details.
You should have received a copy of the GNU Lesser General Public License
along with this program; if not, see <http://www.gnu.org/licenses/>.
*/
#ifndef __MACHDEP__
#define __MACHDEP__
namespace FreeDV
{
#ifdef PROFILE
#define PROFILE_VAR(...) unsigned int __VA_ARGS__
#define PROFILE_SAMPLE(timestamp) timestamp = machdep_profile_sample()
#define PROFILE_SAMPLE_AND_LOG(timestamp, prev_timestamp, label) \
timestamp = machdep_profile_sample_and_log(prev_timestamp, label)
#define PROFILE_SAMPLE_AND_LOG2(prev_timestamp, label) \
machdep_profile_sample_and_log(prev_timestamp, label)
#else
#define PROFILE_VAR(...)
#define PROFILE_SAMPLE(timestamp)
#define PROFILE_SAMPLE_AND_LOG(timestamp, prev_timestamp, label)
#define PROFILE_SAMPLE_AND_LOG2(prev_timestamp, label)
#endif
void machdep_profile_init(void);
void machdep_profile_reset(void);
unsigned int machdep_profile_sample(void);
unsigned int machdep_profile_sample_and_log(unsigned int start, char s[]);
void machdep_profile_print_logged_samples(void);
} // FreeDV
#endif

View File

@ -29,8 +29,8 @@
#define __MODEMPROBE_H
#include <stdint.h>
#include <stdlib.h>
#include <complex.h>
#include "comp.h"
#include <complex>
#include "codec2/comp.h"
namespace FreeDV
{
@ -103,28 +103,47 @@ static inline void modem_probe_samp_cft(char *tracename,complex float samp[],siz
#else
static inline void modem_probe_init(char *modname,char *runname){
return;
static inline void modem_probe_init(const char *modname, char *runname)
{
(void) modname;
(void) runname;
return;
}
static inline void modem_probe_close(){
return;
static inline void modem_probe_close() {
return;
}
static inline void modem_probe_samp_i(char *name,int samp[],size_t sampcnt){
return;
static inline void modem_probe_samp_i(const char *name, int samp[], std::size_t sampcnt)
{
(void) name;
(void) samp;
(void) sampcnt;
return;
}
static inline void modem_probe_samp_f(char *name,float samp[],size_t cnt){
return;
static inline void modem_probe_samp_f(const char *name, float samp[], std::size_t cnt)
{
(void) name;
(void) samp;
(void) cnt;
return;
}
static inline void modem_probe_samp_c(char *name,COMP samp[],size_t cnt){
return;
static inline void modem_probe_samp_c(const char *name, COMP samp[], std::size_t cnt)
{
(void) name;
(void) samp;
(void) cnt;
return;
}
static inline void modem_probe_samp_cft(char *name,complex float samp[],size_t cnt){
return;
static inline void modem_probe_samp_cft(const char *name, std::complex<float> samp[], std::size_t cnt)
{
(void) name;
(void) samp;
(void) cnt;
return;
}
#endif

57
libfreedv/os.h Normal file
View File

@ -0,0 +1,57 @@
/* Generate using fir1(47,1/2) in Octave */
namespace FreeDV
{
static const float fdmdv_os_filter[]= {
-0.0008215855034550382,
-0.0007833023901802921,
0.001075563790768233,
0.001199092367787555,
-0.001765309502928316,
-0.002055372115328064,
0.002986877604154257,
0.003462567920638414,
-0.004856570111126334,
-0.005563143845031497,
0.007533613299748122,
0.008563932468880897,
-0.01126857129039911,
-0.01280782411693687,
0.01651443896361847,
0.01894875110322284,
-0.02421604439474981,
-0.02845107338464062,
0.03672973563400258,
0.04542046150312214,
-0.06189165826716491,
-0.08721876380763803,
0.1496157094199961,
0.4497962274137046,
0.4497962274137046,
0.1496157094199961,
-0.08721876380763803,
-0.0618916582671649,
0.04542046150312216,
0.03672973563400257,
-0.02845107338464062,
-0.02421604439474984,
0.01894875110322284,
0.01651443896361848,
-0.01280782411693687,
-0.0112685712903991,
0.008563932468880899,
0.007533613299748123,
-0.005563143845031501,
-0.004856570111126346,
0.003462567920638419,
0.002986877604154259,
-0.002055372115328063,
-0.001765309502928318,
0.001199092367787557,
0.001075563790768233,
-0.0007833023901802925,
-0.0008215855034550383
};
} // FreeDV

46
libfreedv/pilot_coeff.h Normal file
View File

@ -0,0 +1,46 @@
/* Generated by pilot_coeff_file() Octave function */
// const removed since this provides gain
// on the STM32F4 platform
namespace FreeDV
{
#ifdef CORTEX_M4
/* const */ float pilot_coeff[]={
#else
const float pilot_coeff[]={
#endif
0.00223001,
0.00301037,
0.00471258,
0.0075934,
0.0118145,
0.0174153,
0.0242969,
0.0322204,
0.0408199,
0.0496286,
0.0581172,
0.0657392,
0.0719806,
0.0764066,
0.0787022,
0.0787022,
0.0764066,
0.0719806,
0.0657392,
0.0581172,
0.0496286,
0.0408199,
0.0322204,
0.0242969,
0.0174153,
0.0118145,
0.0075934,
0.00471258,
0.00301037,
0.00223001
};
} // FreeDV

11
libfreedv/pilots_coh.h Normal file
View File

@ -0,0 +1,11 @@
/* Generated by write_pilot_file() Octave function */
namespace FreeDV
{
float pilots_coh[][PILOTS_NC]={
{ 1.000000, -1.000000, 1.000000, -1.000000, 1.000000, -1.000000, -1.000000},
{ -1.000000, 1.000000, 1.000000, -1.000000, 1.000000, 1.000000, 1.000000}
};
} // FreeDV

969
libfreedv/rn.h Normal file
View File

@ -0,0 +1,969 @@
/* Generated by rn_file() Octave function */
namespace FreeDV
{
const float gt_alpha5_root[]={
2.86997e-05,
2.2286e-05,
1.82863e-05,
1.42303e-05,
1.04905e-05,
6.70859e-06,
3.05918e-06,
-6.22187e-07,
-4.22748e-06,
-7.85603e-06,
-1.14317e-05,
-1.50227e-05,
-1.85712e-05,
-2.21275e-05,
-2.56455e-05,
-2.91642e-05,
-3.26453e-05,
-3.61199e-05,
-3.95556e-05,
-4.29778e-05,
-4.63581e-05,
-4.97179e-05,
-5.3032e-05,
-5.63184e-05,
-5.95548e-05,
-6.27565e-05,
-6.59032e-05,
-6.90085e-05,
-7.20538e-05,
-7.50509e-05,
-7.7983e-05,
-8.08605e-05,
-8.36678e-05,
-8.64141e-05,
-8.9085e-05,
-9.16888e-05,
-9.42119e-05,
-9.66619e-05,
-9.9026e-05,
-0.000101311,
-0.000103505,
-0.000105614,
-0.000107627,
-0.00010955,
-0.000111372,
-0.000113099,
-0.00011472,
-0.000116241,
-0.000117652,
-0.000118959,
-0.000120152,
-0.000121235,
-0.000122201,
-0.000123053,
-0.000123784,
-0.000124397,
-0.000124884,
-0.00012525,
-0.000125487,
-0.000125598,
-0.000125578,
-0.000125428,
-0.000125145,
-0.000124729,
-0.000124185,
-0.000123518,
-0.000122709,
-0.000121766,
-0.000120685,
-0.000119471,
-0.000118119,
-0.000116633,
-0.000115009,
-0.000113251,
-0.000111356,
-0.000109326,
-0.00010716,
-0.00010486,
-0.000102424,
-9.98553e-05,
-9.71528e-05,
-9.43199e-05,
-9.13551e-05,
-8.82623e-05,
-8.50404e-05,
-8.16936e-05,
-7.82211e-05,
-7.46271e-05,
-7.09109e-05,
-6.70773e-05,
-6.31256e-05,
-5.90607e-05,
-5.48823e-05,
-5.05954e-05,
-4.62001e-05,
-4.17016e-05,
-3.71002e-05,
-3.24015e-05,
-2.7606e-05,
-2.27195e-05,
-1.77428e-05,
-1.2682e-05,
-7.53795e-06,
-2.31702e-06,
2.97965e-06,
8.34567e-06,
1.37796e-05,
1.9275e-05,
2.483e-05,
3.04382e-05,
3.60975e-05,
4.18011e-05,
4.75467e-05,
5.33273e-05,
5.91403e-05,
6.49787e-05,
7.08393e-05,
7.67152e-05,
8.26029e-05,
8.84957e-05,
9.43895e-05,
0.000100278,
0.000106157,
0.00011202,
0.000117864,
0.000123681,
0.000129468,
0.000135218,
0.000140929,
0.000146583,
0.000152183,
0.000157725,
0.000163202,
0.000168608,
0.000173938,
0.000179183,
0.00018434,
0.0001894,
0.00019436,
0.000199211,
0.000203949,
0.000208568,
0.000213063,
0.000217426,
0.000221654,
0.00022574,
0.000229678,
0.000233463,
0.000237089,
0.000240551,
0.000243843,
0.000246959,
0.000249895,
0.000252644,
0.000255202,
0.000257562,
0.000259721,
0.000261672,
0.000263411,
0.000264933,
0.000266234,
0.000267308,
0.000268152,
0.00026876,
0.000269128,
0.000269253,
0.000269129,
0.000268754,
0.000268123,
0.000267232,
0.000266079,
0.000264658,
0.000262968,
0.000261006,
0.000258767,
0.000256251,
0.000253453,
0.000250373,
0.000247007,
0.000243354,
0.000239412,
0.00023518,
0.000230655,
0.000225837,
0.000220723,
0.000215314,
0.000209608,
0.000203605,
0.000197304,
0.000190706,
0.000183812,
0.000176621,
0.000169145,
0.000161363,
0.000153275,
0.000144895,
0.000136224,
0.000127266,
0.00011802,
0.000108491,
9.8679e-05,
8.85877e-05,
7.82196e-05,
6.7577e-05,
5.66636e-05,
4.54822e-05,
3.40369e-05,
2.23311e-05,
1.03695e-05,
-1.844e-06,
-1.43041e-05,
-2.70061e-05,
-3.99444e-05,
-5.31139e-05,
-6.65082e-05,
-8.01218e-05,
-9.39481e-05,
-0.000107981,
-0.000122213,
-0.000136638,
-0.000151248,
-0.000166036,
-0.000180995,
-0.000196115,
-0.00021139,
-0.000226811,
-0.000242369,
-0.000258056,
-0.000273861,
-0.000289776,
-0.000305792,
-0.000321898,
-0.000338084,
-0.000354342,
-0.00037066,
-0.000387027,
-0.000403434,
-0.00041987,
-0.000436324,
-0.000452784,
-0.00046924,
-0.00048568,
-0.000502091,
-0.000518464,
-0.000534785,
-0.000551043,
-0.000567225,
-0.000583319,
-0.000599314,
-0.000615196,
-0.000630955,
-0.000646575,
-0.000662049,
-0.000677361,
-0.000692506,
-0.000707464,
-0.00072229,
-0.000736922,
-0.000751266,
-0.000765372,
-0.000779217,
-0.000792798,
-0.000806094,
-0.000819098,
-0.000831793,
-0.000844168,
-0.000856207,
-0.000867898,
-0.000879227,
-0.00089018,
-0.000900744,
-0.000910906,
-0.000920652,
-0.00092997,
-0.000938844,
-0.000947263,
-0.000955214,
-0.000962682,
-0.000969654,
-0.000976119,
-0.000982062,
-0.00098747,
-0.000992332,
-0.000996634,
-0.00100036,
-0.00100351,
-0.00100606,
-0.001008,
-0.00100932,
-0.00101,
-0.00101005,
-0.00100943,
-0.00100816,
-0.0010062,
-0.00100356,
-0.00100021,
-0.000996162,
-0.000991392,
-0.000985892,
-0.000979654,
-0.000972668,
-0.000964925,
-0.000956415,
-0.000947131,
-0.000937065,
-0.000926208,
-0.000914552,
-0.00090209,
-0.000888816,
-0.000874721,
-0.0008598,
-0.000844046,
-0.000827453,
-0.000810015,
-0.000791726,
-0.000772581,
-0.000752576,
-0.000731704,
-0.000709965,
-0.00068735,
-0.000663865,
-0.000639509,
-0.000614269,
-0.000588146,
-0.000561139,
-0.000533246,
-0.000504468,
-0.000474802,
-0.000444251,
-0.000412813,
-0.00038049,
-0.000347281,
-0.000313189,
-0.000278215,
-0.000242361,
-0.000205629,
-0.000168024,
-0.000129546,
-9.02024e-05,
-4.99954e-05,
-8.93026e-06,
3.2988e-05,
7.57537e-05,
0.000119361,
0.000163804,
0.000209075,
0.000255167,
0.000302074,
0.000349786,
0.000398297,
0.000447596,
0.000497676,
0.000548526,
0.000600136,
0.000652497,
0.000705598,
0.000759427,
0.000813972,
0.000869223,
0.000925166,
0.000981789,
0.00103908,
0.00109702,
0.00115561,
0.00121482,
0.00127464,
0.00133505,
0.00139605,
0.00145762,
0.00151973,
0.00158238,
0.00164555,
0.00170922,
0.00177337,
0.00183799,
0.00190305,
0.00196854,
0.00203445,
0.00210075,
0.00216742,
0.00223445,
0.00230181,
0.00236949,
0.00243747,
0.00250572,
0.00257423,
0.00264296,
0.00271192,
0.00278107,
0.00285039,
0.00291986,
0.00298947,
0.00305918,
0.00312898,
0.00319884,
0.00326874,
0.00333866,
0.00340857,
0.00347846,
0.00354831,
0.00361808,
0.00368775,
0.00375731,
0.00382673,
0.00389599,
0.00396506,
0.00403393,
0.00410256,
0.00417094,
0.00423904,
0.00430684,
0.00437431,
0.00444144,
0.0045082,
0.00457457,
0.00464052,
0.00470603,
0.00477108,
0.00483565,
0.00489972,
0.00496325,
0.00502623,
0.00508865,
0.00515046,
0.00521166,
0.00527223,
0.00533213,
0.00539135,
0.00544987,
0.00550766,
0.00556472,
0.005621,
0.00567651,
0.00573121,
0.00578508,
0.00583811,
0.00589028,
0.00594157,
0.00599196,
0.00604143,
0.00608996,
0.00613754,
0.00618415,
0.00622977,
0.00627439,
0.00631798,
0.00636054,
0.00640204,
0.0064425,
0.00648186,
0.00652009,
0.00655722,
0.00659322,
0.00662808,
0.00666179,
0.00669433,
0.00672571,
0.00675589,
0.00678488,
0.00681266,
0.00683921,
0.00686454,
0.00688863,
0.00691147,
0.00693305,
0.00695336,
0.0069724,
0.00699016,
0.00700663,
0.00702181,
0.00703569,
0.00704826,
0.00705952,
0.00706947,
0.00707809,
0.0070854,
0.00709138,
0.00709604,
0.00709937,
0.00710136,
0.00710203,
0.00710136,
0.00709937,
0.00709604,
0.00709138,
0.0070854,
0.00707809,
0.00706947,
0.00705952,
0.00704826,
0.00703569,
0.00702181,
0.00700663,
0.00699016,
0.0069724,
0.00695336,
0.00693305,
0.00691147,
0.00688863,
0.00686454,
0.00683921,
0.00681266,
0.00678488,
0.00675589,
0.00672571,
0.00669433,
0.00666179,
0.00662808,
0.00659322,
0.00655722,
0.00652009,
0.00648186,
0.0064425,
0.00640204,
0.00636054,
0.00631798,
0.00627439,
0.00622977,
0.00618415,
0.00613754,
0.00608996,
0.00604143,
0.00599196,
0.00594157,
0.00589028,
0.00583811,
0.00578508,
0.00573121,
0.00567651,
0.005621,
0.00556472,
0.00550766,
0.00544987,
0.00539135,
0.00533213,
0.00527223,
0.00521166,
0.00515046,
0.00508865,
0.00502623,
0.00496325,
0.00489972,
0.00483565,
0.00477108,
0.00470603,
0.00464052,
0.00457457,
0.0045082,
0.00444144,
0.00437431,
0.00430684,
0.00423904,
0.00417094,
0.00410256,
0.00403393,
0.00396506,
0.00389599,
0.00382673,
0.00375731,
0.00368775,
0.00361808,
0.00354831,
0.00347846,
0.00340857,
0.00333866,
0.00326874,
0.00319884,
0.00312898,
0.00305918,
0.00298947,
0.00291986,
0.00285039,
0.00278107,
0.00271192,
0.00264296,
0.00257423,
0.00250572,
0.00243747,
0.00236949,
0.00230181,
0.00223445,
0.00216742,
0.00210075,
0.00203445,
0.00196854,
0.00190305,
0.00183799,
0.00177337,
0.00170922,
0.00164555,
0.00158238,
0.00151973,
0.00145762,
0.00139605,
0.00133505,
0.00127464,
0.00121482,
0.00115561,
0.00109702,
0.00103908,
0.000981789,
0.000925166,
0.000869223,
0.000813972,
0.000759427,
0.000705598,
0.000652497,
0.000600136,
0.000548526,
0.000497676,
0.000447596,
0.000398297,
0.000349786,
0.000302074,
0.000255167,
0.000209075,
0.000163804,
0.000119361,
7.57537e-05,
3.2988e-05,
-8.93026e-06,
-4.99954e-05,
-9.02024e-05,
-0.000129546,
-0.000168024,
-0.000205629,
-0.000242361,
-0.000278215,
-0.000313189,
-0.000347281,
-0.00038049,
-0.000412813,
-0.000444251,
-0.000474802,
-0.000504468,
-0.000533246,
-0.000561139,
-0.000588146,
-0.000614269,
-0.000639509,
-0.000663865,
-0.00068735,
-0.000709965,
-0.000731704,
-0.000752576,
-0.000772581,
-0.000791726,
-0.000810015,
-0.000827453,
-0.000844046,
-0.0008598,
-0.000874721,
-0.000888816,
-0.00090209,
-0.000914552,
-0.000926208,
-0.000937065,
-0.000947131,
-0.000956415,
-0.000964925,
-0.000972668,
-0.000979654,
-0.000985892,
-0.000991392,
-0.000996162,
-0.00100021,
-0.00100356,
-0.0010062,
-0.00100816,
-0.00100943,
-0.00101005,
-0.00101,
-0.00100932,
-0.001008,
-0.00100606,
-0.00100351,
-0.00100036,
-0.000996634,
-0.000992332,
-0.00098747,
-0.000982062,
-0.000976119,
-0.000969654,
-0.000962682,
-0.000955214,
-0.000947263,
-0.000938844,
-0.00092997,
-0.000920652,
-0.000910906,
-0.000900744,
-0.00089018,
-0.000879227,
-0.000867898,
-0.000856207,
-0.000844168,
-0.000831793,
-0.000819098,
-0.000806094,
-0.000792798,
-0.000779217,
-0.000765372,
-0.000751266,
-0.000736922,
-0.00072229,
-0.000707464,
-0.000692506,
-0.000677361,
-0.000662049,
-0.000646575,
-0.000630955,
-0.000615196,
-0.000599314,
-0.000583319,
-0.000567225,
-0.000551043,
-0.000534785,
-0.000518464,
-0.000502091,
-0.00048568,
-0.00046924,
-0.000452784,
-0.000436324,
-0.00041987,
-0.000403434,
-0.000387027,
-0.00037066,
-0.000354342,
-0.000338084,
-0.000321898,
-0.000305792,
-0.000289776,
-0.000273861,
-0.000258056,
-0.000242369,
-0.000226811,
-0.00021139,
-0.000196115,
-0.000180995,
-0.000166036,
-0.000151248,
-0.000136638,
-0.000122213,
-0.000107981,
-9.39481e-05,
-8.01218e-05,
-6.65082e-05,
-5.31139e-05,
-3.99444e-05,
-2.70061e-05,
-1.43041e-05,
-1.844e-06,
1.03695e-05,
2.23311e-05,
3.40369e-05,
4.54822e-05,
5.66636e-05,
6.7577e-05,
7.82196e-05,
8.85877e-05,
9.8679e-05,
0.000108491,
0.00011802,
0.000127266,
0.000136224,
0.000144895,
0.000153275,
0.000161363,
0.000169145,
0.000176621,
0.000183812,
0.000190706,
0.000197304,
0.000203605,
0.000209608,
0.000215314,
0.000220723,
0.000225837,
0.000230655,
0.00023518,
0.000239412,
0.000243354,
0.000247007,
0.000250373,
0.000253453,
0.000256251,
0.000258767,
0.000261006,
0.000262968,
0.000264658,
0.000266079,
0.000267232,
0.000268123,
0.000268754,
0.000269129,
0.000269253,
0.000269128,
0.00026876,
0.000268152,
0.000267308,
0.000266234,
0.000264933,
0.000263411,
0.000261672,
0.000259721,
0.000257562,
0.000255202,
0.000252644,
0.000249895,
0.000246959,
0.000243843,
0.000240551,
0.000237089,
0.000233463,
0.000229678,
0.00022574,
0.000221654,
0.000217426,
0.000213063,
0.000208568,
0.000203949,
0.000199211,
0.00019436,
0.0001894,
0.00018434,
0.000179183,
0.000173938,
0.000168608,
0.000163202,
0.000157725,
0.000152183,
0.000146583,
0.000140929,
0.000135218,
0.000129468,
0.000123681,
0.000117864,
0.00011202,
0.000106157,
0.000100278,
9.43895e-05,
8.84957e-05,
8.26029e-05,
7.67152e-05,
7.08393e-05,
6.49787e-05,
5.91403e-05,
5.33273e-05,
4.75467e-05,
4.18011e-05,
3.60975e-05,
3.04382e-05,
2.483e-05,
1.9275e-05,
1.37796e-05,
8.34567e-06,
2.97965e-06,
-2.31702e-06,
-7.53795e-06,
-1.2682e-05,
-1.77428e-05,
-2.27195e-05,
-2.7606e-05,
-3.24015e-05,
-3.71002e-05,
-4.17016e-05,
-4.62001e-05,
-5.05954e-05,
-5.48823e-05,
-5.90607e-05,
-6.31256e-05,
-6.70773e-05,
-7.09109e-05,
-7.46271e-05,
-7.82211e-05,
-8.16936e-05,
-8.50404e-05,
-8.82623e-05,
-9.13551e-05,
-9.43199e-05,
-9.71528e-05,
-9.98553e-05,
-0.000102424,
-0.00010486,
-0.00010716,
-0.000109326,
-0.000111356,
-0.000113251,
-0.000115009,
-0.000116633,
-0.000118119,
-0.000119471,
-0.000120685,
-0.000121766,
-0.000122709,
-0.000123518,
-0.000124185,
-0.000124729,
-0.000125145,
-0.000125428,
-0.000125578,
-0.000125598,
-0.000125487,
-0.00012525,
-0.000124884,
-0.000124397,
-0.000123784,
-0.000123053,
-0.000122201,
-0.000121235,
-0.000120152,
-0.000118959,
-0.000117652,
-0.000116241,
-0.00011472,
-0.000113099,
-0.000111372,
-0.00010955,
-0.000107627,
-0.000105614,
-0.000103505,
-0.000101311,
-9.9026e-05,
-9.66619e-05,
-9.42119e-05,
-9.16888e-05,
-8.9085e-05,
-8.64141e-05,
-8.36678e-05,
-8.08605e-05,
-7.7983e-05,
-7.50509e-05,
-7.20538e-05,
-6.90085e-05,
-6.59032e-05,
-6.27565e-05,
-5.95548e-05,
-5.63184e-05,
-5.3032e-05,
-4.97179e-05,
-4.63581e-05,
-4.29778e-05,
-3.95556e-05,
-3.61199e-05,
-3.26453e-05,
-2.91642e-05,
-2.56455e-05,
-2.21275e-05,
-1.85712e-05,
-1.50227e-05,
-1.14317e-05,
-7.85603e-06,
-4.22748e-06,
-6.22187e-07,
3.05918e-06,
6.70859e-06,
1.04905e-05,
1.42303e-05,
1.82863e-05,
2.2286e-05
};
} // FreeDV

609
libfreedv/rn_coh.h Normal file
View File

@ -0,0 +1,609 @@
/* Generated by rn_file() Octave function */
namespace FreeDV
{
const float gt_alpha5_root_coh[]={
4.05576e-05,
2.58255e-05,
1.58964e-05,
5.78773e-06,
-3.71244e-06,
-1.33229e-05,
-2.2664e-05,
-3.20611e-05,
-4.12734e-05,
-5.04935e-05,
-5.9545e-05,
-6.85565e-05,
-7.73902e-05,
-8.6137e-05,
-9.46835e-05,
-0.000103097,
-0.000111281,
-0.000119289,
-0.000127034,
-0.000134559,
-0.000141789,
-0.000148756,
-0.000155393,
-0.000161723,
-0.000167689,
-0.000173315,
-0.00017854,
-0.000183382,
-0.000187794,
-0.000191793,
-0.000195333,
-0.000198429,
-0.000201038,
-0.000203173,
-0.000204797,
-0.000205922,
-0.000206515,
-0.00020659,
-0.000206117,
-0.000205109,
-0.000203541,
-0.000201427,
-0.000198743,
-0.000195505,
-0.000191693,
-0.000187324,
-0.000182382,
-0.000176885,
-0.000170822,
-0.00016421,
-0.000157041,
-0.000149335,
-0.000141089,
-0.000132323,
-0.000123038,
-0.000113258,
-0.000102985,
-9.22439e-05,
-8.10442e-05,
-6.94109e-05,
-5.73536e-05,
-4.49012e-05,
-3.20661e-05,
-1.88794e-05,
-5.35615e-06,
8.47105e-06,
2.25833e-05,
3.69472e-05,
5.15418e-05,
6.63317e-05,
8.12934e-05,
9.63895e-05,
0.000111594,
0.000126869,
0.000142183,
0.000157497,
0.000172781,
0.000187996,
0.000203111,
0.000218088,
0.000232892,
0.000247474,
0.000261806,
0.000275847,
0.000289559,
0.000302903,
0.000315839,
0.00032833,
0.000340339,
0.000351824,
0.000362751,
0.00037308,
0.000382774,
0.000391795,
0.000400108,
0.000407675,
0.000414464,
0.000420437,
0.000425565,
0.000429812,
0.000433151,
0.000435544,
0.000436975,
0.000437401,
0.000436865,
0.000435237,
0.00043246,
0.000428592,
0.000423608,
0.000417497,
0.00041024,
0.000401823,
0.000392231,
0.000381449,
0.000369471,
0.000356284,
0.000341885,
0.000326267,
0.00030943,
0.000291373,
0.000272099,
0.000251612,
0.000229921,
0.000207034,
0.000182964,
0.000157726,
0.000131338,
0.000103821,
7.51956e-05,
4.54842e-05,
1.4721e-05,
-1.7067e-05,
-4.98479e-05,
-8.35883e-05,
-0.000118248,
-0.00015379,
-0.000190167,
-0.000227336,
-0.000265248,
-0.000303856,
-0.000343104,
-0.000382942,
-0.00042331,
-0.000464152,
-0.000505403,
-0.000547003,
-0.000588883,
-0.000630979,
-0.000673218,
-0.000715533,
-0.000757849,
-0.000800092,
-0.000842187,
-0.000884054,
-0.000925613,
-0.000966788,
-0.00100749,
-0.00104765,
-0.00108717,
-0.00112597,
-0.00116397,
-0.00120108,
-0.0012372,
-0.00127227,
-0.00130617,
-0.00133884,
-0.00137017,
-0.00140008,
-0.00142848,
-0.00145528,
-0.0014804,
-0.00150374,
-0.00152522,
-0.00154475,
-0.00156225,
-0.00157763,
-0.00159081,
-0.00160171,
-0.00161024,
-0.00161633,
-0.0016199,
-0.00162088,
-0.00161917,
-0.00161472,
-0.00160744,
-0.00159729,
-0.00158419,
-0.00156807,
-0.00154888,
-0.00152655,
-0.00150103,
-0.00147227,
-0.00144021,
-0.00140482,
-0.00136604,
-0.00132384,
-0.00127818,
-0.00122903,
-0.00117635,
-0.00112013,
-0.00106033,
-0.000996946,
-0.000929956,
-0.000859348,
-0.000785117,
-0.000707261,
-0.000625779,
-0.00054068,
-0.000451952,
-0.000359651,
-0.000263788,
-0.00016436,
-6.13947e-05,
4.5076e-05,
0.000155016,
0.000268384,
0.000385134,
0.000505217,
0.000628582,
0.000755171,
0.000884923,
0.00101777,
0.00115366,
0.00129249,
0.00143421,
0.00157873,
0.00172596,
0.00187583,
0.00202822,
0.00218306,
0.00234023,
0.00249965,
0.00266119,
0.00282475,
0.00299023,
0.00315749,
0.00332643,
0.00349691,
0.00366882,
0.00384202,
0.00401639,
0.0041918,
0.0043681,
0.00454516,
0.00472285,
0.00490101,
0.00507951,
0.00525821,
0.00543695,
0.0056156,
0.005794,
0.00597201,
0.00614947,
0.00632623,
0.00650216,
0.00667708,
0.00685086,
0.00702335,
0.00719439,
0.00736383,
0.00753153,
0.00769734,
0.00786111,
0.00802269,
0.00818194,
0.00833872,
0.00849289,
0.0086443,
0.00879283,
0.00893832,
0.00908066,
0.00921971,
0.00935534,
0.00948743,
0.00961585,
0.00974049,
0.00986123,
0.00997795,
0.0100905,
0.0101989,
0.0103029,
0.0104025,
0.0104976,
0.0105881,
0.0106738,
0.0107548,
0.010831,
0.0109022,
0.0109684,
0.0110295,
0.0110855,
0.0111364,
0.011182,
0.0112224,
0.0112575,
0.0112872,
0.0113115,
0.0113305,
0.0113441,
0.0113522,
0.0113549,
0.0113522,
0.0113441,
0.0113305,
0.0113115,
0.0112872,
0.0112575,
0.0112224,
0.011182,
0.0111364,
0.0110855,
0.0110295,
0.0109684,
0.0109022,
0.010831,
0.0107548,
0.0106738,
0.0105881,
0.0104976,
0.0104025,
0.0103029,
0.0101989,
0.0100905,
0.00997795,
0.00986123,
0.00974049,
0.00961585,
0.00948743,
0.00935534,
0.00921971,
0.00908066,
0.00893832,
0.00879283,
0.0086443,
0.00849289,
0.00833872,
0.00818194,
0.00802269,
0.00786111,
0.00769734,
0.00753153,
0.00736383,
0.00719439,
0.00702335,
0.00685086,
0.00667708,
0.00650216,
0.00632623,
0.00614947,
0.00597201,
0.005794,
0.0056156,
0.00543695,
0.00525821,
0.00507951,
0.00490101,
0.00472285,
0.00454516,
0.0043681,
0.0041918,
0.00401639,
0.00384202,
0.00366882,
0.00349691,
0.00332643,
0.00315749,
0.00299023,
0.00282475,
0.00266119,
0.00249965,
0.00234023,
0.00218306,
0.00202822,
0.00187583,
0.00172596,
0.00157873,
0.00143421,
0.00129249,
0.00115366,
0.00101777,
0.000884923,
0.000755171,
0.000628582,
0.000505217,
0.000385134,
0.000268384,
0.000155016,
4.5076e-05,
-6.13947e-05,
-0.00016436,
-0.000263788,
-0.000359651,
-0.000451952,
-0.00054068,
-0.000625779,
-0.000707261,
-0.000785117,
-0.000859348,
-0.000929956,
-0.000996946,
-0.00106033,
-0.00112013,
-0.00117635,
-0.00122903,
-0.00127818,
-0.00132384,
-0.00136604,
-0.00140482,
-0.00144021,
-0.00147227,
-0.00150103,
-0.00152655,
-0.00154888,
-0.00156807,
-0.00158419,
-0.00159729,
-0.00160744,
-0.00161472,
-0.00161917,
-0.00162088,
-0.0016199,
-0.00161633,
-0.00161024,
-0.00160171,
-0.00159081,
-0.00157763,
-0.00156225,
-0.00154475,
-0.00152522,
-0.00150374,
-0.0014804,
-0.00145528,
-0.00142848,
-0.00140008,
-0.00137017,
-0.00133884,
-0.00130617,
-0.00127227,
-0.0012372,
-0.00120108,
-0.00116397,
-0.00112597,
-0.00108717,
-0.00104765,
-0.00100749,
-0.000966788,
-0.000925613,
-0.000884054,
-0.000842187,
-0.000800092,
-0.000757849,
-0.000715533,
-0.000673218,
-0.000630979,
-0.000588883,
-0.000547003,
-0.000505403,
-0.000464152,
-0.00042331,
-0.000382942,
-0.000343104,
-0.000303856,
-0.000265248,
-0.000227336,
-0.000190167,
-0.00015379,
-0.000118248,
-8.35883e-05,
-4.98479e-05,
-1.7067e-05,
1.4721e-05,
4.54842e-05,
7.51956e-05,
0.000103821,
0.000131338,
0.000157726,
0.000182964,
0.000207034,
0.000229921,
0.000251612,
0.000272099,
0.000291373,
0.00030943,
0.000326267,
0.000341885,
0.000356284,
0.000369471,
0.000381449,
0.000392231,
0.000401823,
0.00041024,
0.000417497,
0.000423608,
0.000428592,
0.00043246,
0.000435237,
0.000436865,
0.000437401,
0.000436975,
0.000435544,
0.000433151,
0.000429812,
0.000425565,
0.000420437,
0.000414464,
0.000407675,
0.000400108,
0.000391795,
0.000382774,
0.00037308,
0.000362751,
0.000351824,
0.000340339,
0.00032833,
0.000315839,
0.000302903,
0.000289559,
0.000275847,
0.000261806,
0.000247474,
0.000232892,
0.000218088,
0.000203111,
0.000187996,
0.000172781,
0.000157497,
0.000142183,
0.000126869,
0.000111594,
9.63895e-05,
8.12934e-05,
6.63317e-05,
5.15418e-05,
3.69472e-05,
2.25833e-05,
8.47105e-06,
-5.35615e-06,
-1.88794e-05,
-3.20661e-05,
-4.49012e-05,
-5.73536e-05,
-6.94109e-05,
-8.10442e-05,
-9.22439e-05,
-0.000102985,
-0.000113258,
-0.000123038,
-0.000132323,
-0.000141089,
-0.000149335,
-0.000157041,
-0.00016421,
-0.000170822,
-0.000176885,
-0.000182382,
-0.000187324,
-0.000191693,
-0.000195505,
-0.000198743,
-0.000201427,
-0.000203541,
-0.000205109,
-0.000206117,
-0.00020659,
-0.000206515,
-0.000205922,
-0.000204797,
-0.000203173,
-0.000201038,
-0.000198429,
-0.000195333,
-0.000191793,
-0.000187794,
-0.000183382,
-0.00017854,
-0.000173315,
-0.000167689,
-0.000161723,
-0.000155393,
-0.000148756,
-0.000141789,
-0.000134559,
-0.000127034,
-0.000119289,
-0.000111281,
-0.000103097,
-9.46835e-05,
-8.6137e-05,
-7.73902e-05,
-6.85565e-05,
-5.9545e-05,
-5.04935e-05,
-4.12734e-05,
-3.20611e-05,
-2.2664e-05,
-1.33229e-05,
-3.71244e-06,
5.78773e-06,
1.58964e-05,
2.58255e-05
};
} // FreeDV

40
libfreedv/rxdec_coeff.h Normal file
View File

@ -0,0 +1,40 @@
/* Generated by rxdec_file() Octave function */
namespace FreeDV
{
const float rxdec_coeff[]={
-0.00125472,
-0.00204605,
-0.0019897,
0.000163906,
0.00490937,
0.00986375,
0.0096718,
-0.000480351,
-0.019311,
-0.0361822,
-0.0341251,
0.000827866,
0.0690577,
0.152812,
0.222115,
0.249004,
0.222115,
0.152812,
0.0690577,
0.000827866,
-0.0341251,
-0.0361822,
-0.019311,
-0.000480351,
0.0096718,
0.00986375,
0.00490937,
0.000163906,
-0.0019897,
-0.00204605,
-0.00125472
};
} // FreeDV

170
libfreedv/test_bits.h Normal file
View File

@ -0,0 +1,170 @@
/* Generated by test_bits_file() Octave function */
namespace FreeDV
{
const int test_bits[]={
0,
1,
1,
0,
0,
0,
1,
1,
0,
0,
1,
0,
1,
0,
0,
1,
0,
1,
1,
0,
0,
1,
1,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
1,
1,
1,
0,
1,
1,
0,
0,
1,
1,
1,
0,
1,
1,
0,
1,
1,
1,
1,
1,
0,
0,
1,
0,
0,
1,
1,
1,
0,
0,
1,
1,
1,
0,
0,
0,
0,
1,
1,
1,
0,
0,
1,
1,
1,
1,
1,
0,
1,
1,
1,
0,
0,
1,
1,
0,
1,
1,
1,
1,
1,
1,
1,
0,
0,
1,
1,
0,
1,
0,
0,
0,
1,
1,
1,
0,
0,
0,
0,
1,
1,
1,
1,
1,
0,
1,
1,
0,
0,
0,
1,
0,
0,
1,
0,
0,
0,
1,
0,
0,
1,
0,
0,
0,
0,
0,
0,
0,
0,
1,
1,
0,
1,
1,
0,
0,
0,
1,
0,
1,
1,
1,
0,
1
};
} // FreeDV

569
libfreedv/test_bits_coh.h Normal file
View File

@ -0,0 +1,569 @@
/* Generated by test_bits_coh_file() Octave function */
namespace FreeDV
{
const int test_bits_coh[]={
0,
1,
1,
0,
0,
0,
1,
1,
0,
0,
1,
0,
1,
0,
0,
1,
0,
1,
1,
0,
0,
1,
1,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
1,
1,
1,
0,
1,
1,
0,
0,
1,
1,
1,
0,
1,
1,
0,
1,
1,
1,
1,
1,
0,
0,
1,
0,
0,
1,
1,
1,
0,
0,
1,
1,
1,
0,
0,
0,
0,
1,
1,
1,
0,
0,
1,
1,
1,
1,
1,
0,
1,
1,
1,
0,
0,
1,
1,
0,
1,
1,
1,
1,
1,
1,
1,
0,
0,
1,
1,
0,
1,
0,
0,
0,
1,
1,
1,
0,
0,
0,
0,
1,
1,
1,
1,
1,
0,
1,
1,
0,
0,
0,
1,
0,
0,
1,
0,
0,
0,
1,
0,
0,
1,
0,
0,
0,
0,
0,
0,
0,
0,
1,
1,
0,
1,
1,
0,
0,
0,
1,
0,
1,
1,
1,
0,
1,
1,
1,
0,
1,
0,
1,
0,
1,
0,
0,
1,
1,
0,
1,
0,
1,
1,
0,
0,
0,
1,
0,
1,
1,
1,
0,
1,
1,
1,
1,
0,
0,
0,
1,
0,
0,
0,
1,
0,
0,
0,
1,
1,
0,
0,
0,
1,
1,
0,
0,
1,
1,
1,
0,
1,
1,
0,
1,
0,
1,
0,
0,
1,
0,
1,
1,
1,
0,
0,
0,
1,
1,
1,
1,
0,
1,
0,
0,
0,
1,
1,
1,
0,
1,
1,
0,
1,
0,
0,
0,
1,
1,
1,
0,
0,
1,
1,
0,
1,
0,
0,
1,
0,
0,
1,
0,
0,
0,
0,
1,
0,
1,
0,
1,
1,
0,
0,
0,
0,
1,
0,
0,
1,
0,
1,
0,
0,
0,
1,
1,
1,
0,
0,
1,
1,
1,
1,
1,
0,
1,
0,
0,
0,
0,
1,
0,
1,
1,
1,
0,
0,
0,
0,
1,
1,
0,
0,
1,
1,
1,
0,
0,
0,
0,
1,
0,
0,
1,
0,
1,
0,
1,
0,
1,
1,
0,
1,
0,
1,
1,
1,
0,
0,
1,
1,
0,
1,
0,
1,
0,
0,
1,
1,
1,
1,
1,
1,
0,
0,
0,
1,
1,
0,
0,
1,
1,
1,
1,
1,
0,
0,
0,
0,
0,
1,
0,
1,
0,
0,
0,
0,
0,
1,
0,
0,
1,
0,
0,
1,
1,
1,
0,
1,
1,
0,
0,
0,
0,
0,
1,
1,
1,
0,
1,
0,
0,
1,
1,
0,
1,
1,
0,
1,
1,
0,
1,
1,
1,
1,
1,
1,
1,
0,
0,
0,
1,
1,
0,
1,
1,
0,
1,
0,
1,
0,
1,
1,
1,
0,
1,
1,
0,
1,
1,
1,
1,
0,
1,
1,
0,
1,
0,
0,
0,
0,
1,
1,
0,
1,
0,
0,
0,
0,
1,
0,
0,
0,
0,
1,
1,
1,
0,
0,
1,
0,
1,
0,
1,
1,
1,
1,
1,
0,
1,
1,
1,
0,
0,
0,
1,
0,
1,
1,
1,
1,
1,
0,
1,
1,
0,
1,
0,
1,
0,
0,
0,
0,
0,
1,
1,
0,
1,
0,
0,
0,
0,
1,
1,
1,
1,
1,
0,
1,
0,
1,
1,
0,
0,
1,
1,
0,
0,
0,
0,
0,
1,
1,
1,
1,
1,
0,
1,
1,
1,
1,
0,
1,
1,
1,
1,
1,
1,
1,
1,
0,
0,
1,
1,
1,
0
};
} // FreeDV

View File

@ -23,7 +23,8 @@ set(freedv_FORMS
include_directories(
.
${CMAKE_CURRENT_BINARY_DIR}
${CMAKE_SOURCE_DIR}/swagger/sdrangel/code/qt5/client
${CMAKE_SOURCE_DIR}/swagger/sdrangel/code/qt5/client
${CMAKE_SOURCE_DIR}/libfreedv
${CODEC2_INCLUDE_DIR}
)
@ -44,6 +45,7 @@ target_link_libraries(demodfreedv
sdrbase
sdrgui
swagger
freedv
${CODEC2_LIBRARIES}
)

View File

@ -22,7 +22,7 @@
#include <QNetworkReply>
#include <QBuffer>
#include "codec2/freedv_api.h"
#include "libfreedv.h"
#include "SWGChannelSettings.h"
#include "SWGFreeDVDemodSettings.h"
@ -67,12 +67,12 @@ void FreeDVDemod::FreeDVStats::init()
m_fps = 1;
}
void FreeDVDemod::FreeDVStats::collect(struct freedv *freeDV)
void FreeDVDemod::FreeDVStats::collect(struct FreeDV::freedv *freeDV)
{
struct MODEM_STATS stats;
struct FreeDV::MODEM_STATS stats;
freedv_get_modem_extended_stats(freeDV, &stats);
m_totalBitErrors = freedv_get_total_bit_errors(freeDV);
FreeDV::freedv_get_modem_extended_stats(freeDV, &stats);
m_totalBitErrors = FreeDV::freedv_get_total_bit_errors(freeDV);
m_clockOffset = stats.clock_offset;
m_freqOffset = stats.foff;
m_syncMetric = stats.sync_metric;
@ -150,7 +150,7 @@ FreeDVDemod::FreeDVDemod(DeviceSourceAPI *deviceAPI) :
m_lowCutoff(0),
m_volume(2),
m_spanLog2(3),
m_sum(0),
m_sum(fftfilt::cmplx{0,0}),
m_inputSampleRate(48000),
m_modemSampleRate(48000),
m_speechSampleRate(8000), // fixed 8 kS/s
@ -387,7 +387,7 @@ bool FreeDVDemod::handleMessage(const Message& cmd)
{
qDebug("FreeDVDemod::handleMessage: MsgResyncFreeDVDemod");
m_settingsMutex.lock();
freedv_set_sync(m_freeDV, unsync);
FreeDV::freedv_set_sync(m_freeDV, FreeDV::unsync);
m_settingsMutex.unlock();
return true;
}
@ -593,27 +593,27 @@ void FreeDVDemod::applyFreeDVMode(FreeDVDemodSettings::FreeDVMode mode)
if (fdv_mode == FREEDV_MODE_700D)
{
struct freedv_advanced adv;
struct FreeDV::freedv_advanced adv;
adv.interleave_frames = 1;
m_freeDV = freedv_open_advanced(fdv_mode, &adv);
}
else
{
m_freeDV = freedv_open(fdv_mode);
m_freeDV = FreeDV::freedv_open(fdv_mode);
}
if (m_freeDV)
{
freedv_set_test_frames(m_freeDV, 0);
freedv_set_snr_squelch_thresh(m_freeDV, -100.0);
freedv_set_squelch_en(m_freeDV, 0);
freedv_set_clip(m_freeDV, 0);
freedv_set_ext_vco(m_freeDV, 0);
freedv_set_sync(m_freeDV, manualsync);
FreeDV::freedv_set_test_frames(m_freeDV, 0);
FreeDV::freedv_set_snr_squelch_thresh(m_freeDV, -100.0);
FreeDV::freedv_set_squelch_en(m_freeDV, 0);
FreeDV::freedv_set_clip(m_freeDV, 0);
FreeDV::freedv_set_ext_vco(m_freeDV, 0);
FreeDV::freedv_set_sync(m_freeDV, FreeDV::manualsync);
freedv_set_callback_txt(m_freeDV, nullptr, nullptr, nullptr);
freedv_set_callback_protocol(m_freeDV, nullptr, nullptr, nullptr);
freedv_set_callback_data(m_freeDV, nullptr, nullptr, nullptr);
FreeDV::freedv_set_callback_txt(m_freeDV, nullptr, nullptr, nullptr);
FreeDV::freedv_set_callback_protocol(m_freeDV, nullptr, nullptr, nullptr);
FreeDV::freedv_set_callback_data(m_freeDV, nullptr, nullptr, nullptr);
int nSpeechSamples = freedv_get_n_speech_samples(m_freeDV);
int nMaxModemSamples = freedv_get_n_max_modem_samples(m_freeDV);

View File

@ -43,7 +43,10 @@ class QNetworkReply;
class DeviceSourceAPI;
class ThreadedBasebandSampleSink;
class DownChannelizer;
namespace FreeDV {
struct freedv;
}
class FreeDVDemod : public BasebandSampleSink, public ChannelSinkAPI {
Q_OBJECT
@ -208,7 +211,7 @@ private:
{
FreeDVStats();
void init();
void collect(struct freedv *freedv);
void collect(struct FreeDV::freedv *freedv);
bool m_sync;
float m_snrEst;
@ -381,7 +384,7 @@ private:
QNetworkAccessManager *m_networkManager;
QNetworkRequest m_networkRequest;
struct freedv *m_freeDV;
struct FreeDV::freedv *m_freeDV;
int m_nSpeechSamples;
int m_nMaxModemSamples;
int m_nin;