Code further broken up

cleanup
Marshal Horn 2020-07-01 10:29:21 -07:00
rodzic 7a8759711c
commit 0f42a423b2
14 zmienionych plików z 1055 dodań i 1046 usunięć

Plik diff jest za duży Load Diff

92
code/filter.h 100644
Wyświetl plik

@ -0,0 +1,92 @@
#ifndef FILTER_HEADER
#define FILTER_HEADER
// FIXME: relies on CW_TONE
#define N_FILT 7
volatile int8_t filt = 0;
int8_t prev_filt[] = { 0 , 4 }; // default filter for modes resp. CW, SSB
inline int16_t filt_var(int16_t za0) //filters build with www.micromodeler.com
{
static int16_t za1,za2;
static int16_t zb0,zb1,zb2;
static int16_t zc0,zc1,zc2;
if(filt < 4)
{ // for SSB filters
// 1st Order (SR=8kHz) IIR in Direct Form I, 8x8:16
static int16_t zz1,zz2;
za0=(29*(za0-zz1)+50*za1)/64; //300-Hz
zz2=zz1;
zz1=za0;
// 4th Order (SR=8kHz) IIR in Direct Form I, 8x8:16
switch(filt){
case 1: zb0=za0; break; //0-4000Hz (pass-through)
case 2: zb0=(10*(za0+2*za1+za2)+16*zb1-17*zb2)/32; break; //0-2500Hz elliptic -60dB@3kHz
case 3: zb0=(7*(za0+2*za1+za2)+48*zb1-18*zb2)/32; break; //0-1700Hz elliptic
}
switch(filt){
case 1: zc0=zb0; break; //0-4000Hz (pass-through)
case 2: zc0=(8*(zb0+zb2)+13*zb1-43*zc1-52*zc2)/64; break; //0-2500Hz elliptic -60dB@3kHz
case 3: zc0=(4*(zb0+zb1+zb2)+22*zc1-47*zc2)/64; break; //0-1700Hz elliptic
}
zc2=zc1;
zc1=zc0;
zb2=zb1;
zb1=zb0;
za2=za1;
za1=za0;
return zc0;
} else { // for CW filters
// (2nd Order (SR=4465Hz) IIR in Direct Form I, 8x8:16), adding 64x front-gain (to deal with later division)
if(cw_tone == 0){
switch(filt){
case 4: zb0=(za0+2*za1+za2)/2+(41L*zb1-23L*zb2)/32; break; //500-1000Hz
case 5: zb0=5*(za0-2*za1+za2)+(105L*zb1-58L*zb2)/64; break; //650-840Hz
case 6: zb0=3*(za0-2*za1+za2)+(108L*zb1-61L*zb2)/64; break; //650-750Hz
case 7: zb0=(2*za0-3*za1+2*za2)+(111L*zb1-62L*zb2)/64; break; //630-680Hz
}
switch(filt){
case 4: zc0=(zb0-2*zb1+zb2)/4+(105L*zc1-52L*zc2)/64; break; //500-1000Hz
case 5: zc0=((zb0+2*zb1+zb2)+97L*zc1-57L*zc2)/64; break; //650-840Hz
case 6: zc0=((zb0+zb1+zb2)+104L*zc1-60L*zc2)/64; break; //650-750Hz
case 7: zc0=((zb1)+109L*zc1-62L*zc2)/64; break; //630-680Hz
}
}
if(cw_tone == 1){
switch(filt){
case 4: zb0=(5*za0+9*za1+5*za2)+(30L*zb1-38L*zb2)/64; break; //720Hz+-250Hz
case 5: zb0=(2*za0+4*za1+2*za2)+(51L*zb1-52L*zb2)/64; break; //720Hz+-100Hz
case 6: zb0=(1*za0+2*za1+1*za2)+(59L*zb1-58L*zb2)/64; break; //720Hz+-50Hz
case 7: zb0=(0*za0+1*za1+0*za2)+(66L*zb1-61L*zb2)/64; break; //720Hz+-25Hz
}
switch(filt){
case 4: zc0=(zb0-2*zb1+zb2)/4+(76L*zc1-44L*zc2)/64; break; //720Hz+-250Hz
case 5: zc0=(zb0-2*zb1+zb2)/8+(72L*zc1-53L*zc2)/64; break; //720Hz+-100Hz
case 6: zc0=(zb0-2*zb1+zb2)/16+(70L*zc1-58L*zc2)/64; break; //720Hz+-50Hz
case 7: zc0=(zb0-2*zb1+zb2)/32+(70L*zc1-62L*zc2)/64; break; //720Hz+-25Hz
}
}
zc2=zc1;
zc1=zc0;
zb2=zb1;
zb1=zb0;
za2=za1;
za1=za0;
return zc0 / 64; // compensate the 64x front-end gain
}
}
#endif

47
code/hal/adc.h 100644
Wyświetl plik

@ -0,0 +1,47 @@
void adc_start(uint8_t adcpin, bool ref1v1, uint32_t fs)
{
#ifndef AUTO_ADC_BIAS
DIDR0 |= (1 << adcpin); // disable digital input
#endif
ADCSRA = 0; // clear ADCSRA register
ADCSRB = 0; // clear ADCSRB register
ADMUX = 0; // clear ADMUX register
ADMUX |= (adcpin & 0x0f); // set analog input pin
ADMUX |= ((ref1v1) ? (1 << REFS1) : 0) | (1 << REFS0); // set AREF=1.1V (Internal ref); otherwise AREF=AVCC=(5V)
ADCSRA |= ((uint8_t)log2((uint8_t)(F_CPU / 13 / fs))) & 0x07; // ADC Prescaler (for normal conversions non-auto-triggered): ADPS = log2(F_CPU / 13 / Fs) - 1; ADSP=0..7 resulting in resp. conversion rate of 1536, 768, 384, 192, 96, 48, 24, 12 kHz
//ADCSRA |= (1 << ADIE); // enable interrupts when measurement complete
ADCSRA |= (1 << ADEN); // enable ADC
//ADCSRA |= (1 << ADSC); // start ADC measurements
#ifdef ADC_NR
// set_sleep_mode(SLEEP_MODE_ADC); // ADC NR sleep destroys the timer2 integrity, therefore Idle sleep is better alternative (keeping clkIO as an active clock domain)
set_sleep_mode(SLEEP_MODE_IDLE);
sleep_enable();
#endif
}
void adc_stop()
{
//ADCSRA &= ~(1 << ADATE); // disable auto trigger
ADCSRA &= ~(1 << ADIE); // disable interrupts when measurement complete
ADCSRA |= (1 << ADPS2) | (1 << ADPS1) | (1 << ADPS0); // 128 prescaler for 9.6kHz
#ifdef ADC_NR
sleep_disable();
#endif
ADMUX = (1 << REFS0); // restore reference voltage AREF (5V)
}
int analogSafeRead(uint8_t pin)
{ // performs classical analogRead with default Arduino sample-rate and analog reference setting; restores previous settings
noInterrupts();
uint8_t adcsra = ADCSRA;
uint8_t admux = ADMUX;
ADCSRA &= ~(1 << ADIE); // disable interrupts when measurement complete
ADCSRA |= (1 << ADPS2) | (1 << ADPS1) | (1 << ADPS0); // 128 prescaler for 9.6kHz
ADMUX = (1 << REFS0); // restore reference voltage AREF (5V)
delay(1); // settle
int val = analogRead(pin);
ADCSRA = adcsra;
ADMUX = admux;
interrupts();
return val;
}

Wyświetl plik

@ -311,3 +311,74 @@ const uint8_t font[]PROGMEM = {
#define FONT_STRETCHV 1
#define FONT_STRETCHH 0
*/
char blanks[] = " ";
#define lcd_blanks() lcd.print(blanks);
#define N_FONTS 8
const byte fonts[N_FONTS][8] PROGMEM = {
{ 0b01000, // 1; logo
0b00100,
0b01010,
0b00101,
0b01010,
0b00100,
0b01000,
0b00000 },
{ 0b00000, // 2; s-meter, 0 bars
0b00000,
0b00000,
0b00000,
0b00000,
0b00000,
0b00000,
0b00000 },
{ 0b10000, // 3; s-meter, 1 bars
0b10000,
0b10000,
0b10000,
0b10000,
0b10000,
0b10000,
0b10000 },
{ 0b10000, // 4; s-meter, 2 bars
0b10000,
0b10100,
0b10100,
0b10100,
0b10100,
0b10100,
0b10100 },
{ 0b10000, // 5; s-meter, 3 bars
0b10000,
0b10101,
0b10101,
0b10101,
0b10101,
0b10101,
0b10101 },
{ 0b01100, // 6; vfo-a
0b10010,
0b11110,
0b10010,
0b10010,
0b00000,
0b00000,
0b00000 },
{ 0b11100, // 7; vfo-b
0b10010,
0b11100,
0b10010,
0b11100,
0b00000,
0b00000,
0b00000 },
{ 0b00000, // 8; tbd
0b00000,
0b00000,
0b00000,
0b00000,
0b00000,
0b00000,
0b00000 }
};

Wyświetl plik

@ -50,3 +50,36 @@ ssb_cap=1; dsp_cap=2;
#define F_CPU F_XTAL
experimentally: #define AUTO_ADC_BIAS 1
*/
void initPins(){
// initialize
digitalWrite(SIG_OUT, LOW);
digitalWrite(RX, HIGH);
digitalWrite(KEY_OUT, LOW);
digitalWrite(SIDETONE, LOW);
// pins
pinMode(SIDETONE, OUTPUT);
pinMode(SIG_OUT, OUTPUT);
pinMode(RX, OUTPUT);
pinMode(KEY_OUT, OUTPUT);
//#define ONEBUTTON 1
#ifdef ONEBUTTON
pinMode(BUTTONS, INPUT_PULLUP); // rotary button
#else
pinMode(BUTTONS, INPUT); // L/R/rotary button
#endif
pinMode(DIT, INPUT_PULLUP);
//pinMode(DAH, INPUT);
pinMode(DAH, INPUT_PULLUP); // Could this replace D4?
digitalWrite(AUDIO1, LOW); // when used as output, help can mute RX leakage into AREF
digitalWrite(AUDIO2, LOW);
pinMode(AUDIO1, INPUT);
pinMode(AUDIO2, INPUT);
#ifdef NTX
digitalWrite(NTX, HIGH);
pinMode(NTX, OUTPUT);
#endif
}

44
code/hal/timer.h 100644
Wyświetl plik

@ -0,0 +1,44 @@
typedef void (*func_t)(void);
volatile func_t func_ptr;
void timer1_start(uint32_t fs)
{ // Timer 1: OC1A and OC1B in PWM mode
TCCR1A = 0;
TCCR1B = 0;
TCCR1A |= (1 << COM1A1) | (1 << COM1B1) | (1 << WGM11); // Clear OC1A/OC1B on compare match, set OC1A/OC1B at BOTTOM (non-inverting mode)
TCCR1B |= (1 << CS10) | (1 << WGM13) | (1 << WGM12); // Mode 14 - Fast PWM; CS10: clkI/O/1 (No prescaling)
ICR1H = 0x00;
ICR1L = min(255, (float)F_CPU / (float)fs - 0.5); // PWM value range (fs>78431): Fpwm = F_CPU / [Prescaler * (1 + TOP)]
//TCCR1A |= (1 << COM1A1) | (1 << COM1B1) | (1 << WGM10); // Clear OC1A/OC1B on compare match, set OC1A/OC1B at BOTTOM (non-inverting mode)
//TCCR1B |= (1 << CS10) | (1 << WGM12); // Mode 5 - Fast PWM, 8-bit; CS10: clkI/O/1 (No prescaling)
OCR1AH = 0x00;
OCR1AL = 0x00; // OC1A (SIDETONE) PWM duty-cycle (span defined by ICR).
OCR1BH = 0x00;
OCR1BL = 0x00; // OC1B (KEY_OUT) PWM duty-cycle (span defined by ICR).
}
void timer1_stop()
{
OCR1AL = 0x00;
OCR1BL = 0x00;
}
void timer2_start(uint32_t fs)
{ // Timer 2: interrupt mode
ASSR &= ~(1 << AS2); // Timer 2 clocked from CLK I/O (like Timer 0 and 1)
TCCR2A = 0;
TCCR2B = 0;
TCNT2 = 0;
TCCR2A |= (1 << WGM21); // WGM21: Mode 2 - CTC (Clear Timer on Compare Match)
TCCR2B |= (1 << CS22); // Set C22 bits for 64 prescaler
TIMSK2 |= (1 << OCIE2A); // enable timer compare interrupt TIMER2_COMPA_vect
uint8_t ocr = (((float)F_CPU / (float)64) / (float)fs + 0.5) - 1; // OCRn = (F_CPU / pre-scaler / fs) - 1;
OCR2A = ocr;
}
void timer2_stop()
{ // Stop Timer 2 interrupt
TIMSK2 &= ~(1 << OCIE2A); // disable timer compare interrupt
delay(1); // wait until potential in-flight interrupts are finished
}

14
code/radio/am.h 100644
Wyświetl plik

@ -0,0 +1,14 @@
void dsp_tx_am()
{ // jitter dependent things first
ADCSRA |= (1 << ADSC); // start next ADC conversion (trigger ADC interrupt if ADIE flag is set)
OCR1BL = amp; // submit amplitude to PWM register (actually this is done in advance (about 140us) of phase-change, so that phase-delays in key-shaping circuit filter can settle)
int16_t adc = ADC - 512; // current ADC sample 10-bits analog input, NOTE: first ADCL, then ADCH
int16_t in = (adc >> MIC_ATTEN);
in = in << (drive-4);
//static int16_t dc;
//dc += (in - dc) / 2;
//in = in - dc; // DC decoupling
#define AM_BASE 32
in=max(0, min(255, (in + AM_BASE)));
amp=in;// lut[in];
}

17
code/radio/cat.h 100644
Wyświetl plik

@ -0,0 +1,17 @@
static char cat[20]; // temporary here
static uint8_t nc = 0;
static uint16_t cat_cmd = 0;
void parse_cat(uint8_t in){ // TS480 CAT protocol: https://www.kenwood.com/i/products/info/amateur/ts_480/pdf/ts_480_pc.pdf
if(nc == 0) cat_cmd = in << 8;
if(nc == 1) cat_cmd += in;
if(in == ';'){ // end of cat command -> parse and process
switch(cat_cmd){
case 'I'<<8|'F': Serial.write("IF00010138000 +00000000002000000 ;"); lcd.setCursor(0, 0); lcd.print("IF"); break;
}
nc = 0; // reset
} else {
if(nc < (sizeof(cat) - 1)) cat[nc++] = in; // buffer and count-up
}
}

Wyświetl plik

@ -19,7 +19,8 @@ inline void _vox(uint8_t trigger)
}
static char out[] = " ";
volatile bool cw_event = false;
uint8_t lut[256];
volatile uint8_t amp;
volatile uint8_t vox_thresh = (1 << 2);
@ -31,4 +32,111 @@ volatile uint8_t drive = 2; // hmm.. drive>2 impacts cpu load..why?
volatile int8_t mox = 0;
volatile int8_t volume = 12;
volatile uint16_t acc;
volatile uint32_t cw_offset;
volatile uint8_t cw_tone = 1;
const uint32_t tones[] = {325, 700};
volatile int16_t p_sin = 0; // initialized with A*sin(0) = 0
volatile int16_t n_cos = 448/2; // initialized with A*cos(t) = A
inline void process_minsky() // Minsky circle sample [source: https://www.cl.cam.ac.uk/~am21/hakmemc.html, ITEM 149]: p_sin+=n_cos*2*PI*f/fs; n_cos-=p_sin*2*PI*f/fs;
{
uint8_t alpha100 = tones[cw_tone]/*cw_offset*/ * 628 / F_SAMP_TX; // alpha = f_tone * 6.28 / fs
p_sin += alpha100 * n_cos / 100;
n_cos -= alpha100 * p_sin / 100;
}
uint8_t reg;
volatile int8_t cwdec = 0;
static int32_t signal;
static int16_t avg = 0;
static int16_t maxpk=0;
static int16_t k0=0;
static int16_t k1=0;
static uint8_t sym;
static int16_t ta=0;
const char m2c[] PROGMEM = "**ETIANMSURWDKGOHVF*L*PJBXCYZQ**54S3***2**+***J16=/***H*7*G*8*90************?_****\"**.****@***'**-********;!*)*****,****:****";
static uint8_t nsamp=0;
#define F_SAMP_PWM (78125/1)
//#define F_SAMP_RX 78125
#define F_SAMP_RX 62500 //overrun; sample rate of 55500 can be obtained
//#define F_SAMP_RX 52083
//#define F_SAMP_RX 44643
//#define F_SAMP_RX 39062
//#define F_SAMP_RX 34722
//#define F_SAMP_RX 31250
//#define F_SAMP_RX 28409
#define F_ADC_CONV (192307/1) // finding: tiny-clicks above noise-floor occur with 192kHz ADC conversion-rate and 78kHz PWM output, can be resolved by either lower down PWM or conversation-rate
volatile bool agc = true;
volatile uint8_t nr = 0;
volatile uint8_t att = 0;
volatile uint8_t att2 = 0;
volatile uint8_t _init;
//static uint32_t gain = 1024;
static int16_t gain = 1024;
inline int16_t process_agc(int16_t in)
{
//int16_t out = ((uint32_t)(gain) >> 20) * in;
//gain = gain + (1024 - abs(out) + 512);
int16_t out = (gain >= 1024) ? (gain >> 10) * in : in;
//if(gain >= 1024) out = (gain >> 10) * in; // net gain >= 1
//else if(gain >= 16) out = ((gain >> 4) * in) >> 6; // net gain < 1
//else out = (gain * in) >> 10;
int16_t accum = (1 - abs(out >> 10));
if((INT16_MAX - gain) > accum) gain = gain + accum;
if(gain < 1) gain = 1;
return out;
}
inline int16_t process_nr_old(int16_t ac)
{
ac = ac >> (6-abs(ac)); // non-linear below amp of 6; to reduce noise (switchoff agc and tune-up volume until noise dissapears, todo:extra volume control needed)
ac = ac << 3;
return ac;
}
#define EA(y, x, one_over_alpha) (y) = (y) + ((x) - (y)) / (one_over_alpha); // exponental averaging [Lyons 13.33.1]
#define MLEA(y, x, L, M) (y) = (y) + ((((x) - (y)) >> (L)) - (((x) - (y)) >> (M))); // multiplierless exponental averaging [Lyons 13.33.1], with alpha=1/2^L - 1/2^M
inline int16_t process_nr_old2(int16_t ac)
{
int16_t x = ac;
static int16_t ea1;
//ea1 = MLEA(ea1, ac, 5, 6); // alpha=0.0156
ea1 = EA(ea1, ac, 64); // alpha=1/64=0.0156
//static int16_t ea2;
//ea2 = EA(ea2, ea1, 64); // alpha=1/64=0.0156
return ea1;
}
inline int16_t process_nr(int16_t in)
{
/*
static int16_t avg;
avg = EA(avg, abs(in), 64); // alpha=1/64=0.0156
param_c = avg;
*/
/*
int32_t _avg = 64 * avg;
// if(_avg > 4) _avg = 4; // clip
// uint16_t brs_avgsq = 1 << (_avg * _avg);
if(_avg > 14) _avg = 14; // clip
uint16_t brs_avgsq = 1 << (_avg);
int16_t inv_gain;
if(brs_avgsq > 1) inv_gain = brs_avgsq / (brs_avgsq - 1); // = 1 / (1 - 1/(1 << (1*avg*avg)) );
else inv_gain = 32768;*/
static int16_t ea1;
ea1 = EA(ea1, in, 1 << (nr-1) );
//static int16_t ea2;
//ea2 = EA(ea2, ea1, inv_gain);
return ea1;
}

47
code/radio/cw.h 100644
Wyświetl plik

@ -0,0 +1,47 @@
void dsp_tx_cw()
{ // jitter dependent things first
OCR1BL = lut[255];
process_minsky();
OCR1AL = (p_sin >> (16 - volume)) + 128;
}
char cw(int16_t in)
{
char ch = 0;
int i;
signal += abs(in);
#define OSR 64 // (8*FS/1000)
if((nsamp % OSR) == 0){ // process every 8 ms
nsamp=0;
if(!signal) return ch;
signal = signal / OSR; //normalize
maxpk = signal > maxpk ? signal : maxpk;
#define RT 4
if(signal>(maxpk/2) ){ // threshold: 3dB below max signal
k1++; // key on
k0=0;
} else {
k0++; // key off
if(k0>0 && k1>0){ //symbol space
if(k1>(ta/100)) ta=RT*ta/100+(100-RT)*k1; // go slower
if(k1>(ta/600) && k1<(ta/300)) ta=(100-RT)*ta/100+RT*k1*3; // go faster
if(k1>(ta/600)) sym=(sym<<1)|(k1>(ta/200)); // dit (0) or dash (1)
k1=0;
}
if(k0>=(ta/200) && sym>1){ //letter space
if(sym<128) ch=/*m2c[sym]*/ pgm_read_byte_near(m2c + sym);
sym=1;
}
if(k0>=(ta/67)){ //word space (67=1.5/100)
ch = ' ';
k0=-1000*(ta/100); //delay word spaces
}
}
avg = avg*99/100 + signal*1/100;
maxpk = maxpk*99/100 + signal*1/100;
signal = 0;
}
nsamp++;
return ch;
}

12
code/radio/dsb.h 100644
Wyświetl plik

@ -0,0 +1,12 @@
void dsp_tx_dsb()
{ // jitter dependent things first
ADCSRA |= (1 << ADSC); // start next ADC conversion (trigger ADC interrupt if ADIE flag is set)
OCR1BL = amp; // submit amplitude to PWM register (actually this is done in advance (about 140us) of phase-change, so that phase-delays in key-shaping circuit filter can settle)
si5351.SendRegister(16+2, reg); // CLK2 polarity depending on amplitude
int16_t adc = ADC - 512; // current ADC sample 10-bits analog input, NOTE: first ADCL, then ADCH
int16_t in = (adc >> MIC_ATTEN);
in = in << drive;
reg = (in < 0) ? 0x2C|3|0x10 : 0x2C|3; //0x2C=PLLB local msynth 3=8mA 0x10=invert
in=min(255, abs(in));
amp=in;// lut[in];
}

11
code/radio/fm.h 100644
Wyświetl plik

@ -0,0 +1,11 @@
void dsp_tx_fm()
{ // jitter dependent things first
ADCSRA |= (1 << ADSC); // start next ADC conversion (trigger ADC interrupt if ADIE flag is set)
OCR1BL = lut[255]; // submit amplitude to PWM register (actually this is done in advance (about 140us) of phase-change, so that phase-delays in key-shaping circuit filter can settle)
si5351.SendPLLBRegisterBulk(); // submit frequency registers to SI5351 over 731kbit/s I2C (transfer takes 64/731 = 88us, then PLL-loopfilter probably needs 50us to stabalize)
int16_t adc = ADC - 512; // current ADC sample 10-bits analog input, NOTE: first ADCL, then ADCH
int16_t in = (adc >> MIC_ATTEN);
in = in << (drive);
int16_t df = in;
si5351.freq_calc_fast(df); // calculate SI5351 registers based on frequency shift and carrier frequency
}

314
code/radio/rx.h 100644
Wyświetl plik

@ -0,0 +1,314 @@
#include "../filter.h"
static uint32_t absavg256 = 0;
volatile uint32_t _absavg256 = 0;
volatile int16_t i, q;
inline int16_t slow_dsp(int16_t ac)
{
static uint8_t absavg256cnt;
if(!(absavg256cnt--)){ _absavg256 = absavg256; absavg256 = 0;
//#define AUTO_ADC_BIAS 1
#ifdef AUTO_ADC_BIAS
if(param_b < 0){
pinMode(AUDIO1, INPUT_PULLUP);
pinMode(AUDIO1, INPUT);
}
if(param_c < 0){
pinMode(AUDIO2, INPUT_PULLUP);
pinMode(AUDIO2, INPUT);
}
if(param_b > 500){
pinMode(AUDIO1, OUTPUT);
digitalWrite(AUDIO1, LOW);
pinMode(AUDIO1, INPUT);
}
if(param_c > 500){
pinMode(AUDIO2, OUTPUT);
digitalWrite(AUDIO2, LOW);
pinMode(AUDIO2, INPUT);
}
#endif
} else absavg256 += abs(ac);
if(mode == AM) { // (12%CPU for the mode selection etc)
ac = magn(i, q); //(25%CPU)
{ static int16_t dc;
dc += (ac - dc) / 2;
ac = ac - dc; } // DC decoupling
} else if(mode == FM){
static int16_t z1;
int16_t z0 = arctan3(q, i);
ac = z0 - z1; // Differentiator
z1 = z0;
//ac = ac * (F_SAMP_RX/R) / _UA; // =ac*3.5 -> skip
} // needs: p.12 https://www.veron.nl/wp-content/uploads/2014/01/FmDemodulator.pdf
else { ; } // USB, LSB, CW
if(agc) ac = process_agc(ac);
ac = ac >> (16-volume);
if(nr) ac = process_nr(ac);
if(filt) ac = filt_var(ac) << 2;
if(mode == CW){
if(cwdec){ // CW decoder enabled?
char ch = cw(ac >> 0);
if(ch){
for(int i=0; i!=15;i++) out[i]=out[i+1];
out[15] = ch;
cw_event = true;
}
}
}
//if(!(absavg256cnt--)){ _absavg256 = absavg256; absavg256 = 0; } else absavg256 += abs(ac); //hack
//static int16_t dc;
//dc += (ac - dc) / 2;
//dc = (15*dc + ac)/16;
//dc = (15*dc + (ac - dc))/16;
//ac = ac - dc; // DC decoupling
ac = min(max(ac, -512), 511);
//ac = min(max(ac, -128), 127);
return ac;
}
#undef R // Decimating 2nd Order CIC filter
#define R 4 // Rate change from 62500/2 kSPS to 7812.5SPS, providing 12dB gain
//#define SIMPLE_RX 1
#ifndef SIMPLE_RX
volatile uint8_t admux[3];
volatile int16_t ocomb, qh;
volatile uint8_t rx_state = 0;
void sdr_rx_q(void);
void sdr_rx_common();
// Non-recursive CIC Filter (M=2, R=4) implementation, so two-stages of (followed by down-sampling with factor 2):
// H1(z) = (1 + z^-1)^2 = 1 + 2*z^-1 + z^-2 = (1 + z^-2) + (2) * z^-1 = FA(z) + FB(z) * z^-1;
// with down-sampling before stage translates into poly-phase components: FA(z) = 1 + z^-1, FB(z) = 2
// source: Lyons Understanding Digital Signal Processing 3rd edition 13.24.1
void sdr_rx()
{
// process I for even samples [75% CPU@R=4;Fs=62.5k] (excluding the Comb branch and output stage)
ADMUX = admux[1]; // set MUX for next conversion
ADCSRA |= (1 << ADSC); // start next ADC conversion
int16_t adc = ADC - 511; // current ADC sample 10-bits analog input, NOTE: first ADCL, then ADCH
func_ptr = sdr_rx_q; // processing function for next conversion
sdr_rx_common();
// Only for I: correct I/Q sample delay by means of linear interpolation
static int16_t prev_adc;
int16_t corr_adc = (prev_adc + adc) / 2;
prev_adc = adc;
adc = corr_adc;
//static int16_t dc;
//dc += (adc - dc) / 2; // we lose LSB with this method
//dc = (3*dc + adc)/4;
//int16_t ac = adc - dc; // DC decoupling
int16_t ac = adc;
#ifdef AUTO_ADC_BIAS
param_b = (7*param_b + adc)/8;
#endif
int16_t ac2;
static int16_t z1;
if(rx_state == 0 || rx_state == 4){ // 1st stage: down-sample by 2
static int16_t za1;
int16_t _ac = ac + za1 + z1 * 2; // 1st stage: FA + FB
za1 = ac;
static int16_t _z1;
if(rx_state == 0){ // 2nd stage: down-sample by 2
static int16_t _za1;
ac2 = _ac + _za1 + _z1 * 2; // 2nd stage: FA + FB
_za1 = _ac;
{
ac2 >>= att2; // digital gain control
// post processing I and Q (down-sampled) results
static int16_t v[7];
i = v[0]; v[0] = v[1]; v[1] = v[2]; v[2] = v[3]; v[3] = v[4]; v[4] = v[5]; v[5] = v[6]; v[6] = ac2; // Delay to match Hilbert transform on Q branch
int16_t ac = i + qh;
ac = slow_dsp(ac);
// Output stage
static int16_t ozd1, ozd2;
if(_init){ ac = 0; ozd1 = 0; ozd2 = 0; _init = 0; } // hack: on first sample init accumlators of further stages (to prevent instability)
#define SECOND_ORDER_DUC 1
#ifdef SECOND_ORDER_DUC
int16_t od1 = ac - ozd1; // Comb section
ocomb = od1 - ozd2;
ozd2 = od1;
#else
ocomb = ac - ozd1; // Comb section
#endif
ozd1 = ac;
}
} else _z1 = _ac;
} else z1 = ac;
rx_state++;
}
void sdr_rx_q()
{
// process Q for odd samples [75% CPU@R=4;Fs=62.5k] (excluding the Comb branch and output stage)
ADMUX = admux[0]; // set MUX for next conversion
ADCSRA |= (1 << ADSC); // start next ADC conversion
int16_t adc = ADC - 511; // current ADC sample 10-bits analog input, NOTE: first ADCL, then ADCH
func_ptr = sdr_rx; // processing function for next conversion
#ifdef SECOND_ORDER_DUC
// sdr_rx_common(); //necessary? YES!... Maybe NOT!
#endif
//static int16_t dc;
//dc += (adc - dc) / 2; // we lose LSB with this method
//dc = (3*dc + adc)/4;
//int16_t ac = adc - dc; // DC decoupling
int16_t ac = adc;
#ifdef AUTO_ADC_BIAS
param_c = (7*param_c + adc)/8;
#endif
int16_t ac2;
static int16_t z1;
if(rx_state == 3 || rx_state == 7){ // 1st stage: down-sample by 2
static int16_t za1;
int16_t _ac = ac + za1 + z1 * 2; // 1st stage: FA + FB
za1 = ac;
static int16_t _z1;
if(rx_state == 7){ // 2nd stage: down-sample by 2
static int16_t _za1;
ac2 = _ac + _za1 + _z1 * 2; // 2nd stage: FA + FB
_za1 = _ac;
{
ac2 >>= att2; // digital gain control
// Process Q (down-sampled) samples
static int16_t v[14];
q = v[7];
qh = ((v[0] - ac2) * 2 + (v[2] - v[12]) * 8 + (v[4] - v[10]) * 21 + (v[6] - v[8]) * 15) / 128 + (v[6] - v[8]) / 2; // Hilbert transform, 40dB side-band rejection in 400..1900Hz (@4kSPS) when used in image-rejection scenario; (Hilbert transform require 5 additional bits)
for(uint8_t j = 0; j != 13; j++) v[j] = v[j + 1]; v[13] = ac2;
}
rx_state = 0; return;
} else _z1 = _ac;
} else z1 = ac;
rx_state++;
}
inline void sdr_rx_common()
{
static int16_t ozi1, ozi2;
if(_init){ ocomb=0; ozi1 = 0; ozi2 = 0; } // hack
// Output stage [25% CPU@R=4;Fs=62.5k]
#ifdef SECOND_ORDER_DUC
ozi2 = ozi1 + ozi2; // Integrator section
#endif
ozi1 = ocomb + ozi1;
#ifdef SECOND_ORDER_DUC
if(volume) OCR1AL = min(max((ozi2>>5) + 128, 0), 255); //if(volume) OCR1AL = min(max((ozi2>>5) + ICR1L/2, 0), ICR1L); // center and clip wrt PWM working range
#else
if(volume) OCR1AL = (ozi1>>5) + 128;
//if(volume) OCR1AL = min(max((ozi1>>5) + 128, 0), 255); //if(volume) OCR1AL = min(max((ozi2>>5) + ICR1L/2, 0), ICR1L); // center and clip wrt PWM working range
#endif
}
#endif
#ifdef SIMPLE_RX
volatile uint8_t admux[3];
static uint8_t rx_state = 0;
static struct rx {
int16_t z1;
int16_t za1;
int16_t _z1;
int16_t _za1;
} rx_inst[2];
void sdr_rx()
{
static int16_t ocomb;
static int16_t qh;
uint8_t b = !(rx_state & 0x01);
rx* p = &rx_inst[b];
uint8_t _rx_state;
int16_t ac;
if(b){ // rx_state == 0, 2, 4, 6 -> I-stage
ADMUX = admux[1]; // set MUX for next conversion
ADCSRA |= (1 << ADSC); // start next ADC conversion
ac = ADC - 512; // current ADC sample 10-bits analog input, NOTE: first ADCL, then ADCH
//sdr_common
static int16_t ozi1, ozi2;
if(_init){ ocomb=0; ozi1 = 0; ozi2 = 0; } // hack
// Output stage [25% CPU@R=4;Fs=62.5k]
#define SECOND_ORDER_DUC 1
#ifdef SECOND_ORDER_DUC
ozi2 = ozi1 + ozi2; // Integrator section
#endif
ozi1 = ocomb + ozi1;
#ifdef SECOND_ORDER_DUC
if(volume) OCR1AL = min(max((ozi2>>5) + 128, 0), 255); //if(volume) OCR1AL = min(max((ozi2>>5) + ICR1L/2, 0), ICR1L); // center and clip wrt PWM working range
#else
if(volume) OCR1AL = (ozi1>>5) + 128;
//if(volume) OCR1AL = min(max((ozi1>>5) + 128, 0), 255); //if(volume) OCR1AL = min(max((ozi2>>5) + ICR1L/2, 0), ICR1L); // center and clip wrt PWM working range
#endif
// Only for I: correct I/Q sample delay by means of linear interpolation
static int16_t prev_adc;
int16_t corr_adc = (prev_adc + ac) / 2;
prev_adc = ac;
ac = corr_adc;
_rx_state = ~rx_state;
} else {
ADMUX = admux[0]; // set MUX for next conversion
ADCSRA |= (1 << ADSC); // start next ADC conversion
ac = ADC - 512; // current ADC sample 10-bits analog input, NOTE: first ADCL, then ADCH
_rx_state = rx_state;
}
if(_rx_state & 0x02){ // rx_state == I: 0, 4 Q: 3, 7 1st stage: down-sample by 2
int16_t _ac = ac + p->za1 + p->z1 * 2; // 1st stage: FA + FB
p->za1 = ac;
if(_rx_state & 0x04){ // rx_state == I: 0 Q:7 2nd stage: down-sample by 2
int16_t ac2 = _ac + p->_za1 + p->_z1 * 2; // 2nd stage: FA + FB
p->_za1 = _ac;
if(b){
// post processing I and Q (down-sampled) results
ac2 >>= att2; // digital gain control
// post processing I and Q (down-sampled) results
static int16_t v[7];
i = v[0]; v[0] = v[1]; v[1] = v[2]; v[2] = v[3]; v[3] = v[4]; v[4] = v[5]; v[5] = v[6]; v[6] = ac2; // Delay to match Hilbert transform on Q branch
int16_t ac = i + qh;
ac = slow_dsp(ac);
// Output stage
static int16_t ozd1, ozd2;
if(_init){ ac = 0; ozd1 = 0; ozd2 = 0; _init = 0; } // hack: on first sample init accumlators of further stages (to prevent instability)
#ifdef SECOND_ORDER_DUC
int16_t od1 = ac - ozd1; // Comb section
ocomb = od1 - ozd2;
ozd2 = od1;
#else
ocomb = ac - ozd1; // Comb section
#endif
ozd1 = ac;
} else {
ac2 >>= att2; // digital gain control
// Process Q (down-sampled) samples
static int16_t v[14];
q = v[7];
qh = ((v[0] - ac2) * 2 + (v[2] - v[12]) * 8 + (v[4] - v[10]) * 21 + (v[6] - v[8]) * 15) / 128 + (v[6] - v[8]) / 2; // Hilbert transform, 40dB side-band rejection in 400..1900Hz (@4kSPS) when used in image-rejection scenario; (Hilbert transform require 5 additional bits)
for(uint8_t j = 0; j != 13; j++) v[j] = v[j + 1]; v[13] = ac2;
}
} else p->_z1 = _ac;
} else p->z1 = ac; // rx_state == I: 2, 6 Q: 1, 5
rx_state++;
}
//#pragma GCC push_options
//#pragma GCC optimize ("Ofast") // compiler-optimization for speed
//#pragma GCC pop_options // end of DSP section
// */
#endif

227
code/ui.h 100644
Wyświetl plik

@ -0,0 +1,227 @@
int8_t prev_bandval = 2;
int8_t bandval = 2;
#define N_BANDS 10
uint32_t band[N_BANDS] = { /*472000, 1840000,*/ 3573000, 5357000, 7074000, 10136000, 14074000, 18100000, 21074000, 24915000, 28074000, 50313000/*, 70101000, 144125000*/ };
enum step_t { STEP_10M, STEP_1M, STEP_500k, STEP_100k, STEP_10k, STEP_1k, STEP_500, STEP_100, STEP_10, STEP_1 };
int32_t stepsizes[10] = { 10000000, 1000000, 500000, 100000, 10000, 1000, 500, 100, 10, 1 };
volatile int8_t stepsize = STEP_1k;
int8_t prev_stepsize[] = { STEP_1k, STEP_500 }; //default stepsize for resp. SSB, CW
void process_encoder_tuning_step(int8_t steps)
{
int32_t stepval = stepsizes[stepsize];
//if(stepsize < STEP_100) freq %= 1000; // when tuned and stepsize > 100Hz then forget fine-tuning details
freq += steps * stepval;
//freq = max(1, min(99999999, freq));
change = true;
}
void stepsize_showcursor()
{
lcd.setCursor(stepsize+1, 1); // display stepsize with cursor
lcd.cursor();
}
void stepsize_change(int8_t val)
{
stepsize += val;
if(stepsize < STEP_1M) stepsize = STEP_10;
if(stepsize > STEP_10) stepsize = STEP_1M;
if(stepsize == STEP_10k || stepsize == STEP_500k) stepsize += val;
stepsize_showcursor();
}
void powerDown()
{ // Reduces power from 110mA to 70mA (back-light on) or 30mA (back-light off), remaining current is probably opamp quiescent current
lcd.setCursor(0, 1); lcd.print(F("Power-off 73 :-)")); lcd_blanks();
MCUSR = ~(1<<WDRF); // MSY be done before wdt_disable()
wdt_disable(); // WDTON Fuse High bit need to be 1 (0xD1), if NOT it will override and set WDE=1; WDIE=0, meaning MCU will reset when watchdog timer is zero, and this seems to happen when wdt_disable() is called
timer2_stop();
timer1_stop();
adc_stop();
si5351.powerDown();
delay(1500);
// Disable external interrupts INT0, INT1, Pin Change
PCICR = 0;
PCMSK0 = 0;
PCMSK1 = 0;
PCMSK2 = 0;
// Disable internal interrupts
TIMSK0 = 0;
TIMSK1 = 0;
TIMSK2 = 0;
WDTCSR = 0;
// Enable BUTTON Pin Change interrupt
*digitalPinToPCMSK(BUTTONS) |= (1<<digitalPinToPCMSKbit(BUTTONS));
*digitalPinToPCICR(BUTTONS) |= (1<<digitalPinToPCICRbit(BUTTONS));
// Power-down sub-systems
PRR = 0xff;
lcd.noDisplay();
set_sleep_mode(SLEEP_MODE_PWR_DOWN);
sleep_enable();
interrupts();
sleep_bod_disable();
//MCUCR |= (1<<BODS) | (1<<BODSE); // turn bod off by settings BODS, BODSE; note BODS is reset after three clock-cycles, so quickly go to sleep before it is too late
//MCUCR &= ~(1<<BODSE); // must be done right before sleep
sleep_cpu(); // go to sleep mode, wake-up by either INT0, INT1, Pin Change, TWI Addr Match, WDT, BOD
sleep_disable();
//void(* reset)(void) = 0; reset(); // soft reset by calling reset vector (does not reset registers to defaults)
do { wdt_enable(WDTO_15MS); for(;;); } while(0); // soft reset by trigger watchdog timeout
}
void show_banner(){
lcd.setCursor(0, 0);
#ifdef QCX
lcd.print(F("QCX"));
const char* cap_label[] = { "SSB", "DSP", "SDR" };
if(ssb_cap || dsp_cap){ lcd.print(F("-")); lcd.print(cap_label[dsp_cap]); }
#else
lcd.print(F("uSDX"));
#endif
lcd.print(F("\x01 ")); lcd_blanks();
}
const char* mode_label[5] = { "LSB", "USB", "CW ", "AM ", "FM " };
void display_vfo(uint32_t f){
lcd.setCursor(0, 1);
lcd.print('\x06'); // VFO A/B
uint32_t scale=10e6; // VFO frequency
if(f/scale == 0){ lcd.print(' '); scale/=10; } // Initial space instead of zero
for(; scale!=1; f%=scale, scale/=10){
lcd.print(f/scale);
if(scale == (uint32_t)1e3 || scale == (uint32_t)1e6) lcd.print(','); // Thousands separator
}
lcd.print(" "); lcd.print(mode_label[mode]); lcd.print(" ");
lcd.setCursor(15, 1); lcd.print("R");
}
volatile uint8_t event;
volatile uint8_t menumode = 0; // 0=not in menu, 1=selects menu item, 2=selects parameter value
volatile int8_t menu = 0; // current parameter id selected in menu
#define pgm_cache_item(addr, sz) byte _item[sz]; memcpy_P(_item, addr, sz); // copy array item from PROGMEM to SRAM
#define get_version_id() ((VERSION[0]-'1') * 2048 + ((VERSION[2]-'0')*10 + (VERSION[3]-'0')) * 32 + ((VERSION[4]) ? (VERSION[4] - 'a' + 1) : 0) * 1) // converts VERSION string with (fixed) format "9.99z" into uint16_t (max. values shown here, z may be removed)
uint8_t eeprom_version;
#define EEPROM_OFFSET 0x150 // avoid collision with QCX settings, overwrites text settings though
int eeprom_addr;
// Support functions for parameter and menu handling
enum action_t { UPDATE, UPDATE_MENU, LOAD, SAVE, SKIP };
template<typename T> void paramAction(uint8_t action, T& value, const __FlashStringHelper* menuid, const __FlashStringHelper* label, const char* enumArray[], int32_t _min, int32_t _max, bool continuous){
switch(action){
case UPDATE:
case UPDATE_MENU:
if(((int32_t)value + encoder_val) < _min) value = (continuous) ? _max : _min;
else value += encoder_val;
encoder_val = 0;
if(continuous) value = (value % (_max+1));
value = max(_min, min((int32_t)value, _max));
if(action == UPDATE_MENU){
lcd.setCursor(0, 0);
lcd.print(menuid); lcd.print(' ');
lcd.print(label); lcd_blanks(); lcd_blanks();
lcd.setCursor(0, 1); // value on next line
} else { // UPDATE (not in menu)
lcd.setCursor(0, 1); lcd.print(label); lcd.print(F(": "));
}
if(enumArray == NULL){
if((_min < 0) && (value >= 0)) lcd.print('+');
lcd.print(value);
} else {
lcd.print(enumArray[value]);
}
lcd_blanks(); lcd_blanks();
//if(action == UPDATE) paramAction(SAVE, value, menuid, label, enumArray, _min, _max, continuous, init_val);
break;
case LOAD:
for(uint8_t* ptr = (uint8_t *) &value, n = sizeof(value); n; --n) *ptr++ = eeprom_read_byte((uint8_t *)eeprom_addr++);
break;
case SAVE:
for(uint8_t* ptr = (uint8_t *) &value, n = sizeof(value); n; --n) eeprom_write_byte((uint8_t *)eeprom_addr++, *ptr++);
break;
case SKIP:
eeprom_addr += sizeof(value);
break;
}
}
uint32_t save_event_time = 0;
uint32_t sec_event_time = 0;
static uint8_t pwm_min = 0; // PWM value for which PA reaches its minimum: 29 when C31 installed; 0 when C31 removed; 0 for biasing BS170 directly
static uint8_t pwm_max = 220; // PWM value for which PA reaches its maximum: 96 when C31 installed; 255 when C31 removed; 220 for biasing BS170 directly
const char* offon_label[2] = {"OFF", "ON"};
const char* filt_label[N_FILT+1] = { "Full", "4000", "2500", "1700", "500", "200", "100", "50" };
const char* band_label[N_BANDS] = { "80m", "60m", "40m", "30m", "20m", "17m", "15m", "12m", "10m", "6m" };
#define _N(a) sizeof(a)/sizeof(a[0])
#define N_PARAMS 26 // number of (visible) parameters
#define N_ALL_PARAMS (N_PARAMS+2) // number of parameters
enum params_t {ALL, VOLUME, MODE, FILTER, BAND, STEP, AGC, NR, ATT, ATT2, SMETER, CWDEC, CWTONE, CWOFF, VOX, VOXGAIN, MOX, DRIVE, SIFXTAL, PWM_MIN, PWM_MAX, CALIB, SR, CPULOAD, PARAM_A, PARAM_B, PARAM_C, FREQ, VERS};
void paramAction(uint8_t action, uint8_t id = ALL) // list of parameters
{
if((action == SAVE) || (action == LOAD)){
eeprom_addr = EEPROM_OFFSET;
for(uint8_t _id = 1; _id < id; _id++) paramAction(SKIP, _id);
}
if(id == ALL) for(id = 1; id != N_ALL_PARAMS+1; id++) paramAction(action, id); // for all parameters
const char* stepsize_label[10] = { "10M", "1M", "0.5M", "100k", "10k", "1k", "0.5k", "100", "10", "1" };
const char* att_label[] = { "0dB", "-13dB", "-20dB", "-33dB", "-40dB", "-53dB", "-60dB", "-73dB" };
const char* smode_label[4] = { "OFF", "dBm", "S", "S-bar" };
const char* cw_tone_label[4] = { "325", "700" };
switch(id){
// Visible parameters
case VOLUME: paramAction(action, volume, F("1.1"), F("Volume"), NULL, -1, 16, false); break;
case MODE: paramAction(action, mode, F("1.2"), F("Mode"), mode_label, 0, _N(mode_label) - 1, true); break;
case FILTER: paramAction(action, filt, F("1.3"), F("Filter BW"), filt_label, 0, _N(filt_label) - 1, false); break;
case BAND: paramAction(action, bandval, F("1.4"), F("Band"), band_label, 0, _N(band_label) - 1, false); break;
case STEP: paramAction(action, stepsize, F("1.5"), F("Tune Rate"), stepsize_label, 0, _N(stepsize_label) - 1, false); break;
case AGC: paramAction(action, agc, F("1.6"), F("AGC"), offon_label, 0, 1, false); break;
case NR: paramAction(action, nr, F("1.7"), F("NR"), NULL, 0, 8, false); break;
case ATT: paramAction(action, att, F("1.8"), F("ATT"), att_label, 0, 7, false); break;
case ATT2: paramAction(action, att2, F("1.9"), F("ATT2"), NULL, 0, 16, false); break;
case SMETER: paramAction(action, smode, F("1.10"), F("S-meter"), smode_label, 0, _N(smode_label) - 1, false); break;
case CWDEC: paramAction(action, cwdec, F("2.1"), F("CW Decoder"), offon_label, 0, 1, false); break;
case CWTONE: paramAction(action, cw_tone, F("2.2"), F("CW Tone"), cw_tone_label, 0, 1, false); break;
case CWOFF: paramAction(action, cw_offset, F("2.3"), F("CW Offset"), NULL, 300, 2000, false); break;
case VOX: paramAction(action, vox, F("3.1"), F("VOX"), offon_label, 0, 1, false); break;
case VOXGAIN: paramAction(action, vox_thresh, F("3.2"), F("VOX Level"), NULL, 0, 255, false); break;
case MOX: paramAction(action, mox, F("3.3"), F("MOX"), NULL, 0, 4, false); break;
case DRIVE: paramAction(action, drive, F("3.4"), F("TX Drive"), NULL, 0, 8, false); break;
case SIFXTAL: paramAction(action, si5351.fxtal, F("8.1"), F("Ref freq"), NULL, 14000000, 28000000, false); break;
case PWM_MIN: paramAction(action, pwm_min, F("8.2"), F("PA Bias min"), NULL, 0, 255, false); break;
case PWM_MAX: paramAction(action, pwm_max, F("8.3"), F("PA Bias max"), NULL, 0, 255, false); break;
#ifdef CAL_IQ
case CALIB: if(dsp_cap != SDR) paramAction(action, cal_iq_dummy, F("8.4"), F("IQ Test/Cal."), NULL, 0, 0, false); break;
#endif
#ifdef DEBUG
case SR: paramAction(action, sr, F("9.1"), F("Sample rate"), NULL, -2147483648, 2147483647, false); break;
case CPULOAD: paramAction(action, cpu_load, F("9.2"), F("CPU load %"), NULL, -2147483648, 2147483647, false); break;
case PARAM_A: paramAction(action, param_a, F("9.3"), F("Param A"), NULL, 0, 65535, false); break;
case PARAM_B: paramAction(action, param_b, F("9.4"), F("Param B"), NULL, -32768, 32767, false); break;
case PARAM_C: paramAction(action, param_c, F("9.5"), F("Param C"), NULL, -32768, 32767, false); break;
#endif
// Invisible parameters
case FREQ: paramAction(action, freq, NULL, NULL, NULL, 0, 0, false); break;
case VERS: paramAction(action, eeprom_version, NULL, NULL, NULL, 0, 0, false); break;
}
}