diff --git a/.cproject b/.cproject
index 180c0f6..fb00609 100644
--- a/.cproject
+++ b/.cproject
@@ -14,13 +14,13 @@
-
+
-
+
@@ -44,20 +44,81 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
-
-
-
-
-
-
diff --git a/.settings/language.settings.xml b/.settings/language.settings.xml
index 9c2ffe1..c2188e1 100644
--- a/.settings/language.settings.xml
+++ b/.settings/language.settings.xml
@@ -12,4 +12,16 @@
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/Makefile b/Makefile
index 4d2b580..bc4a5a3 100644
--- a/Makefile
+++ b/Makefile
@@ -6,15 +6,16 @@
#Build target
ifeq ($(TARGET),)
TARGET = F072
+else
+ TARGET=F303
endif
-TARGET=F303
# Compiler options here.
ifeq ($(USE_OPT),)
ifeq ($(TARGET),F303)
USE_OPT = -Og -fno-inline-small-functions -ggdb -fomit-frame-pointer -falign-functions=16 --specs=nano.specs -fstack-usage -std=c11
else
-USE_OPT = -Og -fno-inline-small-functions -ggdb -fomit-frame-pointer -falign-functions=16 --specs=nano.specs -fstack-usage -std=c11
+USE_OPT = -Og -fno-inline-small-functions -ggdb -fomit-frame-pointer -falign-functions=16 --specs=nano.specs -fstack-usage -fsingle-precision-constant
endif
endif
@@ -98,24 +99,29 @@ endif
#
# Define project name here
+ifeq ($(TARGET),F303)
PROJECT = tinySA4
+else
+PROJECT = tinySA
+endif
# Imported source files and paths
#CHIBIOS = ../ChibiOS-RT
CHIBIOS = ChibiOS
PROJ = .
# Startup files.
-# HAL-OSAL files (optional).
+
ifeq ($(TARGET),F303)
include $(CHIBIOS)/os/common/startup/ARMCMx/compilers/GCC/mk/startup_stm32f3xx.mk
include $(CHIBIOS)/os/hal/hal.mk
include $(CHIBIOS)/os/hal/ports/STM32/STM32F3xx/platform.mk
include NANOVNA_STM32_F303/board.mk
else
- include $(CHIBIOS)/os/common/startup/ARMCMx/compilers/GCC/mk/startup_stm32f0xx.mk
- include $(CHIBIOS)/os/hal/hal.mk
- include $(CHIBIOS)/os/hal/ports/STM32/STM32F0xx/platform.mk
- include NANOVNA_STM32_F072/board.mk
+include $(CHIBIOS)/os/common/startup/ARMCMx/compilers/GCC/mk/startup_stm32f0xx.mk
+# HAL-OSAL files (optional).
+include $(CHIBIOS)/os/hal/hal.mk
+include $(CHIBIOS)/os/hal/ports/STM32/STM32F0xx/platform.mk
+include NANOVNA_STM32_F072/board.mk
endif
include $(CHIBIOS)/os/hal/osal/rt/osal.mk
@@ -132,6 +138,7 @@ include $(CHIBIOS)/os/hal/lib/streams/streams.mk
#include $(CHIBIOS)/os/various/shell/shell.mk
# Define linker script file here
+#LDSCRIPT= $(STARTUPLD)/STM32F072xB.ld
ifeq ($(TARGET),F303)
LDSCRIPT= STM32F303xC.ld
else
@@ -140,6 +147,7 @@ endif
# C sources that can be compiled in ARM or THUMB mode depending on the global
# setting.
+ifeq ($(TARGET),F303)
CSRC = $(STARTUPSRC) \
$(KERNSRC) \
$(PORTSRC) \
@@ -151,7 +159,19 @@ CSRC = $(STARTUPSRC) \
FatFs/ff.c \
FatFs/ffunicode.c \
usbcfg.c \
- main.c plot.c ui.c ili9341.c tlv320aic3204.c si5351.c numfont20x22.c Font5x7.c Font10x14.c flash.c adc.c si4432.c Font7x13b.c rtc.c
+ main.c plot.c ui.c ili9341.c tlv320aic3204.c si5351.c numfont20x22.c Font5x7.c Font10x14.c flash.c adc_F303.c si4468.c Font7x13b.c rtc.c
+else
+CSRC = $(STARTUPSRC) \
+ $(KERNSRC) \
+ $(PORTSRC) \
+ $(OSALSRC) \
+ $(HALSRC) \
+ $(PLATFORMSRC) \
+ $(BOARDSRC) \
+ $(STREAMSSRC) \
+ usbcfg.c \
+ main.c plot.c ui.c ili9341.c numfont20x22.c Font5x7.c Font10x14.c flash.c adc.c si4432.c Font7x13b.c
+endif
# C++ sources that can be compiled in ARM or THUMB mode depending on the global
# setting.
@@ -238,14 +258,14 @@ CPPWARN = -Wall -Wextra -Wundef
# List all user C define here, like -D_DEBUG=1
ifeq ($(TARGET),F303)
- UDEFS = -DARM_MATH_CM4 -DVERSION=\"$(VERSION)\" -DTINYSA_F303 -D__FPU_PRESENT -D__FPU_USED -DST7796S
+ UDEFS = -DARM_MATH_CM4 -DVERSION=\"$(VERSION)\" -DTINYSA_F303 -D__FPU_PRESENT -D__FPU_USED -DST7796S -DTINYSA4
#Enable if install external 32.768kHz clock quartz on PC14 and PC15 pins on STM32 CPU
#UDEFS+= -DVNA_USE_LSE
# Use R as usb pullup
UDEFS+= -DUSB_DP_R_VDD
#-DCH_DBG_STATISTICS
else
- UDEFS = -DARM_MATH_CM0 -DVERSION=\"$(VERSION)\"
+UDEFS = -DSHELL_CMD_TEST_ENABLED=FALSE -DSHELL_CMD_MEM_ENABLED=FALSE -DARM_MATH_CM0 -DVERSION=\"$(VERSION)\"
endif
# Define ASM defines here
diff --git a/adc.c b/adc.c
index 556ec6a..5123d20 100644
--- a/adc.c
+++ b/adc.c
@@ -21,111 +21,79 @@
#include "hal.h"
#include "nanovna.h"
-#define ADC_FULL_SCALE 3300
-#define F303_ADC_VREF_ALWAYS_ON
-
-#define ADC_CHSELR_VREFINT ADC_CHANNEL_IN18
-#define ADC_CHSELR_VBAT ADC_CHANNEL_IN17
-
-#define ADC_TOUCH_SMP_TIME ADC_SMPR_SMP_1P5
-#define ADC_TOUCH_XY_SMP_TIME ADC_SMPR_SMP_601P5
-#define ADC_VBAT_SMP_TIME ADC_SMPR_SMP_601P5
-
-#define ADC_GRP_NUM_CHANNELS_VBAT 2
-static adcsample_t samplesVBAT[ADC_GRP_NUM_CHANNELS_VBAT];
-static adcsample_t samples[1];
-
-static const ADCConversionGroup adcgrpcfgVBAT = {
- FALSE,
- ADC_GRP_NUM_CHANNELS_VBAT,
- NULL,
- NULL,
- ADC_CFGR_CONT | ADC_CFGR1_RES_12BIT, // CFGR1
- ADC_TR(0, 0), // ADC watchdog threshold TR1
- {0, ADC_SMPR2_SMP_AN16(ADC_VBAT_SMP_TIME) | ADC_SMPR2_SMP_AN17(ADC_VBAT_SMP_TIME)/*| ADC_SMPR2_SMP_AN18(ADC_VBAT_SMP_TIME)*/}, // SMPR
- {ADC_SQR1_SQ1_N(ADC_CHANNEL_IN17) | ADC_SQR1_SQ2_N(ADC_CHANNEL_IN18)/*| ADC_SQR1_SQ3_N(ADC_CHANNEL_IN16)*/, 0, 0, 0} // CHSELR
-};
-
-static const ADCConversionGroup adcgrpcfgTouch = {
- TRUE, // Enables the circular buffer mode for the group.
- 1, // Number of the analog channels belonging to the conversion group.
- NULL, // adccallback_touch
- NULL, // adcerrorcallback_touch
- // CFGR
- ADC_CFGR_EXTEN_0 // rising edge of external trigger
- | ADC_CFGR_EXTSEL_2 // EXT4 0x1000 event (TIM3_TRGO)
- | ADC_CFGR_AWD1EN, // Enable Analog watchdog check interrupt
- ADC_TR(0, TOUCH_THRESHOLD), // Analog watchdog threshold TR1, interrupt on touch press
- {ADC_SMPR1_SMP_AN4(ADC_TOUCH_SMP_TIME), 0}, // SMPR[2]
- {ADC_SQR1_SQ1_N(ADC_CHANNEL_IN4), 0, 0, 0} // SQR[4]
-};
-
-static ADCConversionGroup adcgrpcfgXY = {
- FALSE,
- 1,
- NULL, /* adccallback_touch */
- NULL, /* adcerrorcallback_touch */
- ADC_CFGR1_RES_12BIT, /* CFGR */
- ADC_TR(0, 0), /* TR1 */
- {ADC_SMPR1_SMP_AN3(ADC_TOUCH_XY_SMP_TIME) | ADC_SMPR1_SMP_AN4(ADC_TOUCH_XY_SMP_TIME), 0}, /* SMPR[2] */
- {ADC_SQR1_SQ1_N(ADC_CHANNEL_IN3), 0, 0, 0} /* SQR[4] */
-};
+
+#define ADC_TR(low, high) (((uint32_t)(high) << 16U) | \
+ (uint32_t)(low))
+#define ADC_SMPR_SMP_1P5 0U /**< @brief 14 cycles conversion time */
+#define ADC_SMPR_SMP_239P5 7U /**< @brief 252 cycles conversion time. */
+#define ADC_CFGR1_RES_12BIT (0U << 3U)
+
+#define VNA_ADC ADC1
void adc_init(void)
{
- adcStart(&ADCD2, NULL);
- adcStart(&ADCD1, NULL);
- #ifdef F303_ADC_VREF_ALWAYS_ON
- adcSTM32EnableVBAT(&ADCD1);
- adcSTM32EnableVREF(&ADCD1);
-// adcSTM32EnableTS(&ADCD1);
- #endif
+ rccEnableADC1(FALSE);
+
+ /* Ensure flag states */
+ VNA_ADC->IER = 0;
+
+ /* Calibration procedure.*/
+ ADC->CCR = 0;
+ if (VNA_ADC->CR & ADC_CR_ADEN) {
+ VNA_ADC->CR |= ~ADC_CR_ADDIS; /* Disable ADC */
+ }
+ while (VNA_ADC->CR & ADC_CR_ADEN)
+ ;
+ VNA_ADC->CFGR1 &= ~ADC_CFGR1_DMAEN;
+ VNA_ADC->CR |= ADC_CR_ADCAL;
+ while (VNA_ADC->CR & ADC_CR_ADCAL)
+ ;
+
+ if (VNA_ADC->ISR & ADC_ISR_ADRDY) {
+ VNA_ADC->ISR |= ADC_ISR_ADRDY; /* clear ADRDY */
+ }
+ /* Enable ADC */
+ VNA_ADC->CR |= ADC_CR_ADEN;
+ while (!(VNA_ADC->ISR & ADC_ISR_ADRDY))
+ ;
}
uint16_t adc_single_read(uint32_t chsel)
{
/* ADC setup */
-// adcStart(&ADCD2, NULL);
- adcgrpcfgXY.sqr[0] = ADC_SQR1_SQ1_N(chsel);
- adcConvert(&ADCD2, &adcgrpcfgXY, samples, 1);
- return(samples[0]);
+ VNA_ADC->ISR = VNA_ADC->ISR;
+ VNA_ADC->IER = 0;
+ VNA_ADC->TR = ADC_TR(0, 0);
+ VNA_ADC->SMPR = ADC_SMPR_SMP_239P5;
+ VNA_ADC->CFGR1 = ADC_CFGR1_RES_12BIT;
+ VNA_ADC->CHSELR = chsel;
+
+ uint32_t result = 0;
+ uint32_t count = 1<<3; // Average count
+ do{
+ VNA_ADC->CR |= ADC_CR_ADSTART; // ADC conversion start.
+ while (VNA_ADC->CR & ADC_CR_ADSTART)
+ ;
+ result+=VNA_ADC->DR;
+ }while(--count);
+ return result>>3;
}
int16_t adc_vbat_read(void)
{
- uint16_t VREFINT_CAL = (*((uint16_t*)0x1FFFF7BA));
- uint32_t vbat;
- uint32_t vrefint;
-// const uint16_t V25 = 1750;// when V25=1.41V at ref 3.3V
-// const uint16_t Avg_Slope = 5; //when avg_slope=4.3mV/C at ref 3.3V
-// uint16_t temperature_cal1 = *((uint16_t*) ((uint32_t)0x1FFFF7B8U));
-// /* Internal temperature sensor, address of parameter TS_CAL1: On STM32F3,
-// temperature sensor ADC raw data acquired at temperature 25 DegC (tolerance: +-5 DegC),
-// Vref+ = 3.3 V (tolerance: +-10 mV). */
-// uint16_t temperature_cal2 = *((uint16_t*) ((uint32_t)0x1FFFF7C2U));
-// /* Internal temperature sensor, address of parameter TS_CAL2: On STM32F3,
-// temperature sensor ADC raw data acquired at temperature 110 DegC (tolerance: +-5 DegC),
-// Vref+ = 3.3 V (tolerance: +-10 mV). */
-// float avg_slope = ((float)(temperature_cal1 - temperature_cal2))/(110-25);
-// float ts;
- #ifndef F303_ADC_VREF_ALWAYS_ON
- adcSTM32EnableVBAT(&ADCD1);
- adcSTM32EnableVREF(&ADCD1);
-// adcSTM32EnableTS(&ADCD1);
- adcConvert(&ADCD1, &adcgrpcfgVBAT, samplesVBAT, ADC_GRP_BUF_DEPTH_VBAT);
- adcSTM32DisableVBAT(&ADCD1);
- adcSTM32DisableVREF(&ADCD1);
-// adcSTM32DisableTS(&ADCD1);
- #else
- adcConvert(&ADCD1, &adcgrpcfgVBAT, samplesVBAT, sizeof(samplesVBAT)/(sizeof(adcsample_t)*ADC_GRP_NUM_CHANNELS_VBAT));
- #endif
- vbat = samplesVBAT[0];
- vrefint = samplesVBAT[1];
-// ts = samplesVBAT[2];
-// uint16_t vts = (ADC_FULL_SCALE * VREFINT_CAL * ts / (vrefint * ((1<<12)-1)));
-// uint16_t TemperatureC2 = (uint16_t)((V25-ts)/Avg_Slope+25);
-// uint16_t TemperatureC = (uint16_t)((V25-ts)/avg_slope+25);
-
+// 13.9 Temperature sensor and internal reference voltage
+// VREFINT_CAL calibrated on 3.3V, need get value in mV
+#define ADC_FULL_SCALE 3300
+#define VREFINT_CAL (*((uint16_t*)0x1FFFF7BA))
+ adc_stop();
+ ADC->CCR |= ADC_CCR_VREFEN | ADC_CCR_VBATEN;
+ // VREFINT == ADC_IN17
+ uint32_t vrefint = adc_single_read(ADC_CHSELR_CHSEL17);
+ // VBAT == ADC_IN18
+ // VBATEN enables resiter devider circuit. It consume vbat power.
+ uint32_t vbat = adc_single_read(ADC_CHSELR_CHSEL18);
+ ADC->CCR &= ~(ADC_CCR_VREFEN | ADC_CCR_VBATEN);
+ touch_start_watchdog();
// vbat_raw = (3300 * 2 * vbat / 4095) * (VREFINT_CAL / vrefint)
// uint16_t vbat_raw = (ADC_FULL_SCALE * VREFINT_CAL * (float)vbat * 2 / (vrefint * ((1<<12)-1)));
// For speed divide not on 4095, divide on 4096, get little error, but no matter
@@ -137,41 +105,61 @@ int16_t adc_vbat_read(void)
return vbat_raw + config.vbat_offset;
}
-void adc_start_analog_watchdogd(void)
+void adc_start_analog_watchdogd(uint32_t chsel)
{
-// adcStart(&ADCD2, NULL);
- adcStartConversion(&ADCD2, &adcgrpcfgTouch, samples, 1);
+ uint32_t cfgr1;
+
+ cfgr1 = ADC_CFGR1_RES_12BIT | ADC_CFGR1_AWDEN
+ | ADC_CFGR1_EXTEN_0 // rising edge of external trigger
+ | ADC_CFGR1_EXTSEL_0 | ADC_CFGR1_EXTSEL_1; // TRG3 , /* CFGR1 */
+
+ /* ADC setup, if it is defined a callback for the analog watch dog then it
+ is enabled.*/
+ VNA_ADC->ISR = VNA_ADC->ISR;
+ VNA_ADC->IER = ADC_IER_AWDIE;
+ VNA_ADC->TR = ADC_TR(0, TOUCH_THRESHOLD);
+ VNA_ADC->SMPR = ADC_SMPR_SMP_1P5;
+ VNA_ADC->CHSELR = chsel;
+
+ /* ADC configuration and start.*/
+ VNA_ADC->CFGR1 = cfgr1;
+
+ /* ADC conversion start.*/
+ VNA_ADC->CR |= ADC_CR_ADSTART;
}
void adc_stop(void)
{
- #if 1
- adcStopConversion(&ADCD2);
- #else
- if (ADC2->CR & ADC_CR_ADEN) {
- if (ADC2->CR & ADC_CR_ADSTART) {
- ADC2->CR |= ADC_CR_ADSTP;
- while (ADC2->CR & ADC_CR_ADSTP)
+ if (VNA_ADC->CR & ADC_CR_ADEN) {
+ if (VNA_ADC->CR & ADC_CR_ADSTART) {
+ VNA_ADC->CR |= ADC_CR_ADSTP;
+ while (VNA_ADC->CR & ADC_CR_ADSTP)
;
}
+
+ /* VNA_ADC->CR |= ADC_CR_ADDIS;
+ while (VNA_ADC->CR & ADC_CR_ADDIS)
+ ;*/
}
- #endif
}
-static inline void adc_interrupt(void)
+void adc_interrupt(void)
{
- uint32_t isr = ADC2->ISR;
- ADC2->ISR = isr;
+ uint32_t isr = VNA_ADC->ISR;
+ VNA_ADC->ISR = isr;
+
if (isr & ADC_ISR_OVR) {
-// ADC overflow condition, this could happen only if the DMA is unable to read data fast enough.
+ /* ADC overflow condition, this could happen only if the DMA is unable
+ to read data fast enough.*/
+
}
- if (isr & ADC_ISR_AWD1) {
+ if (isr & ADC_ISR_AWD) {
/* Analog watchdog error.*/
handle_touch_interrupt();
}
}
-OSAL_IRQ_HANDLER(STM32_ADC2_HANDLER)
+OSAL_IRQ_HANDLER(STM32_ADC1_HANDLER)
{
OSAL_IRQ_PROLOGUE();
@@ -180,7 +168,7 @@ OSAL_IRQ_HANDLER(STM32_ADC2_HANDLER)
OSAL_IRQ_EPILOGUE();
}
-#if 0
+#if 1
uint16_t adc_multi_read(uint32_t chsel, uint16_t *result, uint32_t count)
{
/* ADC setup */
diff --git a/adc_F303.c b/adc_F303.c
new file mode 100644
index 0000000..556ec6a
--- /dev/null
+++ b/adc_F303.c
@@ -0,0 +1,237 @@
+/*
+ * Copyright (c) 2014-2015, TAKAHASHI Tomohiro (TTRFTECH) edy555@gmail.com
+ * All rights reserved.
+ *
+ * This is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 3, or (at your option)
+ * any later version.
+ *
+ * The software 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 General Public License
+ * along with GNU Radio; see the file COPYING. If not, write to
+ * the Free Software Foundation, Inc., 51 Franklin Street,
+ * Boston, MA 02110-1301, USA.
+ */
+#include "ch.h"
+#include "hal.h"
+#include "nanovna.h"
+
+#define ADC_FULL_SCALE 3300
+#define F303_ADC_VREF_ALWAYS_ON
+
+#define ADC_CHSELR_VREFINT ADC_CHANNEL_IN18
+#define ADC_CHSELR_VBAT ADC_CHANNEL_IN17
+
+#define ADC_TOUCH_SMP_TIME ADC_SMPR_SMP_1P5
+#define ADC_TOUCH_XY_SMP_TIME ADC_SMPR_SMP_601P5
+#define ADC_VBAT_SMP_TIME ADC_SMPR_SMP_601P5
+
+#define ADC_GRP_NUM_CHANNELS_VBAT 2
+static adcsample_t samplesVBAT[ADC_GRP_NUM_CHANNELS_VBAT];
+static adcsample_t samples[1];
+
+static const ADCConversionGroup adcgrpcfgVBAT = {
+ FALSE,
+ ADC_GRP_NUM_CHANNELS_VBAT,
+ NULL,
+ NULL,
+ ADC_CFGR_CONT | ADC_CFGR1_RES_12BIT, // CFGR1
+ ADC_TR(0, 0), // ADC watchdog threshold TR1
+ {0, ADC_SMPR2_SMP_AN16(ADC_VBAT_SMP_TIME) | ADC_SMPR2_SMP_AN17(ADC_VBAT_SMP_TIME)/*| ADC_SMPR2_SMP_AN18(ADC_VBAT_SMP_TIME)*/}, // SMPR
+ {ADC_SQR1_SQ1_N(ADC_CHANNEL_IN17) | ADC_SQR1_SQ2_N(ADC_CHANNEL_IN18)/*| ADC_SQR1_SQ3_N(ADC_CHANNEL_IN16)*/, 0, 0, 0} // CHSELR
+};
+
+static const ADCConversionGroup adcgrpcfgTouch = {
+ TRUE, // Enables the circular buffer mode for the group.
+ 1, // Number of the analog channels belonging to the conversion group.
+ NULL, // adccallback_touch
+ NULL, // adcerrorcallback_touch
+ // CFGR
+ ADC_CFGR_EXTEN_0 // rising edge of external trigger
+ | ADC_CFGR_EXTSEL_2 // EXT4 0x1000 event (TIM3_TRGO)
+ | ADC_CFGR_AWD1EN, // Enable Analog watchdog check interrupt
+ ADC_TR(0, TOUCH_THRESHOLD), // Analog watchdog threshold TR1, interrupt on touch press
+ {ADC_SMPR1_SMP_AN4(ADC_TOUCH_SMP_TIME), 0}, // SMPR[2]
+ {ADC_SQR1_SQ1_N(ADC_CHANNEL_IN4), 0, 0, 0} // SQR[4]
+};
+
+static ADCConversionGroup adcgrpcfgXY = {
+ FALSE,
+ 1,
+ NULL, /* adccallback_touch */
+ NULL, /* adcerrorcallback_touch */
+ ADC_CFGR1_RES_12BIT, /* CFGR */
+ ADC_TR(0, 0), /* TR1 */
+ {ADC_SMPR1_SMP_AN3(ADC_TOUCH_XY_SMP_TIME) | ADC_SMPR1_SMP_AN4(ADC_TOUCH_XY_SMP_TIME), 0}, /* SMPR[2] */
+ {ADC_SQR1_SQ1_N(ADC_CHANNEL_IN3), 0, 0, 0} /* SQR[4] */
+};
+
+void adc_init(void)
+{
+ adcStart(&ADCD2, NULL);
+ adcStart(&ADCD1, NULL);
+ #ifdef F303_ADC_VREF_ALWAYS_ON
+ adcSTM32EnableVBAT(&ADCD1);
+ adcSTM32EnableVREF(&ADCD1);
+// adcSTM32EnableTS(&ADCD1);
+ #endif
+}
+
+uint16_t adc_single_read(uint32_t chsel)
+{
+ /* ADC setup */
+// adcStart(&ADCD2, NULL);
+ adcgrpcfgXY.sqr[0] = ADC_SQR1_SQ1_N(chsel);
+ adcConvert(&ADCD2, &adcgrpcfgXY, samples, 1);
+ return(samples[0]);
+}
+
+int16_t adc_vbat_read(void)
+{
+ uint16_t VREFINT_CAL = (*((uint16_t*)0x1FFFF7BA));
+ uint32_t vbat;
+ uint32_t vrefint;
+// const uint16_t V25 = 1750;// when V25=1.41V at ref 3.3V
+// const uint16_t Avg_Slope = 5; //when avg_slope=4.3mV/C at ref 3.3V
+// uint16_t temperature_cal1 = *((uint16_t*) ((uint32_t)0x1FFFF7B8U));
+// /* Internal temperature sensor, address of parameter TS_CAL1: On STM32F3,
+// temperature sensor ADC raw data acquired at temperature 25 DegC (tolerance: +-5 DegC),
+// Vref+ = 3.3 V (tolerance: +-10 mV). */
+// uint16_t temperature_cal2 = *((uint16_t*) ((uint32_t)0x1FFFF7C2U));
+// /* Internal temperature sensor, address of parameter TS_CAL2: On STM32F3,
+// temperature sensor ADC raw data acquired at temperature 110 DegC (tolerance: +-5 DegC),
+// Vref+ = 3.3 V (tolerance: +-10 mV). */
+// float avg_slope = ((float)(temperature_cal1 - temperature_cal2))/(110-25);
+// float ts;
+ #ifndef F303_ADC_VREF_ALWAYS_ON
+ adcSTM32EnableVBAT(&ADCD1);
+ adcSTM32EnableVREF(&ADCD1);
+// adcSTM32EnableTS(&ADCD1);
+ adcConvert(&ADCD1, &adcgrpcfgVBAT, samplesVBAT, ADC_GRP_BUF_DEPTH_VBAT);
+ adcSTM32DisableVBAT(&ADCD1);
+ adcSTM32DisableVREF(&ADCD1);
+// adcSTM32DisableTS(&ADCD1);
+ #else
+ adcConvert(&ADCD1, &adcgrpcfgVBAT, samplesVBAT, sizeof(samplesVBAT)/(sizeof(adcsample_t)*ADC_GRP_NUM_CHANNELS_VBAT));
+ #endif
+ vbat = samplesVBAT[0];
+ vrefint = samplesVBAT[1];
+// ts = samplesVBAT[2];
+// uint16_t vts = (ADC_FULL_SCALE * VREFINT_CAL * ts / (vrefint * ((1<<12)-1)));
+// uint16_t TemperatureC2 = (uint16_t)((V25-ts)/Avg_Slope+25);
+// uint16_t TemperatureC = (uint16_t)((V25-ts)/avg_slope+25);
+
+ // vbat_raw = (3300 * 2 * vbat / 4095) * (VREFINT_CAL / vrefint)
+ // uint16_t vbat_raw = (ADC_FULL_SCALE * VREFINT_CAL * (float)vbat * 2 / (vrefint * ((1<<12)-1)));
+ // For speed divide not on 4095, divide on 4096, get little error, but no matter
+ uint16_t vbat_raw = ((ADC_FULL_SCALE * 2 * vbat)>>12) * VREFINT_CAL / vrefint;
+ if (vbat_raw < 100) {
+ // maybe D2 is not installed
+ return -1;
+ }
+ return vbat_raw + config.vbat_offset;
+}
+
+void adc_start_analog_watchdogd(void)
+{
+// adcStart(&ADCD2, NULL);
+ adcStartConversion(&ADCD2, &adcgrpcfgTouch, samples, 1);
+}
+
+void adc_stop(void)
+{
+ #if 1
+ adcStopConversion(&ADCD2);
+ #else
+ if (ADC2->CR & ADC_CR_ADEN) {
+ if (ADC2->CR & ADC_CR_ADSTART) {
+ ADC2->CR |= ADC_CR_ADSTP;
+ while (ADC2->CR & ADC_CR_ADSTP)
+ ;
+ }
+ }
+ #endif
+}
+
+static inline void adc_interrupt(void)
+{
+ uint32_t isr = ADC2->ISR;
+ ADC2->ISR = isr;
+ if (isr & ADC_ISR_OVR) {
+// ADC overflow condition, this could happen only if the DMA is unable to read data fast enough.
+ }
+ if (isr & ADC_ISR_AWD1) {
+ /* Analog watchdog error.*/
+ handle_touch_interrupt();
+ }
+}
+
+OSAL_IRQ_HANDLER(STM32_ADC2_HANDLER)
+{
+ OSAL_IRQ_PROLOGUE();
+
+ adc_interrupt();
+
+ OSAL_IRQ_EPILOGUE();
+}
+
+#if 0
+uint16_t adc_multi_read(uint32_t chsel, uint16_t *result, uint32_t count)
+{
+ /* ADC setup */
+ VNA_ADC->ISR = VNA_ADC->ISR;
+ VNA_ADC->IER = 0;
+ VNA_ADC->TR = ADC_TR(0, 0);
+ VNA_ADC->SMPR = ADC_SMPR_SMP_1P5;
+ VNA_ADC->CFGR1 = ADC_CFGR1_RES_12BIT;
+ VNA_ADC->CHSELR = chsel;
+
+
+// palSetPadMode(GPIOA, 10, PAL_MODE_OUTPUT_PUSHPULL);
+
+ do{
+#if 0
+ if (count < 145)
+ palSetPad(GPIOA, 10);
+ else
+ palClearPad(GPIOA, 10);
+#endif
+ VNA_ADC->CR |= ADC_CR_ADSTART; // ADC conversion start.
+// while (VNA_ADC->CR & ADC_CR_ADSTART)
+ while(!(VNA_ADC->ISR & ADC_ISR_EOC));
+ ;
+ *(result++) =VNA_ADC->DR;
+ }while(--count);
+ return count;
+}
+
+int16_t adc_buf_read(uint32_t chsel, uint16_t *result, uint32_t count)
+{
+
+ adc_stop();
+
+#if 0
+ // drive high to low on Y line (coordinates from left to right)
+ palSetPad(GPIOB, GPIOB_YN);
+ palClearPad(GPIOA, GPIOA_YP);
+ // Set Y line as output
+ palSetPadMode(GPIOB, GPIOB_YN, PAL_MODE_OUTPUT_PUSHPULL);
+ palSetPadMode(GPIOA, GPIOA_YP, PAL_MODE_OUTPUT_PUSHPULL);
+ // Set X line as input
+ palSetPadMode(GPIOB, GPIOB_XN, PAL_MODE_INPUT); // Hi-z mode
+ palSetPadMode(GPIOA, GPIOA_XP, PAL_MODE_INPUT_ANALOG); // <- ADC_TOUCH_X channel
+ uint16_t res = adc_multi_read(ADC_TOUCH_X, result, count);
+#else
+// palSetPadMode(GPIOA, 9, PAL_MODE_INPUT_ANALOG);
+ uint16_t res = adc_multi_read(chsel, result, count); // ADC_CHSELR_CHSEL9
+#endif
+ touch_start_watchdog();
+ return res;
+}
+
+#endif
diff --git a/chprintf.c b/chprintf.c
index a541795..92aa1ac 100644
--- a/chprintf.c
+++ b/chprintf.c
@@ -56,8 +56,16 @@ static char smallPrefix[] = {'m', 0x1d, 'n', 'p', 'f', 'a', 'z', 'y', 0};
#pragma pack(pop)
+#ifdef TINYSA4
+typedef uint64_t ulong_t;
+typedef int64_t long_t;
+#else
+typedef uint32_t ulong_t;
+typedef int32_t long_t;
+#endif
+
static char *long_to_string_with_divisor(char *p,
- uint64_t num,
+ long_t num,
uint32_t radix,
uint32_t precision) {
char *q = p + MAX_FILLER;
@@ -84,7 +92,7 @@ static char *long_to_string_with_divisor(char *p,
#define FREQ_PREFIX_SPACE 4
static char *
-ulong_freq(char *p, uint64_t freq, uint32_t precision)
+ulong_freq(char *p, long_t freq, uint32_t precision)
{
uint8_t flag = FREQ_PSET;
flag|= precision == 0 ? FREQ_PREFIX_SPACE : FREQ_NO_SPACE;
@@ -105,7 +113,7 @@ ulong_freq(char *p, uint64_t freq, uint32_t precision)
// Fast and compact division uint32_t on 10, using shifts, result:
// c = freq % 10
// freq = freq / 10;
- uint64_t c = freq;
+ long_t c = freq;
freq >>= 1;
freq += freq >> 1;
freq += freq >> 4;
@@ -258,7 +266,8 @@ int chvprintf(BaseSequentialStream *chp, const char *fmt, va_list ap) {
uint32_t u;
int32_t l;
float f;
- int64_t x;
+ long_t x;
+ ulong_t ux;
}value;
#if CHPRINTF_USE_FLOAT
char tmpbuf[2*MAX_FILLER + 1];
@@ -331,14 +340,16 @@ int chvprintf(BaseSequentialStream *chp, const char *fmt, va_list ap) {
state|=DEFAULT_PRESCISION;
//Get [length]
if (c == 'l' || c == 'L') {
+#ifdef TINYSA4
state|=IS_LONG; // Ignore Long
+#endif
if (*fmt)
c = *fmt++;
}
- /*
+#ifdef TINYSA4
else if ((c >= 'A') && (c <= 'Z'))
state|=IS_LONG;
- */
+#endif
// Parse type
switch (c) {
case 'c':
@@ -358,14 +369,16 @@ int chvprintf(BaseSequentialStream *chp, const char *fmt, va_list ap) {
case 'd':
case 'I':
case 'i':
- if (state & IS_LONG)
+#ifdef TINYSA4
+ if (state & IS_LONG)
value.x = va_arg(ap, int64_t);
else
+#endif
value.x = va_arg(ap, int32_t);
if (value.x < 0) {
state|=NEGATIVE;
*p++ = '-';
- value.x = -value.l;
+ value.x = -value.x;
}
else if (state & POSITIVE)
*p++ = '+';
@@ -373,14 +386,17 @@ int chvprintf(BaseSequentialStream *chp, const char *fmt, va_list ap) {
else if (state & PLUS_SPACE)
*p++ = ' ';
#endif
- p = long_to_string_with_divisor(p, (int64_t)value.x, 10, 0);
+ p = long_to_string_with_divisor(p, value.x, 10, 0);
break;
case 'q':
+ case 'Q':
+#ifdef TINYSA4
if (state & IS_LONG)
- value.x = va_arg(ap, uint64_t);
+ value.ux = va_arg(ap, uint64_t);
else
- value.x = va_arg(ap, uint32_t);
- p=ulong_freq(p, value.x, precision);
+#endif
+ value.ux = va_arg(ap, uint32_t);
+ p=ulong_freq(p, value.ux, precision);
break;
#if CHPRINTF_USE_FLOAT
case 'F':
@@ -416,11 +432,13 @@ int chvprintf(BaseSequentialStream *chp, const char *fmt, va_list ap) {
case 'o':
c = 8;
unsigned_common:
+#ifdef TINYSA4
if (state & IS_LONG)
- value.x = va_arg(ap, uint64_t);
+ value.ux = va_arg(ap, uint64_t);
else
- value.x = va_arg(ap, uint32_t);
- p = long_to_string_with_divisor(p, value.x, c, 0);
+#endif
+ value.ux = va_arg(ap, uint32_t);
+ p = long_to_string_with_divisor(p, value.ux, c, 0);
break;
default:
*p++ = c;
diff --git a/halconf.h b/halconf.h
index 01ffd12..4042e8a 100644
--- a/halconf.h
+++ b/halconf.h
@@ -317,7 +317,11 @@
* buffers.
*/
#if !defined(SERIAL_USB_BUFFERS_SIZE) || defined(__DOXYGEN__)
+#ifdef TINYSA4
#define SERIAL_USB_BUFFERS_SIZE 128
+#else
+#define SERIAL_USB_BUFFERS_SIZE 64
+#endif
#endif
/**
diff --git a/ili9341.c b/ili9341.c
index 9c9033f..1a36e4e 100644
--- a/ili9341.c
+++ b/ili9341.c
@@ -20,28 +20,43 @@
#include "ch.h"
#include "hal.h"
#include "nanovna.h"
+#ifdef TINYSA4
#include "si4432.h"
+#endif
#include "spi.h"
// Allow enable DMA for read display data
+#ifdef TINYSA4
#define __USE_DISPLAY_DMA_RX__
+#endif
// Pin macros for LCD
+#ifdef TINYSA4
#define LCD_CS_LOW palClearPad(GPIO_LCD_CS_PORT, GPIO_LCD_CS)
#define LCD_CS_HIGH palSetPad(GPIO_LCD_CS_PORT, GPIO_LCD_CS)
#define LCD_RESET_ASSERT palClearPad(GPIO_LCD_RESET_PORT, GPIO_LCD_RESET)
#define LCD_RESET_NEGATE palSetPad(GPIO_LCD_RESET_PORT, GPIO_LCD_RESET)
#define LCD_DC_CMD palClearPad(GPIO_LCD_CD_PORT, GPIO_LCD_CD)
#define LCD_DC_DATA palSetPad(GPIO_LCD_CD_PORT, GPIO_LCD_CD)
+#else
+#define LCD_CS_LOW palClearPad(GPIOB, GPIOB_LCD_CS)
+#define LCD_CS_HIGH palSetPad(GPIOB, GPIOB_LCD_CS)
+#define LCD_RESET_ASSERT palClearPad(GPIOA, GPIOA_LCD_RESET)
+#define LCD_RESET_NEGATE palSetPad(GPIOA, GPIOA_LCD_RESET)
+#define LCD_DC_CMD palClearPad(GPIOB, GPIOB_LCD_CD)
+#define LCD_DC_DATA palSetPad(GPIOB, GPIOB_LCD_CD)
+#endif
#define LCD_SPI SPI1
// Set SPI bus speed for LCD
#define LCD_SPI_SPEED SPI_BR_DIV2
//Not define if need use some as Tx speed
+#ifdef TINYSA4
#define LCD_SPI_RX_SPEED SPI_BR_DIV4
+#endif
uint16_t spi_buffer[SPI_BUFFER_SIZE];
// Default foreground & background colors
@@ -311,6 +326,7 @@ static void spi_init(void)
LCD_SPI->CR1|= SPI_CR1_SPE; //SPI enable
}
+#ifdef TINYSA4
static uint16_t current_spi_mode;
void set_SPI_mode(uint16_t mode){
if (current_spi_mode == mode) return;
@@ -335,14 +351,19 @@ void set_SPI_mode(uint16_t mode){
}
current_spi_mode = mode;
}
+#endif
// Disable inline for this function
static void send_command(uint8_t cmd, uint8_t len, const uint8_t *data)
{
// Uncomment on low speed SPI (possible get here before previous tx complete)
-// while (SPI_IN_TX_RX(LCD_SPI))
+#ifndef TINYSA4
+ while (SPI_IN_TX_RX(LCD_SPI));
+#endif
+#ifdef TINYSA4
// while (SPI_IN_TX_RX);
set_SPI_mode(SPI_MODE_LCD);
+#endif
LCD_CS_LOW;
LCD_DC_CMD;
SPI_WRITE_8BIT(LCD_SPI, cmd);
@@ -359,6 +380,7 @@ static void send_command(uint8_t cmd, uint8_t len, const uint8_t *data)
//LCD_CS_HIGH;
}
+#ifdef TINYSA4
static const uint8_t ST7796S_init_seq[] = {
// SW reset
ILI9341_SOFTWARE_RESET, 0,
@@ -402,6 +424,66 @@ static const uint8_t ST7796S_init_seq[] = {
ILI9341_DISPLAY_ON, 0,
0 // sentinel
};
+#else
+static const uint8_t ili9341_init_seq[] = {
+ // cmd, len, data...,
+ // SW reset
+ ILI9341_SOFTWARE_RESET, 0,
+ // display off
+ ILI9341_DISPLAY_OFF, 0,
+ // Power control B
+ ILI9341_POWERB, 3, 0x00, 0xC1, 0x30,
+ // Power on sequence control
+ ILI9341_POWER_SEQ, 4, 0x64, 0x03, 0x12, 0x81,
+ // Driver timing control A
+ ILI9341_DTCA, 3, 0x85, 0x00, 0x78,
+ // Power control A
+ ILI9341_POWERA, 5, 0x39, 0x2C, 0x00, 0x34, 0x02,
+ // Pump ratio control
+ ILI9341_PUMP_RATIO_CONTROL, 1, 0x20,
+ // Driver timing control B
+ ILI9341_DTCB, 2, 0x00, 0x00,
+ // POWER_CONTROL_1
+ ILI9341_POWER_CONTROL_1, 1, 0x23,
+ // POWER_CONTROL_2
+ ILI9341_POWER_CONTROL_2, 1, 0x10,
+ // VCOM_CONTROL_1
+ ILI9341_VCOM_CONTROL_1, 2, 0x3e, 0x28,
+ // VCOM_CONTROL_2
+ ILI9341_VCOM_CONTROL_2, 1, 0xBE,
+ // MEMORY_ACCESS_CONTROL
+ //ILI9341_MEMORY_ACCESS_CONTROL, 1, 0x48, // portlait
+ ILI9341_MEMORY_ACCESS_CONTROL, 1, DISPLAY_ROTATION_0, // landscape
+ // COLMOD_PIXEL_FORMAT_SET : 16 bit pixel
+ ILI9341_PIXEL_FORMAT_SET, 1, 0x55,
+ // Frame Rate
+ ILI9341_FRAME_RATE_CONTROL_1, 2, 0x00, 0x18,
+ // Gamma Function Disable
+ ILI9341_3GAMMA_EN, 1, 0x00,
+ // gamma set for curve 01/2/04/08
+ ILI9341_GAMMA_SET, 1, 0x01,
+ // positive gamma correction
+ ILI9341_POSITIVE_GAMMA_CORRECTION, 15, 0x0F, 0x31, 0x2B, 0x0C, 0x0E, 0x08, 0x4E, 0xF1, 0x37, 0x07, 0x10, 0x03, 0x0E, 0x09, 0x00,
+ // negativ gamma correction
+ ILI9341_NEGATIVE_GAMMA_CORRECTION, 15, 0x00, 0x0E, 0x14, 0x03, 0x11, 0x07, 0x31, 0xC1, 0x48, 0x08, 0x0F, 0x0C, 0x31, 0x36, 0x0F,
+ // Column Address Set
+//ILI9341_COLUMN_ADDRESS_SET, 4, 0x00, 0x00, 0x01, 0x3f, // width 320
+ // Page Address Set
+//ILI9341_PAGE_ADDRESS_SET, 4, 0x00, 0x00, 0x00, 0xef, // height 240
+ // entry mode
+ ILI9341_ENTRY_MODE_SET, 1, 0x06,
+ // display function control
+ ILI9341_DISPLAY_FUNCTION_CONTROL, 3, 0x08, 0x82, 0x27,
+ // Interface Control (set WEMODE=0)
+ ILI9341_INTERFACE_CONTROL, 3, 0x00, 0x00, 0x00,
+ // sleep out
+ ILI9341_SLEEP_OUT, 0,
+ // display on
+ ILI9341_DISPLAY_ON, 0,
+ 0 // sentinel
+};
+
+#endif
void ili9341_init(void)
{
@@ -411,12 +493,19 @@ void ili9341_init(void)
chThdSleepMilliseconds(10);
LCD_RESET_NEGATE;
const uint8_t *p;
- for (p = ST7796S_init_seq; *p; ) {
+#ifdef TINYSA4
+ p = ST7796S_init_seq;
+#else
+ p = ili9341_init_seq;
+#endif
+ while (*p) {
send_command(p[0], p[1], &p[2]);
p += 2 + p[1];
chThdSleepMilliseconds(5);
}
+#ifdef TINYSA4
LCD_CS_HIGH;
+#endif
}
static void ili9341_setWindow(int x, int y, int w, int h){
@@ -518,8 +607,19 @@ void ili9341_read_memory(int x, int y, int w, int h, int len, uint16_t *out)
#endif
// require 8bit dummy clock
spi_RxByte();
+#ifdef TINYSA4
// receive pixel data to buffer
spi_RxBuffer((uint8_t *)out, len * 2);
+#else
+ while (len-- > 0) {
+ uint8_t r, g, b;
+ // read data is always 18bit
+ r = spi_RxByte();
+ g = spi_RxByte();
+ b = spi_RxByte();
+ *out++ = RGB565(r, g, b);
+ }
+#endif
// restore speed if need
#ifdef LCD_SPI_RX_SPEED
SPI_BR_SET(LCD_SPI, LCD_SPI_SPEED);
@@ -534,6 +634,7 @@ void ili9341_read_memory(int x, int y, int w, int h, int len, uint16_t *out)
{
uint16_t dummy_tx = 0;
uint8_t *rgbbuf = (uint8_t *)out;
+#ifdef TINYSA4
uint16_t data_size = len * 2;
//uint8_t xx[4] = { x >> 8, x, (x+w-1) >> 8, (x+w-1) };
//uint8_t yy[4] = { y >> 8, y, (y+h-1) >> 8, (y+h-1) };
@@ -541,7 +642,13 @@ void ili9341_read_memory(int x, int y, int w, int h, int len, uint16_t *out)
uint32_t yy = __REV16(y | ((y + h - 1) << 16));
send_command(ILI9341_COLUMN_ADDRESS_SET, 4, (uint8_t *)&xx);
send_command(ILI9341_PAGE_ADDRESS_SET, 4, (uint8_t *)&yy);
+#else
+ uint16_t data_size = len * 3;
+
+ ili9341_setWindow(x, y ,w, h);
+#endif
send_command(ILI9341_MEMORY_READ, 0, NULL);
+
// Init Rx DMA buffer, size, mode (spi and mem data size is 8 bit)
dmaStreamSetMemory0(dmarx, rgbbuf);
dmaStreamSetTransactionSize(dmarx, data_size);
@@ -569,6 +676,18 @@ void ili9341_read_memory(int x, int y, int w, int h, int len, uint16_t *out)
SPI_BR_SET(LCD_SPI, LCD_SPI_SPEED);
#endif
LCD_CS_HIGH;
+#ifndef TINYSA4
+ // Parce recived data
+ while (len-- > 0) {
+ uint8_t r, g, b;
+ // read data is always 18bit
+ r = rgbbuf[0];
+ g = rgbbuf[1];
+ b = rgbbuf[2];
+ *out++ = RGB565(r, g, b);
+ rgbbuf += 3;
+ }
+#endif
}
#endif
diff --git a/main.c b/main.c
index 4004657..7e61356 100644
--- a/main.c
+++ b/main.c
@@ -1,5 +1,6 @@
/*
*
+ * This is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3, or (at your option)
* any later version.
@@ -124,15 +125,22 @@ const char *info_about[]={
};
uint16_t dirty = true;
+
bool completed = false;
+#ifdef TINYSA4
static THD_WORKING_AREA(waThread1, 1124);
+#else
+static THD_WORKING_AREA(waThread1, 768);
+#endif
static THD_FUNCTION(Thread1, arg)
{
(void)arg;
chRegSetThreadName("sweep");
-// ui_process();
+#ifndef TINYSA4
+ ui_process();
+#endif
while (1) {
// START_PROFILE
@@ -445,9 +453,9 @@ int set_frequency(freq_t freq)
// Rewrite universal standart str to value functions to more compact
//
// Convert string to int32
-static int64_t my_atoi(const char *p)
+static long_t my_atoi(const char *p)
{
- int64_t value = 0;
+ long_t value = 0;
uint32_t c;
bool neg = false;
@@ -468,9 +476,9 @@ static int64_t my_atoi(const char *p)
// 0o - for oct radix
// 0b - for bin radix
// default dec radix
-uint64_t my_atoui(const char *p)
+freq_t my_atoui(const char *p)
{
- uint64_t value = 0, radix = 10, c;
+ freq_t value = 0, radix = 10, c;
if (*p == '+') p++;
if (*p == '0') {
switch (p[1]) {
@@ -739,7 +747,9 @@ void i2s_end_callback(I2SDriver *i2sp, size_t offset, size_t n)
--wait_count;
} else if (wait_count > 0) {
if (accumerate_count > 0) {
- // dsp_process(p, n);
+#ifndef TINYSA4
+ // dsp_process(p, n);
+#endif
accumerate_count--;
}
#ifdef ENABLED_DUMP
@@ -846,16 +856,17 @@ VNA_SHELL_FUNCTION(cmd_release)
VNA_SHELL_FUNCTION(cmd_capture)
{
// read pixel count at one time (PART*2 bytes required for read buffer)
+ (void)argc;
+ (void)argv;
int i, y;
- if (argc == 1) {
- int m = generic_option_cmd("capture", "off|on", argc, argv[0]);
- if (m>=0) {
- auto_capture = m;
- return;
- }
- }
+#ifdef TINYSA4
#if SPI_BUFFER_SIZE < (2*LCD_WIDTH)
#error "Low size of spi_buffer for cmd_capture"
+#endif
+#else
+#if SPI_BUFFER_SIZE < (3*LCD_WIDTH + 1)
+#error "Low size of spi_buffer for cmd_capture"
+#endif
#endif
// read 2 row pixel time (read buffer limit by 2/3 + 1 from spi_buffer size)
for (y = 0; y < LCD_HEIGHT; y += 2) {
@@ -945,33 +956,40 @@ config_t config = {
.harmonic_freq_threshold = 300000000,
#endif
.lcd_palette = LCD_DEFAULT_PALETTE,
- .vbat_offset = 220,
#ifdef TINYSA4
- .frequency_IF1 = DEFAULT_IF,
- .frequency_IF2 = 0,
- .ultra_threshold = 800000000,
#endif
- .low_level_offset = 100.0, // Uncalibrated
- .high_level_offset = 100.0, // Uncalibrated
- .low_level_output_offset = 0.0, // Uncalibrated
- .high_level_output_offset = 0.0, // Uncalibrated
#ifdef TINYSA3
+ .vbat_offset = 500,
+ .low_level_offset = 100, // Uncalibrated
+ .high_level_offset = 100, // Uncalibrated
.low_correction_frequency = { 10000, 100000, 200000, 500000, 30000000, 140000000, 200000000, 300000000, 330000000, 350000000 },
.low_correction_value = { +6.0, +2.8, +1.6, -0.4, 0.0, -0.4, +0.4, +3.0, +4.0, +8.1 },
.high_correction_frequency = { 240000000, 280000000, 300000000, 400000000, 500000000, 600000000, 700000000, 800000000, 900000000, 960000000 },
.high_correction_value = { 0, 0, 0, 0, 0.0, 0, 0, 0, 0, 0 },
+ .setting_frequency_10mhz = 10000000,
+ .cor_am = -14,
+ .cor_wfm = -17,
+ .cor_nfm = -17,
#endif
#ifdef TINYSA4
+ .vbat_offset = 220,
+ .frequency_IF1 = DEFAULT_IF,
+ .frequency_IF2 = 0,
+ .ultra_threshold = 800000000,
+ .low_level_offset = 100.0, // Uncalibrated
+ .high_level_offset = 100.0, // Uncalibrated
+ .low_level_output_offset = 0.0, // Uncalibrated
+ .high_level_output_offset = 0.0, // Uncalibrated
.low_correction_frequency = { 10000, 100000, 200000, 500000, 30000000, 140000000, 200000000, 300000000, 330000000, 350000000 },
.low_correction_value = { 0, 0, 0, 0, 0.0, 0, 0, 0, 0, 0 },
.high_correction_frequency = { 10000, 100000, 200000, 500000, 50000000, 140000000, 200000000, 300000000, 330000000, 350000000 },
.high_correction_value = { 0, 0, 0, 0, 0.0, 0, 0, 0, 0, 0 },
-#endif
.setting_frequency_30mhz = 30000000,
.cor_am = -5,
.cor_wfm = -55,
.cor_nfm = -55,
.ultra = false,
+#endif
.sweep_voltage = 3.3,
};
@@ -1134,7 +1152,7 @@ VNA_SHELL_FUNCTION(cmd_scan)
uint16_t mask = my_atoui(argv[3]);
if (mask) {
for (i = 0; i < points; i++) {
- if (mask & 1) shell_printf("%Lu ", frequencies[i]);
+ if (mask & 1) shell_printf("%U ", frequencies[i]);
if (mask & 2) shell_printf("%f %f ", value(measured[2][i]), 0.0);
if (mask & 4) shell_printf("%f %f ", value(measured[1][i]), 0.0);
if (mask & 8) shell_printf("%f %f ", value(measured[0][i]), 0.0);
@@ -1332,7 +1350,7 @@ get_sweep_frequency(int type)
VNA_SHELL_FUNCTION(cmd_sweep)
{
if (argc == 0) {
- shell_printf("%Ld %Ld %d\r\n", get_sweep_frequency(ST_START), get_sweep_frequency(ST_STOP), sweep_points);
+ shell_printf("%D %D %d\r\n", get_sweep_frequency(ST_START), get_sweep_frequency(ST_STOP), sweep_points);
return;
} else if (argc > 3) {
goto usage;
@@ -2000,7 +2018,7 @@ VNA_SHELL_FUNCTION(cmd_marker)
if (argc == 0) {
for (t = 0; t < MARKERS_MAX; t++) {
if (markers[t].enabled) {
- shell_printf("%d %d %Ld %f\r\n", t+1, markers[t].index, markers[t].frequency, value(actual_t[markers[t].index]));
+ shell_printf("%d %d %D %f\r\n", t+1, markers[t].index, markers[t].frequency, value(actual_t[markers[t].index]));
}
}
return;
@@ -2017,7 +2035,7 @@ VNA_SHELL_FUNCTION(cmd_marker)
goto usage;
if (argc == 1) {
display_marker:
- shell_printf("%d %d %Ld %.2f\r\n", t+1, markers[t].index, markers[t].frequency, value(actual_t[markers[t].index]));
+ shell_printf("%d %d %D %.2f\r\n", t+1, markers[t].index, markers[t].frequency, value(actual_t[markers[t].index]));
active_marker = t;
// select active marker
markers[t].enabled = TRUE;
@@ -2085,7 +2103,7 @@ VNA_SHELL_FUNCTION(cmd_frequencies)
(void)argv;
for (i = 0; i < sweep_points; i++) {
if (frequencies[i] != 0)
- shell_printf("%Lu\r\n", frequencies[i]);
+ shell_printf("%U\r\n", frequencies[i]);
}
}
@@ -2475,7 +2493,9 @@ static const VNAShellCommand commands[] =
{"color" , cmd_color , 0},
#endif
{ "if", cmd_if, 0 },
+#ifdef TINYSA4
{ "if1", cmd_if1, 0 },
+#endif
{ "attenuate", cmd_attenuate, 0 },
{ "level", cmd_level, 0 },
{ "sweeptime", cmd_sweeptime, 0 },
@@ -2485,9 +2505,11 @@ static const VNAShellCommand commands[] =
{ "rbw", cmd_rbw, 0 },
{ "mode", cmd_mode, CMD_WAIT_MUTEX },
{ "spur", cmd_spur, 0 },
+#ifdef TINYSA4
{ "lna", cmd_lna, 0 },
{ "ultra", cmd_ultra, 0 },
{ "ultra_start", cmd_ultra_start, CMD_WAIT_MUTEX },
+#endif
{ "load", cmd_load, 0 },
{ "offset", cmd_offset, 0},
{ "output", cmd_output, 0 },
@@ -2783,6 +2805,7 @@ static const I2CConfig i2ccfg = {
.cr2 = 0
};
#endif
+
static DACConfig dac1cfg1 = {
//init: 2047U,
init: 1922U,
@@ -2799,7 +2822,11 @@ static const GPTConfig gpt4cfg = {
void my_microsecond_delay(int t)
{
+#ifdef TINYSA4
if (t>1) gptPolledDelay(&GPTD4, t); // t us delay
+#else
+ if (t>1) gptPolledDelay(&GPTD14, t); // t us delay
+#endif
}
#if 0
/*
@@ -2881,7 +2908,11 @@ int main(void)
palClearPad(GPIOB, GPIOA_RF_PWR);
chThdSleepMilliseconds(200);
#endif
+#ifdef TINYSA4
palSetPad(GPIOB, GPIOA_RF_PWR);
+#else
+ palSetPad(GPIOB, GPIO_RF_PWR);
+#endif
chThdSleepMilliseconds(500);
#endif
@@ -2919,24 +2950,31 @@ int main(void)
/*
* Initiate 1 micro second timer
*/
- gptStart(&GPTD4, &gpt4cfg);
+#ifdef TINYSA4
+ gptStart(&GPTD4, &gpt4cfg);
gptPolledDelay(&GPTD4, 10); // 10 us delay
+#else
+ gptStart(&GPTD14, &gpt4cfg);
+ gptPolledDelay(&GPTD14, 10); // 10 us delay
+#endif
/* restore config */
config_recall();
-#if 1
if (caldata_recall(0) == -1) {
load_LCD_properties();
}
-#endif
+
/*
* Init Shell console connection data (after load config for settings)
*/
shell_init_connection();
-/* restore frequencies and calibration 0 slot properties from flash memory */
-
+#ifdef TINYSA4
dac1cfg1.init = config.dac_value;
+#else
+ dac1cfg1.init = 0;
+#endif
+
/*
* Starting DAC1 driver, setting up the output pin as analog as suggested
* by the Reference Manual.
diff --git a/mcuconf.h b/mcuconf.h
index be724e5..1d4b073 100644
--- a/mcuconf.h
+++ b/mcuconf.h
@@ -14,27 +14,26 @@
limitations under the License.
*/
-#ifdef TINYSA_F303
-#include "mcuconf_F303.h"
-#else
#ifndef MCUCONF_H
#define MCUCONF_H
+#ifdef TINYSA_F303
+
/*
- * STM32F0xx drivers configuration.
+ * STM32F3xx drivers configuration.
* The following settings override the default settings present in
* the various device driver implementation headers.
* Note that the settings for each driver only have effect if the whole
* driver is enabled in halconf.h.
*
* IRQ priorities:
- * 3...0 Lowest...Highest.
+ * 15...0 Lowest...Highest.
*
* DMA priorities:
* 0...3 Lowest...Highest.
*/
-#define STM32F0xx_MCUCONF
+#define STM32F3xx_MCUCONF
/*
* HAL driver system settings.
@@ -42,26 +41,38 @@
#define STM32_NO_INIT FALSE
#define STM32_PVD_ENABLE FALSE
#define STM32_PLS STM32_PLS_LEV0
-#define STM32_HSI_ENABLED TRUE
-#define STM32_HSI14_ENABLED TRUE
-#define STM32_HSI48_ENABLED TRUE
+#if 0 // 72MHz
+#define STM32_HSI_ENABLED FALSE
+#define STM32_HSE_ENABLED TRUE
+#define STM32_SW STM32_SW_PLL
+#define STM32_PLLSRC STM32_PLLSRC_HSE
+#define STM32_PREDIV_VALUE 1
+#define STM32_PLLMUL_VALUE 9
+#define STM32_USBPRE STM32_USBPRE_DIV1P5
+#else
+#define STM32_HSI_ENABLED TRUE // 48MHz
#define STM32_HSE_ENABLED FALSE
#define STM32_SW STM32_SW_PLL
-#define STM32_PLLSRC STM32_PLLSRC_HSI_DIV2
+#define STM32_PLLSRC STM32_PLLSRC_HSI
#define STM32_PREDIV_VALUE 1
-#define STM32_PLLMUL_VALUE 12
+#define STM32_PLLMUL_VALUE 12 // prediv HSI always 2
+#define STM32_USBPRE STM32_USBPRE_DIV1
+#endif
#define STM32_HPRE STM32_HPRE_DIV1
-#define STM32_PPRE STM32_PPRE_DIV1
-#define STM32_ADCSW STM32_ADCSW_HSI14
-#define STM32_ADCPRE STM32_ADCPRE_DIV4
+#define STM32_PPRE1 STM32_PPRE1_DIV2
+// Set SPI1 more faster use PPRE2 max speed
+#define STM32_PPRE2 STM32_PPRE2_DIV1
#define STM32_MCOSEL STM32_MCOSEL_PLLDIV2
-#define STM32_ADCPRE STM32_ADCPRE_DIV4
-#define STM32_ADCSW STM32_ADCSW_HSI14
-#define STM32_USBSW STM32_USBSW_HSI48
-#define STM32_CECSW STM32_CECSW_HSI
-//#define STM32_I2C1SW STM32_I2C1SW_HSI
-#define STM32_I2C1SW STM32_I2C1SW_SYSCLK
+#define STM32_ADC12PRES STM32_ADC12PRES_DIV2
+//#define STM32_ADC34PRES STM32_ADC34PRES_DIV1
#define STM32_USART1SW STM32_USART1SW_PCLK
+//#define STM32_USART2SW STM32_USART2SW_PCLK
+//#define STM32_USART3SW STM32_USART3SW_PCLK
+#define STM32_I2C1SW STM32_I2C1SW_SYSCLK
+//#define STM32_I2C2SW STM32_I2C2SW_SYSCLK
+#define STM32_TIM1SW STM32_TIM1SW_PCLK2
+#define STM32_TIM8SW STM32_TIM8SW_PCLK2
+#define STM32_USB_CLOCK_REQUIRED TRUE
/*
* RTC driver system settings for stm32f303
@@ -84,6 +95,222 @@
#define STM32_LSEDRV (3 << 3)
#endif
+/*
+ * ADC driver system settings.
+ */
+#define STM32_ADC_USE_ADC1 TRUE
+#define STM32_ADC_USE_ADC2 TRUE
+#define STM32_ADC_USE_ADC3 FALSE
+#define STM32_ADC_ADC1_DMA_STREAM STM32_DMA_STREAM_ID(1, 1)
+#define STM32_ADC_ADC2_DMA_STREAM STM32_DMA_STREAM_ID(2, 1)
+//#define STM32_ADC_ADC3_DMA_STREAM STM32_DMA_STREAM_ID(2, 5)
+//#define STM32_ADC_ADC4_DMA_STREAM STM32_DMA_STREAM_ID(2, 2)
+#define STM32_ADC_ADC12_DMA_PRIORITY 2
+//#define STM32_ADC_ADC34_DMA_PRIORITY 2
+#define STM32_ADC_ADC12_IRQ_PRIORITY 2
+//#define STM32_ADC_ADC34_IRQ_PRIORITY 5
+#define STM32_ADC_ADC12_DMA_IRQ_PRIORITY 2
+//#define STM32_ADC_ADC34_DMA_IRQ_PRIORITY 5
+//#define STM32_ADC_ADC12_CLOCK_MODE ADC_CCR_CKMODE_ADCCK
+//#define STM32_ADC_ADC12_CLOCK_MODE ADC_CCR_CKMODE_AHB_DIV2
+#define STM32_ADC_ADC12_CLOCK_MODE ADC_CCR_CKMODE_AHB_DIV1
+//#define STM32_ADC_ADC34_CLOCK_MODE ADC_CCR_CKMODE_AHB_DIV1
+#define STM32_ADC_DUAL_MODE FALSE
+
+/*
+ * CAN driver system settings.
+ */
+#define STM32_CAN_USE_CAN1 FALSE
+#define STM32_CAN_CAN1_IRQ_PRIORITY 11
+
+/*
+ * DAC driver system settings.
+ */
+#define STM32_DAC_DUAL_MODE FALSE
+#define STM32_DAC_USE_DAC1_CH1 TRUE
+#define STM32_DAC_USE_DAC1_CH2 TRUE
+#define STM32_DAC_DAC1_CH1_IRQ_PRIORITY 10
+#define STM32_DAC_DAC1_CH2_IRQ_PRIORITY 10
+#define STM32_DAC_DAC1_CH1_DMA_PRIORITY 2
+#define STM32_DAC_DAC1_CH2_DMA_PRIORITY 2
+
+/*
+ * EXT driver system settings.
+ */
+#define STM32_EXT_EXTI0_1_IRQ_PRIORITY 3
+#define STM32_EXT_EXTI2_3_IRQ_PRIORITY 3
+#define STM32_EXT_EXTI4_15_IRQ_PRIORITY 3
+#define STM32_EXT_EXTI16_IRQ_PRIORITY 3
+#define STM32_EXT_EXTI17_IRQ_PRIORITY 3
+#define STM32_EXT_EXTI21_22_IRQ_PRIORITY 3
+
+#define STM32_DISABLE_EXTI2122_HANDLER TRUE
+
+/*
+ * GPT driver system settings.
+ */
+#define STM32_GPT_USE_TIM1 FALSE
+#define STM32_GPT_USE_TIM2 FALSE
+#define STM32_GPT_USE_TIM3 TRUE
+#define STM32_GPT_USE_TIM4 TRUE
+#define STM32_GPT_TIM1_IRQ_PRIORITY 2
+#define STM32_GPT_TIM2_IRQ_PRIORITY 2
+#define STM32_GPT_TIM3_IRQ_PRIORITY 2
+#define STM32_GPT_TIM4_IRQ_PRIORITY 2
+
+/*
+ * I2C driver system settings.
+ */
+#define STM32_I2C_USE_I2C1 TRUE
+#define STM32_I2C_USE_I2C2 FALSE
+#define STM32_I2C_BUSY_TIMEOUT 50
+#define STM32_I2C_I2C1_IRQ_PRIORITY 3
+#define STM32_I2C_I2C2_IRQ_PRIORITY 3
+#define STM32_I2C_USE_DMA TRUE
+#define STM32_I2C_I2C1_DMA_PRIORITY 1
+#define STM32_I2C_I2C2_DMA_PRIORITY 1
+#define STM32_I2C_DMA_ERROR_HOOK(i2cp) osalSysHalt("DMA failure")
+
+/*
+ * I2S driver system settings.
+ */
+#define STM32_I2S_USE_SPI1 FALSE
+#define STM32_I2S_USE_SPI2 TRUE
+#define STM32_I2S_SPI1_MODE (STM32_I2S_MODE_MASTER | \
+ STM32_I2S_MODE_RX)
+#define STM32_I2S_SPI2_MODE (STM32_I2S_MODE_SLAVE | \
+ STM32_I2S_MODE_RX )
+#define STM32_I2S_SPI1_IRQ_PRIORITY 2
+#define STM32_I2S_SPI2_IRQ_PRIORITY 2
+#define STM32_I2S_SPI1_DMA_PRIORITY 1
+#define STM32_I2S_SPI2_DMA_PRIORITY 1
+#define STM32_I2S_SPI1_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 2)
+#define STM32_I2S_SPI1_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 3)
+#define STM32_I2S_SPI2_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 4)
+#define STM32_I2S_SPI2_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 5)
+#define STM32_I2S_DMA_ERROR_HOOK(i2sp) osalSysHalt("DMA failure")
+
+/*
+ * ICU driver system settings.
+ */
+#define STM32_ICU_USE_TIM1 FALSE
+#define STM32_ICU_USE_TIM2 FALSE
+#define STM32_ICU_USE_TIM3 FALSE
+#define STM32_ICU_TIM1_IRQ_PRIORITY 3
+#define STM32_ICU_TIM2_IRQ_PRIORITY 3
+#define STM32_ICU_TIM3_IRQ_PRIORITY 3
+
+/*
+ * PWM driver system settings.
+ */
+#define STM32_PWM_USE_ADVANCED FALSE
+#define STM32_PWM_USE_TIM1 FALSE
+#define STM32_PWM_USE_TIM2 FALSE
+#define STM32_PWM_USE_TIM3 FALSE
+#define STM32_PWM_TIM1_IRQ_PRIORITY 3
+#define STM32_PWM_TIM2_IRQ_PRIORITY 3
+#define STM32_PWM_TIM3_IRQ_PRIORITY 3
+
+/*
+ * SERIAL driver system settings.
+ */
+#define STM32_SERIAL_USE_USART1 TRUE
+#define STM32_SERIAL_USE_USART2 FALSE
+#define STM32_SERIAL_USART1_PRIORITY 3
+#define STM32_SERIAL_USART2_PRIORITY 3
+
+/*
+ * SPI driver system settings.
+ */
+#define STM32_SPI_USE_SPI1 TRUE
+#define STM32_SPI_USE_SPI2 FALSE
+#define STM32_SPI_USE_SPI3 FALSE
+#define STM32_SPI_SPI1_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 2)
+#define STM32_SPI_SPI1_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 3)
+#define STM32_SPI_SPI1_DMA_PRIORITY 1
+#define STM32_SPI_SPI2_DMA_PRIORITY 1
+#define STM32_SPI_SPI1_IRQ_PRIORITY 2
+#define STM32_SPI_SPI2_IRQ_PRIORITY 2
+#define STM32_SPI_DMA_ERROR_HOOK(spip) osalSysHalt("DMA failure")
+
+/*
+ * ST driver system settings.
+ */
+#define STM32_ST_IRQ_PRIORITY 2
+#define STM32_ST_USE_TIMER 2
+
+/*
+ * UART driver system settings.
+ */
+#define STM32_UART_USE_USART1 FALSE
+#define STM32_UART_USE_USART2 FALSE
+#define STM32_UART_USART1_IRQ_PRIORITY 3
+#define STM32_UART_USART2_IRQ_PRIORITY 3
+#define STM32_UART_USART1_DMA_PRIORITY 0
+#define STM32_UART_USART2_DMA_PRIORITY 0
+#define STM32_UART_USART3_DMA_PRIORITY 0
+#define STM32_UART_DMA_ERROR_HOOK(uartp) osalSysHalt("DMA failure")
+
+/*
+ * USB driver system settings.
+ */
+#define STM32_USB_USE_USB1 TRUE
+#define STM32_USB_LOW_POWER_ON_SUSPEND FALSE
+#define STM32_USB_USB1_LP_IRQ_PRIORITY 3
+
+/*
+ * WDG driver system settings.
+ */
+#define STM32_WDG_USE_IWDG FALSE
+
+#else
+
+/*
+ * STM32F0xx drivers configuration.
+ * The following settings override the default settings present in
+ * the various device driver implementation headers.
+ * Note that the settings for each driver only have effect if the whole
+ * driver is enabled in halconf.h.
+ *
+ * IRQ priorities:
+ * 3...0 Lowest...Highest.
+ *
+ * DMA priorities:
+ * 0...3 Lowest...Highest.
+ */
+
+#define STM32F0xx_MCUCONF
+
+/*
+ * HAL driver system settings.
+ */
+#define STM32_NO_INIT FALSE
+#define STM32_PVD_ENABLE FALSE
+#define STM32_PLS STM32_PLS_LEV0
+#define STM32_HSI_ENABLED TRUE
+#define STM32_HSI14_ENABLED TRUE
+#define STM32_HSI48_ENABLED TRUE
+#define STM32_LSI_ENABLED TRUE
+#define STM32_HSE_ENABLED FALSE
+#define STM32_LSE_ENABLED FALSE
+#define STM32_SW STM32_SW_PLL
+#define STM32_PLLSRC STM32_PLLSRC_HSI_DIV2
+#define STM32_PREDIV_VALUE 1
+#define STM32_PLLMUL_VALUE 12
+#define STM32_HPRE STM32_HPRE_DIV1
+#define STM32_PPRE STM32_PPRE_DIV1
+#define STM32_ADCSW STM32_ADCSW_HSI14
+#define STM32_ADCPRE STM32_ADCPRE_DIV4
+#define STM32_MCOSEL STM32_MCOSEL_PLLDIV2
+#define STM32_ADCPRE STM32_ADCPRE_DIV4
+#define STM32_ADCSW STM32_ADCSW_HSI14
+#define STM32_USBSW STM32_USBSW_HSI48
+#define STM32_CECSW STM32_CECSW_HSI
+//#define STM32_I2C1SW STM32_I2C1SW_HSI
+#define STM32_I2C1SW STM32_I2C1SW_SYSCLK
+#define STM32_USART1SW STM32_USART1SW_PCLK
+#define STM32_RTCSEL STM32_RTCSEL_LSI
+
/*
* ADC driver system settings.
*/
@@ -246,5 +473,6 @@
*/
#define STM32_WDG_USE_IWDG FALSE
-#endif /* MCUCONF_H */
#endif
+
+#endif /* MCUCONF_H */
diff --git a/nanovna.h b/nanovna.h
index 804ee26..fc52518 100644
--- a/nanovna.h
+++ b/nanovna.h
@@ -17,14 +17,14 @@
* Boston, MA 02110-1301, USA.
*/
#include "ch.h"
-#define TINYSA4_PROTO
-//#ifdef TINYSA_F303
+#ifdef TINYSA_F303
#include "adc_F303.h"
-#define TINYSA4
-//#else
-//#define TINYSA3
-//#endif
+// #define TINYSA4
+#define TINYSA4_PROTO
+#else
+#define TINYSA3
+#endif
// Need enable HAL_USE_SPI in halconf.h
#define __USE_DISPLAY_DMA__
@@ -34,11 +34,11 @@
#ifdef TINYSA3
#define __SI4432__
#endif
-//#ifdef TINYSA4
+#ifdef TINYSA4
#define __SI4463__
#define __SI4468__
#define __ADF4351__
-//#endif
+#endif
#define __PE4302__
//#define __SIMULATION__
//#define __PIPELINE__
@@ -51,16 +51,15 @@
#define __FAST_SWEEP__ // Pre-fill SI4432 RSSI buffer to get fastest sweep in zero span mode
// #define __AUDIO__
//#define __HAM_BAND__
-//#define __ULTRA__ // Add harmonics mode on low input.
#define __SPUR__ // Does spur reduction by shifting IF
//#define __USE_SERIAL_CONSOLE__ // Enable serial I/O connection (need enable HAL_USE_SERIAL as TRUE in halconf.h)
-#define __HARMONIC__
-
-
#define __SINGLE_LETTER__
#define __NICE_BIG_FONT__
#define __QUASI_PEAK__
+#ifdef TINYSA4
+#define __HARMONIC__
#define __REMOTE_DESKTOP__
+#endif
#ifdef TINYSA3
#define DEFAULT_IF 433800000
@@ -103,9 +102,11 @@
#ifdef TINYSA3
typedef uint32_t freq_t;
+ typedef int32_t long_t;
#endif
#ifdef TINYSA4
-typedef uint64_t freq_t;
+ typedef uint64_t freq_t;
+ typedef int64_t long_t;
#endif
#define CORRECTION_POINTS 10 // Frequency dependent level correction table entries
@@ -197,8 +198,6 @@ void send_buffer(uint8_t * buf, int s);
void set_marker_frequency(int m, freq_t f);
void toggle_sweep(void);
void toggle_mute(void);
-void toggle_extra_lna(void);
-void set_extra_lna(int t);
void load_default_properties(void);
enum {
@@ -234,28 +233,20 @@ extern uint8_t sweep_mode;
extern bool completed;
extern const char *info_about[];
-// ------------------------------- sa_core.c ----------------------------------
-
#ifdef TINYSA4
-#define SI_DRIVE_STEP 0.5 // Power step per step in drive level
-#define SWITCH_ATTENUATION 34
-//#define POWER_OFFSET -18 // Max level with all enabled
-//#define POWER_RANGE 70
-#define MAX_DRIVE 16
-#define MIN_DRIVE 8
-#define SL_GENHIGH_LEVEL_MIN -15
-#define SL_GENHIGH_LEVEL_RANGE 9
-#define SL_GENLOW_LEVEL_MIN -88
-#define SL_GENLOW_LEVEL_RANGE 70
+void toggle_extra_lna(void);
+void set_extra_lna(int t);
+#endif
+// ------------------------------- sa_core.c ----------------------------------
-#else
-#define SI_DRIVE_STEP 3
-#define SWITCH_ATTENUATION 30
-#define POWER_OFFSET 15
-#endif
+
+extern int level_min(void);
+extern int level_max(void);
+extern int level_range(void);
extern const char * const unit_string[];
+extern const int8_t drive_dBm [];
extern uint8_t signal_is_AM;
extern const int reffer_freq[];
extern freq_t minFreq;
@@ -268,7 +259,6 @@ void SetPowerGrid(int);
void SetRefLevel(float);
void set_refer_output(int);
void toggle_below_IF(void);
-void toggle_ultra(void);
int get_refer_output(void);
void set_attenuation(float);
float get_attenuation(void);
@@ -285,12 +275,9 @@ void set_RBW(uint32_t rbw_x10);
void set_lo_drive(int d);
void set_rx_drive(int d);
void set_IF(int f);
-void set_IF2(int f);
-void set_R(int f);
void set_step_delay(int t);
void set_offset_delay(int t);
void set_repeat(int);
-void clear_frequency_cache(void);
void set_level_sweep(float);
void set_level(float);
void set_sweep_time_us(uint32_t);
@@ -302,8 +289,6 @@ void set_spur(int v);
void toggle_spur(void);
void toggle_mirror_masking(void);
#endif
-void toggle_high_out_adf4350(void);
-extern int high_out_adf4350;
void set_average(int);
int GetAverage(void);
//extern int setting.average;
@@ -332,7 +317,6 @@ void set_attack(int);
void set_noise(int);
void toggle_tracking_output(void);
extern int32_t frequencyExtra;
-void set_30mhz(freq_t);
void set_modulation(int);
void set_modulation_frequency(int);
int search_maximum(int m, freq_t center, int span);
@@ -341,9 +325,21 @@ void set_measurement(int);
// extern int settingSpeed;
//extern int setting.step_delay;
void sweep_remote(void);
-extern void set_modulo(uint32_t f);
extern int generic_option_cmd( const char *cmd, const char *cmd_list, int argc, char *argv);
+
+#ifdef TINYSA4
+void clear_frequency_cache(void);
+void toggle_high_out_adf4350(void);
+extern int high_out_adf4350;
+void set_30mhz(freq_t);
+void toggle_ultra(void);
+void set_IF2(int f);
+void set_R(int f);
+extern void set_modulo(uint32_t f);
extern void fill_spur_table(void);
+#else
+void set_10mhz(freq_t);
+#endif
#ifdef __AUDIO__
/*
@@ -430,9 +426,13 @@ extern uint16_t graph_bottom;
// Menu Button
// Maximum menu buttons count
+#ifdef TINYSA4
#define MENU_BUTTON_MAX 9
+#else
+#define MENU_BUTTON_MAX 8
+#endif
#define MENU_BUTTON_WIDTH 80
-#define MENU_BUTTON_HEIGHT (LCD_HEIGHT/9-1)
+#define MENU_BUTTON_HEIGHT (LCD_HEIGHT/MENU_BUTTON_MAX-1)
#define MENU_BUTTON_BORDER 1
#define KEYBOARD_BUTTON_BORDER 2
#define FORM_BUTTON_BORDER 2
@@ -582,7 +582,11 @@ typedef struct config {
freq_t high_correction_frequency[CORRECTION_POINTS];
float high_correction_value[CORRECTION_POINTS];
uint32_t deviceid;
+#ifdef TINYSA4
freq_t setting_frequency_30mhz;
+#else
+ freq_t setting_frequency_10mhz;
+#endif
uint16_t gridlines;
uint16_t hambands;
@@ -590,12 +594,12 @@ typedef struct config {
freq_t frequency_IF1;
freq_t frequency_IF2;
freq_t ultra_threshold;
+ int8_t ultra;
#endif
- int8_t _mode;
+ uint8_t _mode;
int8_t cor_am;
int8_t cor_wfm;
int8_t cor_nfm;
- int8_t ultra;
float sweep_voltage;
uint32_t dummy;
// uint8_t _reserved[22];
@@ -645,8 +649,8 @@ enum {
};
typedef struct {
- int8_t enabled;
- int8_t mtype;
+ uint8_t enabled;
+ uint8_t mtype;
int16_t index;
freq_t frequency;
} marker_t;
@@ -708,8 +712,13 @@ extern volatile uint8_t redraw_request;
// Define size of screen buffer in pixels (one pixel 16bit size)
#define SPI_BUFFER_SIZE (CELLWIDTH*CELLHEIGHT)
+#ifdef TINYSA4
#define LCD_WIDTH 480
#define LCD_HEIGHT 320
+#else
+#define LCD_WIDTH 320
+#define LCD_HEIGHT 240
+#endif
#define LCD_BG_COLOR 0
#define LCD_FG_COLOR 1
@@ -886,18 +895,19 @@ typedef struct setting
int trigger_mode;
int slider_position;
int32_t slider_span;
+ freq_t *correction_frequency;
+ float *correction_value;
+#ifdef TINYSA4
int extra_lna;
int ultra;
int R;
- freq_t *correction_frequency;
- float *correction_value;
+#endif
uint32_t dummy;
uint32_t checksum; // must be last
}setting_t;
extern setting_t setting;
-//extern int setting_frequency_30mhz;
void reset_settings(int m);
@@ -922,7 +932,9 @@ enum { SD_NORMAL, SD_PRECISE, SD_FAST, SD_MANUAL };
extern freq_t frequencies[POINTS_COUNT];
extern const float unit_scale_value[];
extern const char * const unit_scale_text[];
+#ifdef TINYSA4
extern int debug_frequencies;
+#endif
#if 1 // Still sufficient flash
// Flash save area - flash7 : org = 0x0801B000, len = 20k in *.ld file
// 2k - for config save
@@ -1128,7 +1140,8 @@ void enter_dfu(void);
/*
* adc.c
*/
-#define rccEnableWWDG(lp) rccEnableAPB1(RCC_APB1ENR_WWDGEN, lp)
+#ifdef TINYSA4
+ #define rccEnableWWDG(lp) rccEnableAPB1(RCC_APB1ENR_WWDGEN, lp)
#define ADC_TOUCH_X ADC_CHANNEL_IN3
#define ADC_TOUCH_Y ADC_CHANNEL_IN4
@@ -1137,7 +1150,17 @@ uint16_t adc_single_read(uint32_t chsel);
void adc_start_analog_watchdogd(void);
void adc_stop(void);
int16_t adc_vbat_read(void);
+#else
+#define ADC_TOUCH_X ADC_CHSELR_CHSEL6
+#define ADC_TOUCH_Y ADC_CHSELR_CHSEL7
+void adc_init(void);
+uint16_t adc_single_read(uint32_t chsel);
+void adc_start_analog_watchdogd(uint32_t chsel);
+void adc_stop(void);
+void adc_interrupt(void);
+int16_t adc_vbat_read(void);
+#endif
/*
* misclinous
*/
@@ -1165,7 +1188,11 @@ typedef int16_t pureRSSI_t;
// RSSI values conversion macro
// External programm zero level settings (need decrease on this value -)
+#ifdef TINYSA4
+#define EXT_ZERO_LEVEL (174)
+#else
#define EXT_ZERO_LEVEL (174)
+#endif
#define DEVICE_TO_PURE_RSSI(rssi) ((rssi)<<4)
#define PURE_TO_DEVICE_RSSI(rssi) ((rssi)>>4)
#define float_TO_PURE_RSSI(rssi) ((rssi)*32)
@@ -1204,6 +1231,7 @@ enum {
T_AUTO, T_NORMAL, T_SINGLE, T_DONE, T_UP, T_DOWN, T_MODE, T_PRE, T_POST, T_MID
};
+#ifdef TINYSA4
// si4432.c
extern void ADF4351_mux(int R);
@@ -1228,5 +1256,5 @@ extern void si_set_offset(int16_t offset);
extern int SI4463_offset_changed;
extern void si_fm_offset(int16_t offset);
-
+#endif
/*EOF*/
diff --git a/plot.c b/plot.c
index 707ed7e..b666168 100644
--- a/plot.c
+++ b/plot.c
@@ -547,12 +547,12 @@ value(const float v)
return v + LOG_10_SQRT_50_x20_plus90; // 90.0 + 20.0*LOG_10_SQRT_50;
break;
case U_VOLT:
-// return pow(10, (v-30.0)/20.0) * sqrt((float)50.0);
- return pow((float)10.0, (v-(float)30.0)/(float)20.0)*SQRT_50; // Do NOT change pow to powf as this will increase the size
+// return powf(10, (v-30.0)/20.0) * sqrt((float)50.0);
+ return powf((float)10.0, (v-(float)30.0)/(float)20.0)*SQRT_50; // Do NOT change pow to powf as this will increase the size
// return pow(10, v/20.0) * POW_SQRT; //TODO there is an error in this calculation as the outcome is different from the not optimized version
break;
case U_WATT:
- return pow((float)10.0, v/10.0)/1000.0; // Do NOT change pow to powf as this will increase the size
+ return powf((float)10.0, v/10.0)/1000.0; // Do NOT change pow to powf as this will increase the size
break;
}
// case U_DBM:
@@ -972,7 +972,7 @@ void trace_get_value_string( // Only used at one place
plot_printf(ptr2, sizeof(buf2) - 2, "%3.1f" , (dfreq + 50000) / 1000000.0);
}
#else
- plot_printf(ptr2, sizeof(buf2) - 2, "%9.5LqHz" , dfreq);
+ plot_printf(ptr2, sizeof(buf2) - 2, "%9.5QHz" , dfreq);
}
#endif
v = value(coeff[i]);
@@ -2107,7 +2107,7 @@ static void cell_draw_marker_info(int x0, int y0)
f = markers[2].frequency-markers[1].frequency;
else
f = markers[1].frequency-markers[2].frequency;
- plot_printf(buf, sizeof buf, "WIDTH: %8.3LqHz", f);
+ plot_printf(buf, sizeof buf, "WIDTH: %8.3QHz", f);
show_computed:
j = 3;
int xpos = 1 + (j%2)*(WIDTH/2) + CELLOFFSETX - x0;
@@ -2128,7 +2128,7 @@ static void cell_draw_marker_info(int x0, int y0)
float level = (actual_t[markers[1].index] + actual_t[markers[2].index])/2.0 - actual_t[markers[0].index];
if (level < -70 || level > 0)
break;
- int depth =(int) (pow((float)10.0, 2.0 + (level + 6.02) /20.0));
+ int depth =(int) (powf((float)10.0, 2.0 + (level + 6.02) /20.0));
#endif
plot_printf(buf, sizeof buf, "DEPTH: %3d%%", depth);
goto show_computed;
@@ -2137,7 +2137,7 @@ static void cell_draw_marker_info(int x0, int y0)
if ( markers[2].frequency < dev)
break;
dev = ( markers[2].frequency - dev ) >> 1;
- plot_printf(buf, sizeof buf, "DEVIATION:%6.1LqHz", dev);
+ plot_printf(buf, sizeof buf, "DEVIATION:%6.1QHz", dev);
goto show_computed;
} else if (setting.measurement == M_THD && markers[0].enabled && (markers[0].index << 5) > sweep_points ) {
int old_unit = setting.unit;
@@ -2151,7 +2151,7 @@ static void cell_draw_marker_info(int x0, int y0)
h += index_to_value(markers[1].index);
h_i++;
}
- float thd = 100.0 * sqrt(h/p);
+ float thd = 100.0 * sqrtf(h/p);
setting.unit = old_unit;
ili9341_set_foreground(marker_color(markers[0].mtype));
plot_printf(buf, sizeof buf, "THD: %4.1f%%", thd);
@@ -2273,17 +2273,17 @@ draw_frequencies(void)
if ((domain_mode & DOMAIN_MODE) == DOMAIN_FREQ) {
#endif
if (FREQ_IS_CW()) {
- plot_printf(buf1, sizeof(buf1), " CW %LqHz", get_sweep_frequency(ST_CW));
+ plot_printf(buf1, sizeof(buf1), " CW %QHz", get_sweep_frequency(ST_CW));
// Show user actual select sweep time?
uint32_t t = setting.actual_sweep_time_us;
plot_printf(buf2, sizeof(buf2), " TIME %.3Fs", (float)t/ONE_SECOND_TIME);
} else if (FREQ_IS_STARTSTOP()) {
- plot_printf(buf1, sizeof(buf1), " START %.3LqHz %5.1LqHz/", get_sweep_frequency(ST_START), grid_span);
- plot_printf(buf2, sizeof(buf2), " STOP %.3LqHz", get_sweep_frequency(ST_STOP));
+ plot_printf(buf1, sizeof(buf1), " START %.3QHz %5.1QHz/", get_sweep_frequency(ST_START), grid_span);
+ plot_printf(buf2, sizeof(buf2), " STOP %.3QHz", get_sweep_frequency(ST_STOP));
} else if (FREQ_IS_CENTERSPAN()) {
- plot_printf(buf1, sizeof(buf1), " CENTER %.3LqHz %5.1LqHz/", get_sweep_frequency(ST_CENTER), grid_span);
- plot_printf(buf2, sizeof(buf2), " SPAN %.3LqHz", get_sweep_frequency(ST_SPAN));
+ plot_printf(buf1, sizeof(buf1), " CENTER %.3QHz %5.1QHz/", get_sweep_frequency(ST_CENTER), grid_span);
+ plot_printf(buf2, sizeof(buf2), " SPAN %.3QHz", get_sweep_frequency(ST_SPAN));
}
#ifdef __VNA__
} else {
diff --git a/sa_cmd.c b/sa_cmd.c
index 9a30910..e8d511c 100644
--- a/sa_cmd.c
+++ b/sa_cmd.c
@@ -99,13 +99,18 @@ VNA_SHELL_FUNCTION(cmd_spur)
// shell_printf("usage: spur %s\r\n", cmd);
// return;
// }
+#ifdef TINYSA4
int m = generic_option_cmd("spur", "off|on|auto", argc, argv[0]);
+#else
+ int m = generic_option_cmd("spur", "off|on", argc, argv[0]);
+#endif
if (m>=0) {
set_spur(m);
redraw_request |= REDRAW_CAL_STATUS | REDRAW_AREA;
}
}
+#ifdef TINYSA4
VNA_SHELL_FUNCTION(cmd_lna)
{
// static const char cmd[] = "off|on";
@@ -135,6 +140,7 @@ VNA_SHELL_FUNCTION(cmd_ultra)
update_min_max_freq();
}
}
+#endif
VNA_SHELL_FUNCTION(cmd_output)
{
@@ -258,6 +264,15 @@ VNA_SHELL_FUNCTION(cmd_leveloffset)
else
goto usage;
dirty = true;
+ } else if (argc == 3 && strcmp(argv[1],"output") == 0) {
+ float v = my_atof(argv[2]);
+ if (strcmp(argv[0],"low") == 0)
+ config.low_level_output_offset = v;
+ else if (strcmp(argv[0],"high") == 0)
+ config.high_level_output_offset = v;
+ else
+ goto usage;
+ dirty = true;
} else {
usage:
shell_printf("leveloffset [low|high] {output} []\r\n");
@@ -293,15 +308,19 @@ VNA_SHELL_FUNCTION(cmd_rbw)
{
if (argc != 1) {
usage:
- shell_printf("usage: rbw 0.3..600|auto\r\n");
- return;
+#ifdef TINYSA4
+ shell_printf("usage: rbw 0.3..600|auto\r\n");
+#else
+ shell_printf("usage: rbw 2..600|auto\r\n");
+#endif
+ return;
}
if (get_str_index(argv[0], "auto|0")>=0) {
if (setting.rbw_x10 != 0)
set_RBW(0);
} else {
float a = my_atof(argv[0]);
- if (a < 0.2 || a>900)
+ if (a < 0.2 || a>600)
goto usage;
if (setting.rbw_x10 != a*10)
set_RBW((int) ( a*10));
@@ -312,7 +331,7 @@ VNA_SHELL_FUNCTION(cmd_if)
{
if (argc != 1) {
usage:
- shell_printf("usage: if {433M..435M}\r\n%qHz\r\n", setting.frequency_IF);
+ shell_printf("usage: if {433M..435M}\r\n%QHz\r\n", setting.frequency_IF);
return;
} else {
freq_t a = (freq_t)my_atoi(argv[0]);
@@ -323,6 +342,7 @@ VNA_SHELL_FUNCTION(cmd_if)
}
}
+#ifdef TINYSA4
VNA_SHELL_FUNCTION(cmd_ultra_start)
{
if (argc != 1) {
@@ -350,7 +370,7 @@ VNA_SHELL_FUNCTION(cmd_if1)
config_save();
}
}
-
+#endif
VNA_SHELL_FUNCTION(cmd_trigger)
{
@@ -401,7 +421,6 @@ VNA_SHELL_FUNCTION(cmd_selftest)
static int VFO = 0;
-#ifdef __ADF4351__
uint32_t xtoi(char *t)
{
@@ -421,6 +440,8 @@ uint32_t xtoi(char *t)
return v;
}
+#ifdef __ADF4351__
+
VNA_SHELL_FUNCTION(cmd_x)
{
uint32_t reg;
@@ -478,6 +499,7 @@ VNA_SHELL_FUNCTION(cmd_d)
(void) argc;
(void) argv;
int32_t a = my_atoi(argv[0]);
+#ifdef TINYSA4
int32_t d;
if (argc == 2)
d = my_atoi(argv[1]);
@@ -498,6 +520,10 @@ VNA_SHELL_FUNCTION(cmd_d)
}
// setting.lo_drive=a;
// dirty = true;
+#else
+ setting.lo_drive=a;
+ dirty = true;
+#endif
}
#if 0
@@ -522,7 +548,7 @@ VNA_SHELL_FUNCTION(cmd_a)
{
(void)argc;
if (argc != 1) {
- shell_printf("a=%Lu\r\n", frequencyStart);
+ shell_printf("a=%U\r\n", frequencyStart);
return;
}
freq_t value = my_atoui(argv[0]);
@@ -534,7 +560,7 @@ VNA_SHELL_FUNCTION(cmd_b)
{
(void)argc;
if (argc != 1) {
- shell_printf("b=%Lu\r\n", frequencyStop);
+ shell_printf("b=%U\r\n", frequencyStop);
return;
}
freq_t value = my_atoui(argv[0]);
@@ -588,7 +614,7 @@ VNA_SHELL_FUNCTION(cmd_v)
VNA_SHELL_FUNCTION(cmd_y)
{
if (argc < 1) {
- shell_printf("usage: y {addr(0-FF)} [value(0-FF)]+\r\n");
+ shell_printf("usage: y {addr(0-95)} [value(0-0xFF)]\r\n");
return;
}
#ifdef __SI4432__
@@ -700,7 +726,9 @@ VNA_SHELL_FUNCTION(cmd_p)
{
(void)argc;
int p = my_atoi(argv[0]);
+#ifdef TINYSA4
SI4463_set_output_level(p);
+#endif
return;
int a = my_atoi(argv[1]);
if (p==5)
@@ -712,6 +740,7 @@ return;
set_refer_output(a);
}
+#ifdef TINYSA4
VNA_SHELL_FUNCTION(cmd_g)
{
(void)argc;
@@ -719,6 +748,7 @@ VNA_SHELL_FUNCTION(cmd_g)
int a = my_atoi(argv[1]);
SI4463_set_gpio(p,a);
}
+#endif
VNA_SHELL_FUNCTION(cmd_w)
{
@@ -743,7 +773,7 @@ VNA_SHELL_FUNCTION(cmd_correction)
if (argc == 0) {
shell_printf("index frequency value\r\n");
for (int i=0; i= 100*ONE_MS_TIME || S_STATE(setting.spur_removal)) // if no fast CW sweep possible
@@ -309,6 +384,7 @@ void set_gridlines(int d)
//int setting_frequency_10mhz = 10000000;
+#ifdef TINYSA4
void set_30mhz(freq_t f)
{
if (f < 29000000 || f > 31000000)
@@ -318,6 +394,17 @@ void set_30mhz(freq_t f)
dirty = true;
update_grid();
}
+#else
+void set_10mhz(freq_t f)
+{
+ if (f < 9000000 || f > 11000000)
+ return;
+ config.setting_frequency_10mhz = f;
+ config_save();
+ dirty = true;
+ update_grid();
+}
+#endif
void set_measurement(int m)
{
@@ -385,6 +472,7 @@ void toggle_tracking_output(void)
dirty = true;
}
+#ifdef TINYSA4
void toggle_high_out_adf4350(void)
{
high_out_adf4350 = !high_out_adf4350;
@@ -402,6 +490,7 @@ void set_extra_lna(int t)
setting.extra_lna = t;
dirty = true;
}
+#endif
void toggle_mirror_masking(void)
{
@@ -432,6 +521,7 @@ void toggle_below_IF(void)
dirty = true;
}
+#ifdef TINYSA4
void toggle_ultra(void)
{
if (S_IS_AUTO(setting.ultra ))
@@ -442,6 +532,7 @@ void toggle_ultra(void)
setting.ultra = true;
dirty = true;
}
+#endif
void set_modulation(int m)
{
@@ -498,9 +589,6 @@ void set_modulo(uint32_t f)
}
#endif
-#define POWER_STEP 0 // Should be 5 dB but apparently it is lower
-#define RECEIVE_SWITCH_ATTENUATION 21
-
void set_auto_attenuation(void)
{
setting.auto_attenuation = true;
@@ -518,12 +606,35 @@ void set_auto_reflevel(int v)
setting.auto_reflevel = v;
}
+int level_min(void)
+{
+ if (setting.mode == M_GENLOW)
+ return SL_GENLOW_LEVEL_MIN + config.low_level_output_offset;
+ else
+ return SL_GENHIGH_LEVEL_MIN + config.high_level_output_offset;
+}
+
+int level_max(void)
+{
+ if (setting.mode == M_GENLOW)
+ return SL_GENLOW_LEVEL_MIN + SL_GENLOW_LEVEL_RANGE + config.low_level_output_offset;
+ else
+ return SL_GENHIGH_LEVEL_MIN + SL_GENHIGH_LEVEL_RANGE + config.high_level_output_offset;
+}
+
+int level_range(void)
+{
+ if (setting.mode == M_GENLOW)
+ return SL_GENLOW_LEVEL_RANGE ;
+ else
+ return SL_GENHIGH_LEVEL_RANGE;
+}
float get_attenuation(void)
{
float actual_attenuation = setting.attenuate_x2 / 2.0;
if (setting.mode == M_GENLOW) {
- return (float)( SL_GENLOW_LEVEL_MIN + SL_GENLOW_LEVEL_RANGE + config.low_level_output_offset - actual_attenuation - (MAX_DRIVE - setting.rx_drive) * SI_DRIVE_STEP - ( setting.atten_step ? SWITCH_ATTENUATION : 0) );
+ return (float)( level_max() - actual_attenuation - (MAX_DRIVE - setting.rx_drive) * SI_DRIVE_STEP - ( setting.atten_step ? SWITCH_ATTENUATION : 0) );
} else if (setting.atten_step) {
if (setting.mode == M_LOW)
return actual_attenuation + RECEIVE_SWITCH_ATTENUATION;
@@ -534,22 +645,22 @@ float get_attenuation(void)
}
static pureRSSI_t get_signal_path_loss(void){
-#ifdef __ULTRA__
- if (setting.mode == M_ULTRA)
- return float_TO_PURE_RSSI(-15); // Loss in dB, -9.5 for v0.1, -12.5 for v0.2
-#endif
+#ifdef TINYSA4
if (setting.mode == M_LOW)
return float_TO_PURE_RSSI(-4); // Loss in dB, -9.5 for v0.1, -12.5 for v0.2
return float_TO_PURE_RSSI(+19); // Loss in dB (+ is gain)
+#else
+ if (setting.mode == M_LOW)
+ return float_TO_PURE_RSSI(-5.5); // Loss in dB, -9.5 for v0.1, -12.5 for v0.2
+ return float_TO_PURE_RSSI(+7); // Loss in dB (+ is gain)
+#endif
}
-static const int drive_dBm [] = {-15,-12,-9,-6};
-
-
void set_level(float v) // Set the output level in dB in high/low output
{
if (setting.mode == M_GENHIGH) {
int d = 0;
+ v = v - config.high_level_output_offset;
while (drive_dBm[d] < v - 1 && (unsigned int)d < (sizeof(drive_dBm)/sizeof(int))-1 )
d++;
// if (d == 8 && v < -12) // Round towards closest level
@@ -565,15 +676,16 @@ void set_level(float v) // Set the output level in dB in high/low output
float get_level(void)
{
if (setting.mode == M_GENHIGH) {
- return drive_dBm[setting.lo_drive];
+ return drive_dBm[setting.lo_drive] + config.high_level_output_offset;
} else {
return get_attenuation();
}
}
+
void set_attenuation(float a) // Is used both in low output mode and high/low input mode
{
if (setting.mode == M_GENLOW) {
- a = a - (SL_GENLOW_LEVEL_MIN + config.low_level_output_offset + SL_GENLOW_LEVEL_RANGE); // Move to zero for max power
+ a = a - level_max(); // Move to zero for max power
if (a > 0)
a = 0;
if( a < - SWITCH_ATTENUATION) {
@@ -668,10 +780,6 @@ void set_actual_power(float o) // Set peak level to known value
config.high_level_offset = new_offset;
} else if (setting.mode == M_LOW) {
config.low_level_offset = new_offset;
-#ifdef __ULTRA__
- } else if (setting.mode == M_ULTRA) {
- config.low_level_offset = new_offset;
-#endif
}
dirty = true;
config_save();
@@ -813,8 +921,13 @@ void toggle_tracking(void)
{
setting.tracking = !setting.tracking;
if (setting.tracking) {
- set_refer_output(0);
+#ifdef TINYSA4
+ set_refer_output(0);
set_sweep_frequency(ST_CENTER, 30000000);
+#else
+ set_refer_output(2);
+ set_sweep_frequency(ST_CENTER, 10000000);
+#endif
set_sweep_frequency(ST_SPAN, 5000000);
} else {
set_refer_output(-1);
@@ -960,7 +1073,7 @@ void set_reflevel(float level)
}
void round_reflevel_to_scale(void) {
- int multi = floor((setting.reflevel + setting.scale/2)/setting.scale);
+ int multi = floorf((setting.reflevel + setting.scale/2)/setting.scale);
if (UNIT_IS_LINEAR(setting.unit)) {
if (multi < NGRIDY) {
setting.reflevel = setting.scale*10; // Never negative bottom
@@ -1019,11 +1132,8 @@ void set_offset(float offset)
{
setting.offset = offset;
int min,max;
- if (setting.mode == M_GENLOW) {
- min = SL_GENLOW_LEVEL_MIN + config.low_level_output_offset; max = SL_GENLOW_LEVEL_MIN + SL_GENLOW_LEVEL_RANGE + config.low_level_output_offset;
- } else {
- min = SL_GENHIGH_LEVEL_MIN; max = SL_GENHIGH_LEVEL_MIN + SL_GENHIGH_LEVEL_RANGE;
- }
+ min = level_min();
+ max = min + level_range();
plot_printf(low_level_help_text, sizeof low_level_help_text, "%+d..%+d", min + (int)offset, max + (int)offset);
force_set_markmap();
dirty = true; // No HW update required, only status panel refresh but need to ensure the cached value is updated in the calculation of the RSSI
@@ -1064,10 +1174,6 @@ void set_trigger(int trigger)
//}
void set_mode(int m)
{
-#ifdef __ULTRA__
- if (m == 6)
- m = M_ULTRA;
-#endif
dirty = true;
if (setting.mode == m)
return;
@@ -1193,7 +1299,7 @@ pureRSSI_t get_frequency_correction(freq_t f) // Frequency dependent RSSI c
pureRSSI_t cv = 0;
if (setting.mode == M_GENHIGH)
return(0.0);
-
+#ifdef TINYSA4
if (setting.extra_lna) {
if (f > 2100000000U) {
cv += float_TO_PURE_RSSI(+13);
@@ -1205,7 +1311,7 @@ pureRSSI_t get_frequency_correction(freq_t f) // Frequency dependent RSSI c
if (f > ULTRA_MAX_FREQ) {
cv += float_TO_PURE_RSSI(+4); // 4dB loss in harmonic mode
}
-
+#endif
int i = 0;
while (f > setting.correction_frequency[i] && i < CORRECTION_POINTS)
i++;
@@ -1246,6 +1352,12 @@ void setup_sa(void)
#ifdef __SI4432__
SI4432_Init();
#endif
+#ifdef TINYSA3
+ for (unsigned int i = 0; i < sizeof(old_freq)/sizeof(unsigned long) ; i++) {
+ old_freq[i] = 0;
+ real_old_freq[i] = 0;
+ }
+#endif
#ifdef __SI4432__
SI4432_Sel = SI4432_RX ;
SI4432_Receive();
@@ -1260,7 +1372,7 @@ void setup_sa(void)
#ifdef __SI4463__
SI4463_init_rx(); // Must be before ADF4351_setup!!!!
#endif
-
+#ifdef TINYSA
ADF4351_Setup();
enable_extra_lna(false);
enable_ultra(false);
@@ -1268,7 +1380,7 @@ void setup_sa(void)
enable_high(false);
fill_spur_table();
-
+#endif
#if 0 // Measure fast scan time
setting.sweep_time_us = 0;
setting.additional_step_delay_us = 0;
@@ -1289,7 +1401,9 @@ void setup_sa(void)
#define OFFSET_LOWER_BOUND 0
#endif
+#ifdef TINYSA4
static int fast_counter = 0;
+#endif
void set_freq(int V, freq_t freq) // translate the requested frequency into a setting of the SI4432
{
@@ -1339,6 +1453,8 @@ void set_freq(int V, freq_t freq) // translate the requested frequency into a
} else {
target_f = freq + 80000;
}
+ if (target_f > 960000000)
+ target_f = 960000000;
SI4432_Set_Frequency(target_f);
SI4432_Write_2_Byte(SI4432_FREQ_OFFSET1, 0, 0x02); // set offset to most negative
// SI4432_Write_Byte(SI4432_FREQ_OFFSET2, 0x02);
@@ -1356,8 +1472,9 @@ void set_freq(int V, freq_t freq) // translate the requested frequency into a
SI4432_Set_Frequency(freq); // Not in fast mode
real_old_freq[V] = freq;
}
- } else
+ }
#endif
+#ifdef TINYSA4
if (V==ADF4351_LO){
#if 0
if (setting.step_delay_mode == SD_FAST) { // If in fast scanning mode and NOT SI4432_RX !!!!!!
@@ -1399,23 +1516,24 @@ void set_freq(int V, freq_t freq) // translate the requested frequency into a
real_old_freq[V] = SI4463_set_freq(freq); // Not in fast mode
}
done:
+#endif
old_freq[V] = freq;
}
#ifdef __SI4432__
void set_switch_transmit(void) {
- SI4432_Write_Byte(SI4432_GPIO0_CONF, 0x1f);// Set switch to transmit
- SI4432_Write_Byte(SI4432_GPIO1_CONF, 0x1d);
+ SI4432_Write_2_Byte(SI4432_GPIO0_CONF, 0x1f, 0x1d);// Set switch to transmit
+ // SI4432_Write_Byte(SI4432_GPIO1_CONF, 0x1d);
}
void set_switch_receive(void) {
- SI4432_Write_Byte(SI4432_GPIO0_CONF, 0x1d);// Set switch to receive
- SI4432_Write_Byte(SI4432_GPIO1_CONF, 0x1f);
+ SI4432_Write_2_Byte(SI4432_GPIO0_CONF, 0x1d, 0x1f);// Set switch to receive
+// SI4432_Write_Byte(SI4432_GPIO1_CONF, 0x1f);
}
void set_switch_off(void) {
- SI4432_Write_Byte(SI4432_GPIO0_CONF, 0x1d);// Set both switch off
- SI4432_Write_Byte(SI4432_GPIO1_CONF, 0x1f);
+ SI4432_Write_2_Byte(SI4432_GPIO0_CONF, 0x1d, 0x1f);// Set both switch off
+// SI4432_Write_Byte(SI4432_GPIO1_CONF, 0x1f);
}
#endif
@@ -1429,14 +1547,11 @@ void set_switches(int m)
real_old_freq[0] = 0;
real_old_freq[1] = 0;
SI4432_Sel = SI4432_LO ;
- SI4432_Write_Byte(SI4432_FREQ_OFFSET1, 0); // Back to nominal offset
- SI4432_Write_Byte(SI4432_FREQ_OFFSET2, 0);
+ SI4432_Write_2_Byte(SI4432_FREQ_OFFSET1, 0, 0); // Back to nominal offset
+// SI4432_Write_Byte(SI4432_FREQ_OFFSET2, 0);
#endif
switch(m) {
case M_LOW: // Mixed into 0
-#ifdef __ULTRA__
-case M_ULTRA:
-#endif
#ifdef __SI4432__
SI4432_Sel = SI4432_RX ;
SI4432_Receive();
@@ -1455,6 +1570,7 @@ case M_ULTRA:
}
#endif
set_AGC_LNA();
+#ifdef TINYSA4
ADF4351_enable(true);
ADF4351_drive(setting.lo_drive);
if (setting.tracking_output)
@@ -1462,6 +1578,7 @@ case M_ULTRA:
else
ADF4351_enable_aux_out(false);
ADF4351_enable_out(true);
+#endif
#ifdef __SI4432__
SI4432_Sel = SI4432_LO ;
@@ -1473,10 +1590,12 @@ case M_ULTRA:
SI4432_Transmit(setting.lo_drive);
// set_calibration_freq(setting.refer);
#endif
+#ifdef TINYSA4
enable_rx_output(false);
enable_high(false);
enable_extra_lna(setting.extra_lna);
enable_ultra(false);
+#endif
break;
case M_HIGH: // Direct into 1
mute:
@@ -1498,6 +1617,7 @@ mute:
SI4463_init_rx();
#endif
set_AGC_LNA();
+#ifdef TINYSA4
ADF4351_enable_aux_out(false);
ADF4351_enable_out(false);
ADF4351_enable(false);
@@ -1509,6 +1629,7 @@ mute:
enable_high(true);
enable_extra_lna(false);
enable_ultra(false);
+#endif
break;
case M_GENLOW: // Mixed output from 0
if (setting.mute)
@@ -1534,6 +1655,7 @@ case M_GENLOW: // Mixed output from 0
#ifdef __SI4468__
SI4463_init_tx();
#endif
+#ifdef TINYSA4
ADF4351_enable_out(true);
ADF4351_drive(setting.lo_drive);
ADF4351_enable(true);
@@ -1548,14 +1670,16 @@ case M_GENLOW: // Mixed output from 0
enable_high(false);
enable_extra_lna(false);
enable_ultra(false);
+#endif
break;
case M_GENHIGH: // Direct output from 1
if (setting.mute)
goto mute;
- enable_high(true); // Must be first to protect SAW filters
+#ifdef TINYSA4
+ enable_high(true); // Must be first to protect SAW filters
enable_extra_lna(false);
enable_ultra(false);
-
+#endif
#ifdef __SI4432__
SI4432_Sel = SI4432_RX ;
SI4432_Receive();
@@ -1569,7 +1693,7 @@ case M_GENHIGH: // Direct output from 1
}
SI4432_Transmit(setting.lo_drive);
#endif
-
+#ifdef TINYSA4
if (high_out_adf4350) {
#ifdef __SI4468__
SI4463_init_rx();
@@ -1598,6 +1722,7 @@ case M_GENHIGH: // Direct output from 1
#endif
}
+#endif
break;
}
@@ -1628,8 +1753,12 @@ void update_rbw(void) // calculate the actual_rbw and the vbwSteps (#
temp_actual_rbw_x10 = setting.vbw_x10;
#endif
} else
- temp_actual_rbw_x10 = setting.vbw_x10; // rbw is NOT twice the frequency step to ensure no gaps in coverage
- }
+#ifdef TINYSA4
+ temp_actual_rbw_x10 = setting.vbw_x10; // rbw is NOT twice the frequency step to ensure no gaps in coverage
+#else
+ temp_actual_rbw_x10 = 2*setting.vbw_x10; // rbw is twice the frequency step to ensure no gaps in coverage
+#endif
+ }
#ifdef __SI4432__
if (temp_actual_rbw_x10 < 26)
temp_actual_rbw_x10 = 26;
@@ -1666,7 +1795,11 @@ void update_rbw(void) // calculate the actual_rbw and the vbwSteps (#
}
}
+#ifdef TINYSA4
#define frequency_seatch_gate 60 // 120% of the RBW
+#else
+#define frequency_seatch_gate 100 // 200% of the RBW
+#endif
int binary_search_frequency(freq_t f) // Search which index in the frequency tabled matches with frequency f using actual_rbw
{
@@ -1707,6 +1840,8 @@ int
search_maximum(int m, freq_t center, int span)
{
int center_index = binary_search_frequency(center);
+ if (center_index < 0)
+ return false;
int from = center_index - span/2;
int found = false;
int to = center_index + span/2;
@@ -1769,22 +1904,21 @@ search_maximum(int m, freq_t center, int span)
}
//static int spur_old_stepdelay = 0;
-//static const unsigned int spur_IF = DEFAULT_IF; // The IF frequency for which the spur table is value
-//static const unsigned int spur_alternate_IF = DEFAULT_SPUR_IF; // if the frequency is found in the spur table use this IF frequency
+#ifdef TINYSA3
+static const unsigned int spur_IF = DEFAULT_IF; // The IF frequency for which the spur table is value
+static const unsigned int spur_alternate_IF = DEFAULT_SPUR_IF; // if the frequency is found in the spur table use this IF frequency
+#endif
static freq_t spur_table[] = // Frequencies to avoid
{
+#ifdef TINYSA4
243775000, // OK
325000000, // !!! This is a double spur
325190000, // !!! This is a double spur
487541650, // OK This is linked to the MODULO of the ADF4350
650687000, // OK
731780000, // OK
-
-
-
-
- #if 0
- // 580000, // 433.8 MHz table
+#else
+// 580000, // 433.8 MHz table
// 880000, //?
960000,
// 1487000, //?
@@ -1820,6 +1954,12 @@ static freq_t spur_table[] = // Frequencies to
40960000,
41600000,
49650000,
+ 272400000,
+ 287950000,
+// 288029520,
+ 332494215,
+
+
#endif
};
@@ -1827,8 +1967,13 @@ int binary_search(freq_t f)
{
int L = 0;
int R = (sizeof spur_table)/sizeof(int) - 1;
+#ifdef TINYSA4
freq_t fmin = f - spur_gate;
freq_t fplus = f + spur_gate;
+#else
+ freq_t fmin = f - actual_rbw_x10 * (100 / 2);
+ freq_t fplus = f + actual_rbw_x10 * (100 / 2);
+#endif
while (L <= R) {
int m = (L + R) / 2;
if (spur_table[m] < fmin)
@@ -1838,6 +1983,7 @@ int binary_search(freq_t f)
else
return true; // index is m
}
+#ifdef TINYSA4
#if 1
if (!setting.auto_IF && setting.frequency_IF-2000000 < f && f < setting.frequency_IF -200000)
return true;
@@ -1846,9 +1992,11 @@ int binary_search(freq_t f)
#endif
if(4*config.frequency_IF1 > fmin && 4*config.frequency_IF1 < fplus)
return true;
+#endif
return false;
}
+#ifdef TINYSA4
static const uint8_t spur_div[] = {4, 3, 3, 2, 3, 4};
static const uint8_t spur_mul[] = {1, 1, 1, 1, 2, 3};
#define IF_OFFSET 468750*4 //
@@ -1875,14 +2023,20 @@ void fill_spur_table(void)
spur_table[i] = target;
}
}
+#endif
int avoid_spur(freq_t f) // find if this frequency should be avoided
{
// int window = ((int)actual_rbw ) * 1000*2;
// if (window < 50000)
// window = 50000;
+#ifdef TINYSA4
if (setting.mode != M_LOW /* || !setting.auto_IF */)
return(false);
+#else
+ if (setting.mode != M_LOW || !setting.auto_IF || actual_rbw_x10 > 3000)
+ return(false);
+#endif
return binary_search(f);
}
@@ -1920,10 +2074,17 @@ static const int fm_modulation[4][MODULATION_STEPS] = // Avoid sign changes in
static const int fm_modulation_offset[4] =
{
+#ifdef TINYSA
5000, //85000,
0, //80000,
-2700, //165000,
0, //160000
+#else
+ 85000,
+ 80000,
+ 165000,
+ 160000
+#endif
};
@@ -1950,10 +2111,12 @@ static void calculate_static_correction(void) // Calculate the
- get_signal_path_loss()
+ float_TO_PURE_RSSI(
+ get_level_offset()
+ + get_attenuation()
+#ifdef TINYSA4
- (S_STATE(setting.agc)? 0 : 33)
- (S_STATE(setting.lna)? 0 : 0)
- + get_attenuation()
+ (setting.extra_lna ? -23.0 : 0) // TODO <------------------------- set correct value
+#endif
- setting.offset);
}
@@ -2033,7 +2196,8 @@ pureRSSI_t perform(bool break_on_operation, int i, freq_t f, int tracking) /
}
}
- if (setting.mode == M_GENLOW && ( setting.frequency_step != 0 || setting.level_sweep != 0.0)) {// start burst
+ #ifdef __SI4432__
+ if (setting.mode == M_GENLOW && ( setting.frequency_step != 0 || setting.level_sweep != 0.0)) {// pulse high out
SI4432_Sel = SI4432_LO ;
if (i == 0) {
// set_switch_transmit();
@@ -2043,7 +2207,7 @@ pureRSSI_t perform(bool break_on_operation, int i, freq_t f, int tracking) /
SI4432_Write_Byte(SI4432_GPIO2_CONF, 0x1F) ; // Set GPIO2 output to ground
}
}
-
+#endif
if (setting.mode == M_GENLOW && ( setting.frequency_step != 0 || setting.level_sweep != 0.0 || i == 0)) {// if in low output mode and level sweep or frequency weep is active or at start of sweep
float ls=setting.level_sweep; // calculate and set the output level
if (ls > 0)
@@ -2054,17 +2218,18 @@ pureRSSI_t perform(bool break_on_operation, int i, freq_t f, int tracking) /
a += PURE_TO_float(get_frequency_correction(f));
if (a != old_a) {
old_a = a;
- a = a - (SL_GENLOW_LEVEL_MIN + SL_GENLOW_LEVEL_RANGE + config.low_level_output_offset); // convert to all settings maximum power output equals a = zero
-
+ a = a - level_max(); // convert to all settings maximum power output equals a = zero
if (a < -SWITCH_ATTENUATION) {
a = a + SWITCH_ATTENUATION;
#ifdef TINYSA3
+ SI4432_Sel = SI4432_RX ;
set_switch_receive();
#else
enable_rx_output(false);
#endif
} else {
#ifdef TINYSA3
+ SI4432_Sel = SI4432_RX ;
set_switch_transmit();
#else
enable_rx_output(true);
@@ -2123,8 +2288,13 @@ pureRSSI_t perform(bool break_on_operation, int i, freq_t f, int tracking) /
modulation_delay += config.cor_nfm; // -17 default
// modulation_index = 0; // default value
}
+#ifdef TINYSA4
if ((setting.mode == M_GENLOW) ||
(setting.mode == M_GENHIGH && f > ((freq_t)480000000) ) )
+#else
+ if ((setting.mode == M_GENLOW && f > ((freq_t)480000000) - DEFAULT_IF) ||
+ (setting.mode == M_GENHIGH && f > ((freq_t)480000000) ) )
+#endif
modulation_index += 2;
current_fm_modulation = (int *)fm_modulation[modulation_index];
f -= fm_modulation_offset[modulation_index]; // Shift output frequency
@@ -2160,6 +2330,7 @@ modulation_again:
my_microsecond_delay(modulation_delay);
}
}
+#ifdef TINYSA4
// -------------- set ultra ---------------------------------
if (setting.mode == M_LOW && config.ultra) {
if ((S_IS_AUTO(setting.ultra)&& f > config.ultra_threshold) || S_STATE(setting.ultra) ) {
@@ -2167,17 +2338,21 @@ modulation_again:
} else
enable_ultra(false);
}
+#endif
// -------------------------------- Acquisition loop for one requested frequency covering spur avoidance and vbwsteps ------------------------
pureRSSI_t RSSI = float_TO_PURE_RSSI(-150);
#ifdef __DEBUG_SPUR__ // For debugging the spur avoidance control
+#ifdef TINYSA4
if (!setting.auto_IF)
- stored_t[i] = -90.0; // Display when to do spur shift in the stored trace
+#endif
+ stored_t[i] = -90.0; // Display when to do spur shift in the stored trace
#endif
int t = 0;
do {
freq_t lf = f;
if (vbwSteps > 1) { // Calculate sub steps
- int offs_div10 = (t - (vbwSteps >> 1)) * 100; // steps of x10 * settings.
+#ifdef TINYSA4
+ int offs_div10 = (t - (vbwSteps >> 1)) * 100; // steps of x10 * settings.
if ((vbwSteps & 1) == 0) // Uneven steps, center
offs_div10+= 50; // Even, shift half step
int offs = (offs_div10 * (int32_t)setting.vbw_x10 )/ vbwSteps;
@@ -2188,6 +2363,15 @@ modulation_again:
lf += offs;
// if (lf > MAX_LO_FREQ)
// lf = 0;
+#else
+ int offs_div10 = (t - (vbwSteps >> 1)) * 500 / 10; // steps of half the rbw
+ if ((vbwSteps & 1) == 0) // Uneven steps, center
+ offs_div10+= 250 / 10; // Even, shift half step
+ int offs = offs_div10 * actual_rbw_x10;
+ if (setting.step_delay_mode == SD_PRECISE)
+ offs>>=1; // steps of a quarter rbw
+ lf += offs;
+#endif
}
// -------------- Calculate the IF -----------------------------
@@ -2199,17 +2383,23 @@ modulation_again:
again: // Spur reduction jumps to here for second measurement
local_IF=0; // to get rid of warning
+#ifdef TINYSA4
int LO_shifted = false;
int LO_mirrored = false;
int LO_harmonic = false;
+#endif
if (MODE_HIGH(setting.mode)) {
local_IF = 0;
} else if (MODE_LOW(setting.mode)){ // All low mode
if (!setting.auto_IF)
local_IF = setting.frequency_IF;
else
+#ifdef TINYSA4
local_IF = config.frequency_IF1;
- if (setting.mode == M_LOW) {
+#else
+ local_IF = DEFAULT_IF;
+#endif
+ if (setting.mode == M_LOW) {
if (tracking) { // VERY SPECIAL CASE!!!!! Measure BPF
#if 0 // Isolation test
local_IF = lf;
@@ -2219,6 +2409,14 @@ modulation_again:
lf = (setting.refer == -1 ? 0 : reffer_freq[setting.refer]);
#endif
} else {
+#ifdef TINYSA3
+ if(!in_selftest && avoid_spur(lf)) { // check if alternate IF is needed to avoid spur.
+ local_IF = spur_alternate_IF;
+#ifdef __DEBUG_SPUR__ // For debugging the spur avoidance control
+ stored_t[i] = -60.0; // Display when to do spur shift in the stored trace
+#endif
+ }
+#endif
#ifdef __SI4468__
if (S_IS_AUTO(setting.spur_removal)) {
if (lf >= config.ultra_threshold) {
@@ -2228,16 +2426,21 @@ modulation_again:
}
}
#endif
+#ifdef TINYSA4
if (S_IS_AUTO(setting.below_IF)) {
if ((uint64_t)lf + (uint64_t)local_IF> MAX_LO_FREQ && lf < ULTRA_MAX_FREQ)
setting.below_IF = S_AUTO_ON; // Only way to reach this range.
else
setting.below_IF = S_AUTO_OFF; // default is above IF
}
-
+#endif
if (S_STATE(setting.spur_removal)){ // If in low input mode and spur reduction is on
if (S_IS_AUTO(setting.below_IF) &&
- ( lf > ULTRA_MAX_FREQ || lf < local_IF/2 /* || ( (uint64_t)lf + (uint64_t)local_IF< MAX_LO_FREQ && lf + local_IF > 136000000ULL) */)
+#ifdef TINYSA4
+ ( lf > ULTRA_MAX_FREQ || lf < local_IF/2 /* || ( (uint64_t)lf + (uint64_t)local_IF< MAX_LO_FREQ && lf + local_IF > 136000000ULL) */)
+#else
+ (lf < local_IF / 2 || lf > local_IF)
+#endif
)
{ // else low/above IF
if (spur_second_pass)
@@ -2256,7 +2459,9 @@ modulation_again:
#endif
}
}
- } else if(!in_selftest && avoid_spur(lf)) { // check if alternate IF is needed to avoid spur.
+ }
+#ifdef TINYSA4
+ else if(!in_selftest && avoid_spur(lf)) { // check if alternate IF is needed to avoid spur.
if (S_IS_AUTO(setting.below_IF) && lf < local_IF/2 - 1000000) {
setting.below_IF = S_AUTO_ON;
} else if (setting.auto_IF) {
@@ -2270,61 +2475,36 @@ modulation_again:
stored_t[i] = -60.0; // Display when to do spur shift in the stored trace
#endif
}
+#endif
}
} else { // Output mode
if (setting.modulation == MO_EXTERNAL) // VERY SPECIAL CASE !!!!!! LO input via high port
local_IF += lf;
}
-#ifdef __ULTRA__
- } else if (setting.mode == M_ULTRA) { // No above/below IF mode in Ultra
- local_IF = setting.frequency_IF + (int)(actual_rbw < 350.0 ? S_STATE(setting.spur_removal)*300000 : 0 );
-#ifdef __SI4432__
- set_freq (SI4432_RX , local_IF);
-#endif
-#ifdef __SI4463__
- set_freq (SI4463_RX , local_IF);
-#endif
- // local_IF = setting.frequency_IF + (int)(actual_rbw < 300.0?S_STATE(setting.spur_removal) * 1000 * actual_rbw:0);
-#endif
}
// ------------- Set LO ---------------------------
-#ifdef __ULTRA__
- if (setting.mode == M_ULTRA) { // Set LO to correct harmonic in Ultra mode
- // if (lf > 3406000000 )
- // setFreq (1, local_IF/5 + lf/5);
- // else
- if (S_STATE(setting.spur_removal) != 1) { // Left of tables
- if (lf > 3250000000 )
- set_freq (SI4432_LO , lf/5 - local_IF/5);
- if (lf > 1250000000 )
- set_freq (SI4432_LO, lf/3 - local_IF/3);
- else
- set_freq (SI4432_LO, lf - local_IF);
-
- } else { // Right of tables
- if (lf >= 2350000000)
- set_freq (SI4432_LO, lf/5 + local_IF/5);
- else
- set_freq (SI4432_LO, lf/3 + local_IF/3);
- }
- } else
-#endif
{ // Else set LO ('s)
- uint64_t target_f;
+ freq_t target_f;
+#ifdef TINYSA4
int inverted_f = false;
+#endif
if (setting.mode == M_LOW && !setting.tracking && S_STATE(setting.below_IF)) { // if in low input mode and below IF
+#ifdef TINYSA4
if (lf < local_IF)
- target_f = (uint64_t)local_IF-(uint64_t)lf; // set LO SI4432 to below IF frequency
+#endif
+ target_f = local_IF-lf; // set LO SI4432 to below IF frequency
+#ifdef TINYSA4
else {
- target_f = (uint64_t)lf - (uint64_t)local_IF; // set LO SI4432 to below IF frequency
+ target_f = lf - local_IF; // set LO SI4432 to below IF frequency
inverted_f = true;
LO_mirrored = true;
}
+#endif
}
else
- target_f = (uint64_t)local_IF+(uint64_t)lf; // otherwise to above IF, local_IF == 0 in high mode
+ target_f = local_IF+lf; // otherwise to above IF, local_IF == 0 in high mode
#ifdef __SI4432__
set_freq (SI4432_LO, target_f); // otherwise to above IF
#endif
@@ -2465,6 +2645,7 @@ modulation_again:
my_microsecond_delay(200); // To prevent lockup of SI4432
#endif
}
+#ifdef TINYSA4
if (debug_frequencies ) {
freq_t mult = (LO_harmonic ? 3 : 1);
@@ -2505,6 +2686,7 @@ modulation_again:
old_freq[SI4463_RX], real_old_freq[SI4463_RX], (int32_t)real_offset, f_low, f_high , f_error_low, f_error_high);
osalThreadSleepMilliseconds(100);
}
+#endif
// ------------------------- end of processing when in output mode ------------------------------------------------
skip_LO_setting:
@@ -2554,7 +2736,7 @@ modulation_again:
if (i == 0 && setting.frequency_step == 0 && setting.trigger != T_AUTO) { // if in zero span mode and wait for trigger to happen and NOT in trigger mode
-#if 0
+#ifdef TINYSA3
volatile uint8_t trigger_lvl = PURE_TO_DEVICE_RSSI((int16_t)((float_TO_PURE_RSSI(setting.trigger_level) - correct_RSSI - correct_RSSI_freq)));
SI4432_trigger_fill(MODE_SELECT(setting.mode), trigger_lvl, (setting.trigger_direction == T_UP), setting.trigger_mode);
#else
@@ -2619,12 +2801,11 @@ modulation_again:
pureRSSI = 0;
else
pureRSSI = Si446x_RSSI();
-#endif
//#define __DEBUG_FREQUENCY_SETTING__
#ifdef __DEBUG_FREQUENCY_SETTING__ // For debugging the frequency calculation
stored_t[i] = -60.0 + (real_old_freq[ADF4351_LO] - f - old_freq[2])/10;
#endif
-
+#endif
}
#ifdef __SPUR__
static pureRSSI_t spur_RSSI = -1; // Initialization only to avoid warning.
@@ -2647,7 +2828,7 @@ modulation_again:
if (break_on_operation && operation_requested) // break subscanning if requested
break; // abort
} while (t < vbwSteps); // till all sub steps done
-
+#ifdef TINYSA4
if (old_CFGR != orig_CFGR) {
old_CFGR = orig_CFGR;
RCC->CFGR = orig_CFGR;
@@ -2659,6 +2840,10 @@ modulation_again:
rssi = 0;
}
return rssi;
+#else
+ return RSSI + correct_RSSI + correct_RSSI_freq; // add correction
+#endif
+
}
#define MAX_MAX 4
@@ -2710,7 +2895,7 @@ static bool sweep(bool break_on_operation)
}
} else if ( MODE_INPUT(setting.mode) && setting.frequency_step > 0) {
sweep_counter++;
-#if 0
+#ifdef TINYSA3
if (sweep_counter > 50 ) { // refresh HW after 50 sweeps
dirty = true;
refreshing = true;
@@ -2729,9 +2914,11 @@ sweep_again: // stay in sweep loop when output mo
for (int i = 0; i < sweep_points; i++) {
// --------------------- measure -------------------------
pureRSSI_t rssi = perform(break_on_operation, i, frequencies[i], setting.tracking); // Measure RSSI for one of the frequencies
+#ifdef TINYSA4
if (rssi == IGNORE_RSSI)
RSSI = -174.0;
else
+#endif
RSSI = PURE_TO_float(rssi);
// if break back to top level to handle ui operation
if (refreshing)
@@ -2743,8 +2930,9 @@ sweep_again: // stay in sweep loop when output mo
}
return false;
}
-
+#ifdef __SWEEP_OUTPUT__
dacPutChannelX(&DACD2, 0, (((float)i)*config.sweep_voltage)*4.279); // Output sweep voltage 4095 -> 3.3 Volt
+#endif
// ----------------------- in loop AGC ---------------------------------
@@ -2779,8 +2967,11 @@ sweep_again: // stay in sweep loop when output mo
}
if (MODE_INPUT(setting.mode)) {
-
+#ifdef TINYSA4
if ((i & 0x07) == 0 && (setting.actual_sweep_time_us > ONE_SECOND_TIME || (chVTGetSystemTimeX() - start_of_sweep_timestamp) > ONE_SECOND_TIME / 100)) { // if required
+#else
+ if ( (i & 0x07) == 0 && setting.actual_sweep_time_us > ONE_SECOND_TIME) { // if required
+#endif
int pos = i * (WIDTH+1) / sweep_points;
ili9341_set_background(LCD_SWEEP_LINE_COLOR);
ili9341_fill(OFFSETX, CHART_BOTTOM+1, pos, 1); // update sweep progress bar
@@ -2800,8 +2991,6 @@ sweep_again: // stay in sweep loop when output mo
#ifdef __DEBUG_AGC__ // For debugging the AGC control
stored_t[i] = (SI4432_Read_Byte(0x69) & 0x01f) * 3.0 - 90.0; // Display the AGC value in the stored trace
#endif
-#endif
-#ifdef __SI4432__
if (check_for_AM) {
int AGC_value = (SI4432_Read_Byte(0x69) & 0x01f) * 3 - 90;
if (AGC_value < last_AGC_value && last_AGC_direction_up ) {
@@ -3008,7 +3197,11 @@ sweep_again: // stay in sweep loop when output mo
#endif
#endif
// -------------------------- auto attenuate ----------------------------------
+#ifdef TINYSA4
#define AUTO_TARGET_LEVEL -30
+#else
+#define AUTO_TARGET_LEVEL -25
+#endif
#define AUTO_TARGET_WINDOW 2
if (!in_selftest && setting.mode == M_LOW && setting.auto_attenuation) { // calculate and apply auto attenuate
@@ -3123,9 +3316,9 @@ sweep_again: // stay in sweep loop when output mo
float s_ref = setting.reflevel/setting.scale;
if (s_max < s_ref - NGRIDY || s_min > s_ref) { //Completely outside
if (s_max - s_min < NGRIDY - 2)
- set_reflevel(setting.scale*(floor(s_min+8.8+ 1)));
+ set_reflevel(setting.scale*(floorf(s_min+8.8+ 1)));
else
- set_reflevel(setting.scale*(floor(s_max)+1));
+ set_reflevel(setting.scale*(floorf(s_max)+1));
// dirty = true; // Must be above if(scandirty!!!!!)
}else if (s_max > s_ref - 0.5 || s_min > s_ref - 8.8 ) { // maximum to high or minimum to high
set_reflevel(setting.reflevel + setting.scale);
@@ -3491,6 +3684,7 @@ typedef struct test_case {
} test_case_t;
const test_case_t test_case [] =
+#ifdef TINYSA4
{// Condition Preparation Center Span Pass Width(%)Stop
{TC_BELOW, TP_SILENT, 0.005, 0.01, 0, 0, 0}, // 1 Zero Hz leakage
{TC_BELOW, TP_SILENT, 0.015, 0.01, -30, 0, 0}, // 2 Phase noise of zero Hz
@@ -3522,7 +3716,39 @@ const test_case_t test_case [] =
#define TEST_SPUR 22
{TC_BELOW, TP_SILENT, 144, 8, -95, 0, 0 }, // 22 Measure 48MHz spur
};
-
+#else
+{// Condition Preparation Center Span Pass Width(%)Stop
+ {TC_BELOW, TP_SILENT, 0.005, 0.01, 0, 0, 0}, // 1 Zero Hz leakage
+ {TC_BELOW, TP_SILENT, 0.015, 0.01, -30, 0, 0}, // 2 Phase noise of zero Hz
+ {TC_SIGNAL, TP_10MHZ, 20, 7, -39, 10, -90 }, // 3
+ {TC_SIGNAL, TP_10MHZ, 30, 7, -34, 10, -90 }, // 4
+#define TEST_SILENCE 4
+ {TC_BELOW, TP_SILENT, 200, 100, -75, 0, 0}, // 5 Wide band noise floor low mode
+ {TC_BELOW, TPH_SILENT, 600, 720, -75, 0, 0}, // 6 Wide band noise floor high mode
+ {TC_SIGNAL, TP_10MHZEXTRA, 10, 7, -20, 27, -80 }, // 7 BPF loss and stop band
+ {TC_FLAT, TP_10MHZEXTRA, 10, 4, -18, 9, -60}, // 8 BPF pass band flatness
+ {TC_BELOW, TP_30MHZ, 400, 60, -75, 0, -75}, // 9 LPF cutoff
+ {TC_SIGNAL, TP_10MHZ_SWITCH,20, 7, -39, 10, -60 }, // 10 Switch isolation using high attenuation
+ {TC_DISPLAY, TP_30MHZ, 30, 0, -25, 145, -60 }, // 11 Measure atten step accuracy
+ {TC_ATTEN, TP_30MHZ, 30, 0, -25, 145, -60 }, // 12 Measure atten step accuracy
+#define TEST_END 12
+ {TC_END, 0, 0, 0, 0, 0, 0},
+#define TEST_POWER 13
+ {TC_MEASURE, TP_30MHZ, 30, 7, -25, 10, -55 }, // 12 Measure power level and noise
+ {TC_MEASURE, TP_30MHZ, 270, 4, -50, 10, -75 }, // 13 Measure powerlevel and noise
+ {TC_MEASURE, TPH_30MHZ, 270, 4, -40, 10, -65 }, // 14 Calibrate power high mode
+ {TC_END, 0, 0, 0, 0, 0, 0},
+#define TEST_RBW 17
+ {TC_MEASURE, TP_30MHZ, 30, 1, -20, 10, -60 }, // 16 Measure RBW step time
+ {TC_END, 0, 0, 0, 0, 0, 0},
+ {TC_MEASURE, TPH_30MHZ, 300, 4, -48, 10, -65 }, // 14 Calibrate power high mode
+ {TC_MEASURE, TPH_30MHZ_SWITCH,300, 4, -40, 10, -65 }, // 14 Calibrate power high mode
+#define TEST_ATTEN 21
+ {TC_ATTEN, TP_30MHZ, 30, 0, -25, 145, -60 }, // 20 Measure atten step accuracy
+#define TEST_SPUR 22
+ {TC_BELOW, TP_SILENT, 96, 8, -95, 0, 0 }, // 22 Measure 48MHz spur
+};
+#endif
enum {
@@ -3602,6 +3828,7 @@ int validate_signal_within(int i, float margin)
if (setting.measurement == M_PASS_BAND) {
peakFreq = (markers[2].frequency + markers[1].frequency)/2;
markers[0].frequency = peakFreq;
+ markers[0].index = (markers[2].index + markers[1].index)/2;
}
test_fail_cause[i] = "Frequency ";
if (peakFreq < test_case[i].center * 1000000 - 100000 || test_case[i].center * 1000000 + 100000 < peakFreq )
@@ -3689,6 +3916,8 @@ int validate_atten(int i) {
status = TS_FAIL;
// draw_all(true);
}
+
+
}
}
if (status == TS_PASS)
@@ -3782,7 +4011,11 @@ void test_prepare(int i)
{
setting.tracking = false; //Default test setup
setting.atten_step = false;
+#ifdef TINYSA4
setting.frequency_IF = config.frequency_IF1; // Default frequency
+#else
+ setting.frequency_IF = DEFAULT_IF; // Default frequency
+#endif
setting.auto_IF = true;
setting.auto_attenuation = false;
setting.spur_removal = S_OFF;
@@ -3808,8 +4041,13 @@ common_silent:
set_mode(M_LOW);
setting.tracking = true; //Sweep BPF
setting.auto_IF = false;
- setting.frequency_IF = config.frequency_IF1+1000000; // Center on SAW filters
+#ifdef TINYSA4
+ setting.frequency_IF = config.frequency_IF1+700000; // Center on SAW filters
set_refer_output(0);
+#else
+ setting.frequency_IF = DEFAULT_IF+210000; // Center on SAW filters
+ set_refer_output(2);
+#endif
markers[1].enabled = M_ENABLED;
markers[1].mtype = M_DELTA;
markers[2].enabled = M_ENABLED;
@@ -3953,14 +4191,18 @@ void self_test(int test)
ili9341_clear_screen();
reset_settings(M_LOW);
set_refer_output(-1);
-#ifndef DOESNOTFIT
+#ifdef TINYSA4
} else if (test == 1) {
float p2, p1, p;
in_selftest = true; // Spur search
reset_settings(M_LOW);
test_prepare(TEST_SILENCE);
setting.auto_IF = false;
+#ifdef TINYSA4
setting.frequency_IF=config.frequency_IF1;
+#else
+ setting.frequency_IF=DEFAULT_IF;
+ #endif
setting.frequency_step = 30000;
if (setting.test_argument > 0)
setting.frequency_step=setting.test_argument;
@@ -3979,7 +4221,11 @@ void self_test(int test)
f = 400000;
while (f < DEFAULT_MAX_FREQ) {
p = PURE_TO_float(perform(false, 1, f, false));
+#ifdef TINYSA4
#define SPUR_DELTA 15
+#else
+#define SPUR_DELTA 15
+#endif
if ( p2 < p1 - SPUR_DELTA && p < p1 - SPUR_DELTA) {
shell_printf("Spur of %4.2f at %d with count %d\n\r", p1,(f - setting.frequency_step)/1000, add_spur(f - setting.frequency_step));
}
@@ -3997,38 +4243,43 @@ void self_test(int test)
} else if (test == 2) { // Attenuator test
in_selftest = true;
reset_settings(M_LOW);
- float reference_peak_level = 0;
test_prepare(TEST_ATTEN);
test_acquire(TEST_ATTEN); // Acquire test
test_validate(TEST_ATTEN); // Validate test
-#if 1
+#if 0
+ float reference_peak_level = 0;
for (int j= 0; j < 64; j++ ) {
-// test_prepare(TEST_ATTEN);
+ test_prepare(TEST_ATTEN);
set_attenuation(((float)j)/2.0);
-// float summed_peak_level = 0;
-// for (int k=0; k<10; k++) {
- test_acquire(TEST_ATTEN); // Acquire test
- test_validate(TEST_ATTEN); // Validate test
-// summed_peak_level += peakLevel;
-// }
+ float summed_peak_level = 0;
+ for (int k=0; k<10; k++) {
+ test_acquire(TEST_ATTEN); // Acquire test
+ test_validate(TEST_ATTEN); // Validate test
+ summed_peak_level += peakLevel;
+ }
float peaklevel = 0.0;
for (int k = 0 ; k < sweep_points; k++)
peaklevel += actual_t[k];
peaklevel /= sweep_points;
if (j == 0)
- reference_peak_level = peakLevel;
- shell_printf("Attenuation %.2fdB, measured level %.2fdBm, delta %.2fdB\n\r",((float)j)/2.0, peakLevel, peakLevel - reference_peak_level);
+ reference_peak_level = peaklevel;
+ shell_printf("Attenuation %.2fdB, measured level %.2fdBm, delta %.2fdB\n\r",((float)j)/2.0, peaklevel, peaklevel - reference_peak_level);
}
#endif
reset_settings(M_LOW);
} else if (test == 3) { // RBW step time search
in_selftest = true;
+ ui_mode_normal();
+ test_prepare(TEST_RBW);
// reset_settings(M_LOW);
setting.auto_IF = false;
+#ifdef TINYSA4
setting.frequency_IF=config.frequency_IF1;
- ui_mode_normal();
- test_prepare(TEST_RBW);
setting.step_delay = 15000;
+#else
+ setting.frequency_IF=DEFAULT_IF;
+ setting.step_delay = 8000;
+#endif
for (int j= 0; j < SI4432_RBW_count; j++ ) {
if (setting.test_argument != 0)
j = setting.test_argument;
@@ -4090,7 +4341,11 @@ void self_test(int test)
setting.step_delay = setting.step_delay * 4 / 5;
#endif
+#ifdef TINYSA4
setting.offset_delay = 5000;
+#else
+ setting.offset_delay = 1600;
+#endif
#if 1 // Enable for offset tuning stepping
test_value = saved_peakLevel;
if ((uint32_t)(setting.rbw_x10 * 1000) / (sweep_points) < 8000) { // fast mode possible
@@ -4158,7 +4413,9 @@ void self_test(int test)
reset_settings(M_LOW);
test_prepare(TEST_SPUR);
set_RBW(300);
+#ifdef TINYSA4
setting.extra_lna = true;
+#endif
for (int i = 0; i < 31; i++) {
hsical = (RCC->CR & 0xff00) >> 8;
RCC->CR &= RCC_CR_HSICAL;
diff --git a/si4432.c b/si4432.c
index c2f4ad4..930daf8 100644
--- a/si4432.c
+++ b/si4432.c
@@ -1,4 +1,6 @@
-/*
+/* Copyright (c) 2020, Erik Kaashoek erik@kaashoek.com
+ * All rights reserved.
+ *
* This is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3, or (at your option)
@@ -21,57 +23,23 @@
#include "nanovna.h"
#include
#include "si4432.h"
-#include "spi.h"
#pragma GCC push_options
-#pragma GCC optimize ("Og")
-
-// Define for use hardware SPI mode
-#define USE_HARDWARE_SPI_MODE
-
-// 10MHz clock
-#define SI4432_10MHZ 10000000U
-// !!!! FROM ili9341.c for disable it !!!!
-//#define LCD_CS_HIGH palSetPad(GPIOB, GPIOB_LCD_CS)
-#define SI_CS_LOW palClearLine(LINE_RX_SEL)
-#define SI_CS_HIGH palSetLine(LINE_RX_SEL)
-
-#define SI_SDN_LOW palClearLine(LINE_RX_SDN)
-#define SI_SDN_HIGH palSetLine(LINE_RX_SDN)
-
-
-// Hardware or software SPI use
-#ifdef USE_HARDWARE_SPI_MODE
-#define SI4432_SPI SPI1
-//#define SI4432_SPI_SPEED SPI_BR_DIV64
-//#define SI4432_SPI_SPEED SPI_BR_DIV32
-#define SI4432_SPI_SPEED SPI_BR_DIV16
-
-//#define ADF_SPI_SPEED SPI_BR_DIV64
-//#define ADF_SPI_SPEED SPI_BR_DIV32
-#define ADF_SPI_SPEED SPI_BR_DIV4
+#pragma GCC optimize ("O2")
-#define PE_SPI_SPEED SPI_BR_DIV32
+#define SPI2_CLK_HIGH palSetPad(GPIOB, GPIO_SPI2_CLK)
+#define SPI2_CLK_LOW palClearPad(GPIOB, GPIO_SPI2_CLK)
-static uint32_t old_spi_settings;
-#else
-static uint32_t old_port_moder;
-static uint32_t new_port_moder;
-#endif
+#define SPI2_SDI_HIGH palSetPad(GPIOB, GPIO_SPI2_SDI)
+#define SPI2_SDI_LOW palClearPad(GPIOB, GPIO_SPI2_SDI)
+#define SPI2_RESET palClearPort(GPIOB, (1<>GPIO_SPI2_SDO)&1)
+#define SPI2_portSDO (palReadPort(GPIOB)&(1<>GPIOB_SPI_MISO)&1)
-#define SPI1_portSDO (palReadPort(GPIOB)&(1<CR1;
- SPI_BR_SET(SI4432_SPI, SI4432_SPI_SPEED);
-#else
- // Init legs mode for software bitbang
- old_port_moder = GPIOB->MODER;
- new_port_moder = old_port_moder & ~(PIN_MODE_ANALOG(GPIOB_SPI_SCLK)|PIN_MODE_ANALOG(GPIOB_SPI_MISO)|PIN_MODE_ANALOG(GPIOB_SPI_MOSI));
- new_port_moder|= PIN_MODE_OUTPUT(GPIOB_SPI_SCLK)|PIN_MODE_INPUT(GPIOB_SPI_MISO)|PIN_MODE_OUTPUT(GPIOB_SPI_MOSI);
- GPIOB->MODER = new_port_moder;
- // Pull down SPI
- SPI1_SDI_LOW;
- SPI1_CLK_LOW;
-#endif
-}
-
-void stop_SI4432_SPI_mode(void){
-#ifdef USE_HARDWARE_SPI_MODE
- SI4432_SPI->CR1 = old_spi_settings;
-#else
- // Restore hardware SPI
- GPIOB->MODER = old_port_moder;
-#endif
-}
-
static void shiftOut(uint8_t val)
{
-#ifdef USE_HARDWARE_SPI_MODE
- SPI_WRITE_8BIT(SI4432_SPI, val);
- while (SPI_IS_BUSY(SI4432_SPI)) // drop rx and wait tx
- (void)SPI_READ_8BIT(SI4432_SPI);
-#else
- SI4432_log(SI4432_Sel);
- SI4432_log(val);
+// SI4432_log(SI4432_Sel);
+// SI4432_log(val);
uint8_t i = 0;
do {
- SPI1_SDI_HIGH;
- SPI1_CLK_HIGH;
- SPI1_RESET;
+ if (val & 0x80)
+ SPI2_SDI_HIGH;
+ SPI2_CLK_HIGH;
+ SPI2_RESET;
val<<=1;
}while((++i) & 0x07);
-#endif
}
static uint8_t shiftIn(void)
{
-#ifdef USE_HARDWARE_SPI_MODE
- SPI_WRITE_8BIT(SI4432_SPI, 0xFF);
- while (SPI_IS_BUSY(SI4432_SPI)) // drop rx and wait tx
- while (SPI_RX_IS_EMPTY(SI4432_SPI)); //wait rx data in buffer
- return SPI_READ_8BIT(SI4432_SPI);
-#else
uint32_t value = 0;
uint8_t i = 0;
do {
value<<=1;
- SPI1_CLK_HIGH;
- value|=SPI1_portSDO;
- SPI1_CLK_LOW;
+ SPI2_CLK_HIGH;
+ value|=SPI2_portSDO;
+ SPI2_CLK_LOW;
}while((++i) & 0x07);
- return value>>GPIOB_SPI_MISO;
-#endif
+ return value>>GPIO_SPI2_SDO;
}
static inline void shiftInBuf(uint16_t sel, uint8_t addr, deviceRSSI_t *buf, uint16_t size, uint16_t delay) {
-#ifdef USE_HARDWARE_SPI_MODE
- do{
- palClearPad(GPIOB, sel);
- SPI_WRITE_8BIT(SI4432_SPI, addr);
- while (SPI_IS_BUSY(SI4432_SPI)) // drop rx and wait tx
- (void)SPI_READ_8BIT(SI4432_SPI);
-
- SPI_WRITE_8BIT(SI4432_SPI, 0xFF);
- while (SPI_RX_IS_EMPTY(SI4432_SPI)); //wait rx data in buffer
- *buf++=SPI_READ_8BIT(SI4432_SPI);
- palSetPad(GPIOB, sel);
- if (delay)
- my_microsecond_delay(delay);
- }while(--size);
-#else
uint8_t i = 0;
do{
uint32_t value = addr;
- palClearPad(GPIOB, sel);
+ palClearPad(GPIOC, sel);
do {
if (value & 0x80)
- SPI1_SDI_HIGH;
- SPI1_CLK_HIGH;
- SPI1_RESET;
+ SPI2_SDI_HIGH;
+ SPI2_CLK_HIGH;
+ SPI2_RESET;
value<<=1;
}while((++i) & 0x07);
value = 0;
do {
- SPI1_CLK_HIGH;
+ SPI2_CLK_HIGH;
value<<=1;
- value|=SPI1_portSDO;
- SPI1_CLK_LOW;
+ value|=SPI2_portSDO;
+ SPI2_CLK_LOW;
}while((++i) & 0x07);
- palSetPad(GPIOB, sel);
- *buf++=value>>GPIOB_SPI_MISO;
+ palSetPad(GPIOC, sel);
+ *buf++=value>>GPIO_SPI2_SDO;
if (delay)
my_microsecond_delay(delay);
}while(--size);
-#endif
}
#if 0
static void shiftOutBuf(uint8_t *buf, uint16_t size) {
@@ -192,21 +107,17 @@ static void shiftOutBuf(uint8_t *buf, uint16_t size) {
uint8_t val = *buf++;
do{
if (val & 0x80)
- SPI1_SDI_HIGH;
+ SPI2_SDI_HIGH;
else
- SPI1_SDI_LOW;
+ SPI2_SDI_LOW;
val<<=1;
- SPI1_CLK_HIGH;
- SPI1_CLK_LOW;
+ SPI2_CLK_HIGH;
+ SPI2_CLK_LOW;
}while((++i) & 0x07);
}while(--size);
}
#endif
-int SI4432_step_delay = 1500;
-int SI4432_offset_delay = 1500;
-#define MINIMUM_WAIT_FOR_RSSI 280
-
#ifdef __SI4432__
#define CS_SI0_HIGH palSetPad(GPIOC, GPIO_RX_SEL)
#define CS_SI1_HIGH palSetPad(GPIOC, GPIO_LO_SEL)
@@ -227,17 +138,16 @@ volatile int SI4432_Sel = 0; // currently selected SI4432
#define SELECT_DELAY 10
void SI4432_Write_Byte(uint8_t ADR, uint8_t DATA )
{
- set_SPI_mode(SPI_MODE_SI);
// if (SI4432_guard)
// while(1) ;
// SI4432_guard = 1;
-// SPI1_CLK_LOW;
- palClearPad(GPIOB, SI_nSEL[SI4432_Sel]);
-// my_microsecond_delay(SELECT_DELAY);
+// SPI2_CLK_LOW;
+ palClearPad(GPIOC, SI_nSEL[SI4432_Sel]);
+// chThdSleepMicroseconds(SELECT_DELAY);
ADR |= 0x80 ; // RW = 1
shiftOut( ADR );
shiftOut( DATA );
- palSetPad(GPIOB, SI_nSEL[SI4432_Sel]);
+ palSetPad(GPIOC, SI_nSEL[SI4432_Sel]);
// SI4432_guard = 0;
}
@@ -259,34 +169,32 @@ void SI4432_Write_2_Byte(uint8_t ADR, uint8_t DATA1, uint8_t DATA2)
void SI4432_Write_3_Byte(uint8_t ADR, uint8_t DATA1, uint8_t DATA2, uint8_t DATA3 )
{
- set_SPI_mode(SPI_MODE_SI);
// if (SI4432_guard)
// while(1) ;
// SI4432_guard = 1;
-// SPI1_CLK_LOW;
- palClearPad(GPIOB, SI_nSEL[SI4432_Sel]);
-// my_microsecond_delay(SELECT_DELAY);
+// SPI2_CLK_LOW;
+ palClearPad(GPIOC, SI_nSEL[SI4432_Sel]);
+// chThdSleepMicroseconds(SELECT_DELAY);
ADR |= 0x80 ; // RW = 1
shiftOut( ADR );
shiftOut( DATA1 );
shiftOut( DATA2 );
shiftOut( DATA3 );
- palSetPad(GPIOB, SI_nSEL[SI4432_Sel]);
+ palSetPad(GPIOC, SI_nSEL[SI4432_Sel]);
// SI4432_guard = 0;
}
uint8_t SI4432_Read_Byte( uint8_t ADR )
{
- set_SPI_mode(SPI_MODE_SI);
uint8_t DATA ;
// if (SI4432_guard)
// while(1) ;
// SI4432_guard = 1;
-// SPI1_CLK_LOW;
- palClearPad(GPIOB, SI_nSEL[SI4432_Sel]);
+// SPI2_CLK_LOW;
+ palClearPad(GPIOC, SI_nSEL[SI4432_Sel]);
shiftOut( ADR );
DATA = shiftIn();
- palSetPad(GPIOB, SI_nSEL[SI4432_Sel]);
+ palSetPad(GPIOC, SI_nSEL[SI4432_Sel]);
// SI4432_guard = 0;
return DATA ;
}
@@ -463,6 +371,10 @@ void SI4432_Set_Frequency ( freq_t Freq ) {
uint8_t sbsel = 1 << 6;
uint32_t N = (Freq / config.setting_frequency_10mhz - 24)&0x1F;
uint32_t K = Freq % config.setting_frequency_10mhz;
+ if (N>=24) {
+ N=23;
+ K = 9999999;
+ }
uint32_t Carrier = (K<<2) / 625;
uint8_t Freq_Band = N | hbsel | sbsel;
// int count = 0;
@@ -501,6 +413,7 @@ void SI4432_Set_Frequency ( freq_t Freq ) {
// SI4432_Write_Byte( 0x07, 0x0B);
}
+int SI4432_step_delay = 1500;
//extern int setting.repeat;
#ifdef __FAST_SWEEP__
@@ -614,7 +527,6 @@ done:
void SI4432_Fill(int s, int start)
{
- set_SPI_mode(SPI_MODE_SI);
SI4432_Sel = s;
uint16_t sel = SI_nSEL[SI4432_Sel];
#if 0
@@ -652,6 +564,8 @@ void SI4432_Fill(int s, int start)
}
#endif
+#define MINIMUM_WAIT_FOR_RSSI 280
+int SI4432_offset_delay = 300;
pureRSSI_t getSI4432_RSSI_correction(void){
return SI4432_RSSI_correction;
@@ -693,13 +607,13 @@ pureRSSI_t SI4432_RSSI(uint32_t i, int s)
}
if (stepdelay)
my_microsecond_delay(stepdelay);
- // my_microsecond_delay(SI4432_step_delay);
+ // chThdSleepMicroseconds(SI4432_step_delay);
i = setting.repeat;
RSSI_RAW = 0;
do{
RSSI_RAW += DEVICE_TO_PURE_RSSI((deviceRSSI_t)SI4432_Read_Byte(SI4432_REG_RSSI));
if (--i == 0) break;
-// my_microsecond_delay(100);
+ my_microsecond_delay(100);
}while(1);
if (setting.repeat > 1)
@@ -761,23 +675,22 @@ void SI4432_Sub_Init(void)
void SI4432_Init()
{
- return;
#if 1
CS_SI0_LOW; // Drop CS so power can be removed
CS_SI1_LOW; // Drop CS so power can be removed
CS_PE_LOW; // low is the default safe state
- SPI1_CLK_LOW; // low is the default safe state
- SPI1_SDI_LOW; // will be set with any data out
+ SPI2_CLK_LOW; // low is the default safe state
+ SPI2_SDI_LOW; // will be set with any data out
- palClearPad(GPIOA, GPIOA_RF_PWR); // Drop power
+ palClearPad(GPIOB, GPIO_RF_PWR); // Drop power
chThdSleepMilliseconds(10); // Wait
- palSetPad(GPIOA, GPIOA_RF_PWR); // Restore power
+ palSetPad(GPIOB, GPIO_RF_PWR); // Restore power
CS_SI0_HIGH; // And set chip select lines back to inactive
CS_SI1_HIGH;
chThdSleepMilliseconds(10); // Wait
#endif
- SPI1_CLK_LOW;
+ SPI2_CLK_LOW;
//DebugLine("IO set");
SI4432_Sel = SI4432_RX;
SI4432_Sub_Init();
@@ -820,14 +733,14 @@ void PE4302_shiftOut(uint8_t val)
SI4432_log(val);
for (i = 0; i < 8; i++) {
if (val & (1 << (7 - i)))
- SPI1_SDI_HIGH;
+ SPI2_SDI_HIGH;
else
- SPI1_SDI_LOW;
-// my_microsecond_delay(PE4302_DELAY);
- SPI1_CLK_HIGH;
-// my_microsecond_delay(PE4302_DELAY);
- SPI1_CLK_LOW;
-// my_microsecond_delay(PE4302_DELAY);
+ SPI2_SDI_LOW;
+// chThdSleepMicroseconds(PE4302_DELAY);
+ SPI2_CLK_HIGH;
+// chThdSleepMicroseconds(PE4302_DELAY);
+ SPI2_CLK_LOW;
+// chThdSleepMicroseconds(PE4302_DELAY);
}
}
#endif
@@ -837,21 +750,17 @@ bool PE4302_Write_Byte(unsigned char DATA )
{
if (old_attenuation == DATA)
return false;
-// my_microsecond_delay(PE4302_DELAY);
-// SPI1_CLK_LOW;
-// my_microsecond_delay(PE4302_DELAY);
+// chThdSleepMicroseconds(PE4302_DELAY);
+// SPI2_CLK_LOW;
+// chThdSleepMicroseconds(PE4302_DELAY);
// PE4302_shiftOut(DATA);
- set_SPI_mode(SPI_MODE_SI);
- SPI_BR_SET(SI4432_SPI, PE_SPI_SPEED);
-
shiftOut(DATA);
-// my_microsecond_delay(PE4302_DELAY);
+// chThdSleepMicroseconds(PE4302_DELAY);
CS_PE_HIGH;
-// my_microsecond_delay(PE4302_DELAY);
+// chThdSleepMicroseconds(PE4302_DELAY);
CS_PE_LOW;
-// my_microsecond_delay(PE4302_DELAY);
- SPI_BR_SET(SI4432_SPI, SI4432_SPI_SPEED);
+// chThdSleepMicroseconds(PE4302_DELAY);
return true;
}
@@ -920,23 +829,46 @@ float Simulated_SI4432_RSSI(uint32_t i, int s)
#define bitClear(value, bit) ((value) &= ~(1UL << (bit)))
#define bitWrite(value, bit, bitvalue) (bitvalue ? bitSet(value, bit) : bitClear(value, bit))
-#define CS_ADF0_HIGH palSetLine(LINE_LO_SEL)
-#define CS_ADF1_HIGH palSetLine(LINE_LO_SEL)
+#define CS_ADF0_HIGH palSetPad(GPIOA, 9)
+#define CS_ADF1_HIGH palSetPad(GPIOA, 10)
-#define CS_ADF0_LOW palClearLine(LINE_LO_SEL)
-#define CS_ADF1_LOW palClearLine(LINE_LO_SEL)
+#define CS_ADF0_LOW palClearPad(GPIOA, 9)
+#define CS_ADF1_LOW palClearPad(GPIOA, 10)
+
+#define SPI3_CLK_HIGH palSetPad(GPIOA, 1)
+#define SPI3_CLK_LOW palClearPad(GPIOA, 1)
+
+#define SPI3_SDI_HIGH palSetPad(GPIOA, 2)
+#define SPI3_SDI_LOW palClearPad(GPIOA, 2)
+
+
+void ADF_shiftOut(uint8_t val)
+{
+ uint8_t i;
+ for (i = 0; i < 8; i++) {
+ if (val & (1 << (7 - i)))
+ SPI3_SDI_HIGH;
+ else
+ SPI3_SDI_LOW;
+// chThdSleepMicroseconds(10);
+ SPI3_CLK_HIGH;
+// chThdSleepMicroseconds(10);
+ SPI3_CLK_LOW;
+// chThdSleepMicroseconds(10);
+ }
+}
+
+//unsigned long registers[6] = {0x4580A8, 0x80080C9, 0x4E42, 0x4B3, 0xBC803C, 0x580005} ;
+//unsigned long registers[6] = {0x4C82C8, 0x80083E9, 0x6E42, 0x8004B3, 0x8C81FC, 0x580005} ;
+
+//uint32_t registers[6] = {0x320000, 0x8008011, 0x4E42, 0x4B3,0x8C803C , 0x580005} ; //25 MHz ref
-//uint32_t t_R[6] = {0x320000, 0x8008011, 0x4E42, 0x4B3,0x8C803C , 0x580005} ; //25 MHz ref
-#ifdef TINYSA4_PROTO
-uint32_t registers[6] = {0xC80000, 0x8008011, 0x1800C642, 0x48963,0xA5003C , 0x580005} ; //10 MHz ref
-#else
uint32_t registers[6] = {0xA00000, 0x8000011, 0x4E42, 0x4B3,0xDC003C , 0x580005} ; //10 MHz ref
-#endif
+
int debug = 0;
-ioline_t ADF4351_LE[2] = { LINE_LO_SEL, LINE_LO_SEL};
-//int ADF4351_Mux = 7;
+int ADF4351_LE[2] = { 9, 10};
+int ADF4351_Mux = 7;
-int ADF4351_frequency_changed = false;
//#define DEBUG(X) // Serial.print( X )
//#define DEBUGLN(X) Serial.println( X )
@@ -945,58 +877,46 @@ int ADF4351_frequency_changed = false;
#define DEBUG(X)
#define DEBUGLN(X)
-#ifdef TINYSA4_PROTO
-#define XTAL 29999960
-#else
-#define XTAL 26000000
+
+double RFout, //Output freq in MHz
+#if 0 //Black modules
+ PFDRFout[6] = {25.0,25.0,25.0,10.0,10.0,10.0}, //Reference freq in MHz
+ Chrystal[6] = {25.0,25.0,25.0,10.0,10.0,10.0},
+#else // Green modules
+ PFDRFout[6] = {10.0,10.0,10.0,10.0,10.0,10.0}, //Reference freq in MHz
+ Chrystal[6] = {10.0,10.0,10.0,10.0,10.0,10.0},
#endif
-//double RFout; //Output freq in MHz
-uint64_t PFDRFout[6] = {XTAL,XTAL,XTAL,10000000,10000000,10000000}; //Reference freq in MHz
-//uint64_t Chrystal[6] = {XTAL,XTAL,XTAL,10000000,10000000,10000000};
-//double FRACF; // Temp
-volatile int64_t
+ OutputChannelSpacing = 0.010, // = 0.01
+ FRACF; // Temp
+
+unsigned int long RFint, // Output freq/10Hz
INTA, // Temp
- ADF4350_modulo = 60, // Linked to spur table!!!!!
- MOD,
- target_freq,
+ RFcalc, //UI
+ MOD, //Temp
FRAC; //Temp
uint8_t OutputDivider; // Temp
uint8_t lock=2; //Not used
-static int old_R = 0;
// Lock = A4
-void ADF4351_Setup(void)
+void ADF4351_Setup()
{
// palSetPadMode(GPIOA, 1, PAL_MODE_OUTPUT_PUSHPULL );
// palSetPadMode(GPIOA, 2, PAL_MODE_OUTPUT_PUSHPULL );
-// SPI3_CLK_HIGH;
-// SPI3_SDI_HIGH;
+ SPI3_CLK_HIGH;
+ SPI3_SDI_HIGH;
CS_ADF0_HIGH;
-// CS_ADF1_HIGH;
-
- // bitSet (registers[2], 17); // R set to 8
+ CS_ADF1_HIGH;
+// bitSet (registers[2], 17); // R set to 8
// bitClear (registers[2], 14); // R set to 8
// while(1) {
//
-
- ADF4351_R_counter(1);
-
- ADF4351_CP(0);
-
- ADF4351_fastlock(1); // Fastlock enabled
- ADF4351_csr(1); //Cycle slip enabled
-
- ADF4351_set_frequency(0,200000000);
-
- ADF4351_mux(2); // No led
-// ADF4351_mux(6); // Show lock on led
-
-// ADF4351_set_frequency(1,150000000,0);
+ ADF4351_set_frequency(0,100000000,0);
+ ADF4351_set_frequency(1,150000000,0);
// ADF4351_Set(0);
// ADF4351_Set(1);
// chThdSleepMilliseconds(1000);
@@ -1014,70 +934,38 @@ void ADF4351_Setup(void)
void ADF4351_WriteRegister32(int channel, const uint32_t value)
{
- registers[value & 0x07] = value;
- for (int i = 3; i >= 0; i--) shiftOut((value >> (8 * i)) & 0xFF);
- palSetLine(ADF4351_LE[channel]);
- my_microsecond_delay(1); // Must
- palClearLine(ADF4351_LE[channel]);
+ palClearPad(GPIOA, ADF4351_LE[channel]);
+// chThdSleepMicroseconds(10);
+ for (int i = 3; i >= 0; i--) ADF_shiftOut((value >> (8 * i)) & 0xFF);
+// chThdSleepMicroseconds(10);
+ palSetPad(GPIOA, ADF4351_LE[channel]);
+// chThdSleepMicroseconds(10);
+ palClearPad(GPIOA, ADF4351_LE[channel]);
+// chThdSleepMicroseconds(10);
}
-void ADF4351_Set(int channel)
-{
- set_SPI_mode(SPI_MODE_SI);
- SPI_BR_SET(SI4432_SPI, ADF_SPI_SPEED);
-// my_microsecond_delay(1);
- palClearLine(ADF4351_LE[channel]);
-// my_microsecond_delay(1);
-
- for (int i = 5; i >= 0; i--) {
- ADF4351_WriteRegister32(channel, registers[i]);
- }
- SPI_BR_SET(SI4432_SPI, SI4432_SPI_SPEED);
-}
-
-#if 0
-void ADF4351_disable_output(void)
+void ADF4351_disable_output()
{
- bitClear (registers[4], 5); // main output
+ bitClear (registers[4], 5); // digital lock
ADF4351_Set(0);
}
-void ADF4351_enable_output(void)
+void ADF4351_enable_output()
{
- bitSet (registers[4], 5); // main output
+ bitSet (registers[4], 5); // digital lock
ADF4351_Set(0);
}
-#endif
-
-static freq_t prev_actual_freq = 0;
-
-void ADF4351_force_refresh(void) {
- prev_actual_freq = 0;
+void ADF4351_Set(int channel)
+{ for (int i = 5; i >= 0; i--) {
+ ADF4351_WriteRegister32(channel, registers[i]);
+// if (debug) Serial.println(registers[i],HEX);
}
-
-void ADF4351_modulo(int m)
-{
- ADF4350_modulo = m;
-// ADF4351_set_frequency(0, (uint64_t)prev_actual_freq);
}
-uint64_t ADF4351_set_frequency(int channel, uint64_t freq) // freq / 10Hz
+void ADF4351_set_frequency(int channel, unsigned long freq, int drive) // freq / 10Hz
{
-// freq -= 71000;
-// SI4463_set_gpio(3,GPIO_HIGH);
-
-// uint32_t offs = ((freq / 1000)* ( 0) )/ 1000;
- uint32_t offs = 0;
- uint64_t actual_freq = ADF4351_prepare_frequency(channel,freq + offs);
-// SI4463_set_gpio(3,GPIO_LOW);
- if (actual_freq != prev_actual_freq) {
-//START_PROFILE;
- ADF4351_frequency_changed = true;
- ADF4351_Set(channel);
- prev_actual_freq = actual_freq;
- }
-//STOP_PROFILE;
- return actual_freq;
+ ADF4351_prep_frequency(channel,freq, drive);
+ ADF4351_Set(channel);
}
void ADF4351_spur_mode(int S)
@@ -1091,15 +979,11 @@ void ADF4351_spur_mode(int S)
bitSet (registers[2], 30); // R set to 8
else
bitClear (registers[2], 30); // R set to 8
- ADF4351_Set(0);
}
void ADF4351_R_counter(int R)
{
- if (R == old_R)
- return;
- old_R = R;
- int dbl = false;
+ int dbl = false;
if (R < 0) {
dbl = true;
R = -R;
@@ -1112,56 +996,29 @@ void ADF4351_R_counter(int R)
bitClear (registers[2], 25); // Reference doubler
}
for (int channel=0; channel < 6; channel++) {
- PFDRFout[channel] = (config.setting_frequency_30mhz * (dbl?2:1)) / R;
+ PFDRFout[channel] = Chrystal[channel] * (dbl?2:1) / R;
}
- clear_frequency_cache(); // When R changes the possible frequencies will change
registers[2] &= ~ (((unsigned long)0x3FF) << 14);
registers[2] |= (((unsigned long)R) << 14);
- ADF4351_Set(0);
-}
-
-void ADF4351_mux(int R)
-{
- registers[2] &= ~ (((unsigned long)0x7) << 26);
- registers[2] |= (((unsigned long)R & (unsigned long)0x07) << 26);
- ADF4351_Set(0);
-}
-
-void ADF4351_csr(int c)
-{
- registers[3] &= ~ (((unsigned long)0x1) << 18);
- registers[3] |= (((unsigned long)c & (unsigned long)0x01) << 18);
- ADF4351_Set(0);
-}
-
-void ADF4351_fastlock(int c)
-{
- registers[3] &= ~ (((unsigned long)0x3) << 15);
- registers[3] |= (((unsigned long)c & (unsigned long)0x03) << 15);
- ADF4351_Set(0);
}
void ADF4351_CP(int p)
{
registers[2] &= ~ (((unsigned long)0xF) << 9);
registers[2] |= (((unsigned long)p) << 9);
- ADF4351_Set(0);
}
-void ADF4351_drive(int p)
+void ADF4351_level(int p)
{
registers[4] &= ~ (((unsigned long)0x3) << 3);
registers[4] |= (((unsigned long)p) << 3);
- ADF4351_Set(0);
}
-void ADF4351_aux_drive(int p)
+void ADF4351_channel_spacing(int spacing)
{
- registers[4] &= ~ (((unsigned long)0x3) << 6);
- registers[4] |= (((unsigned long)p) << 6);
- ADF4351_Set(0);
+ OutputChannelSpacing = 0.001 * spacing;
}
-#if 0
+
static uint32_t gcd(uint32_t x, uint32_t y)
{
uint32_t z;
@@ -1172,1482 +1029,157 @@ static uint32_t gcd(uint32_t x, uint32_t y)
}
return x;
}
-#endif
-
-#if 0
-#endif
-uint64_t ADF4351_prepare_frequency(int channel, uint64_t freq) // freq / 10Hz
+void ADF4351_prep_frequency(int channel, unsigned long freq, int drive) // freq / 10Hz
{
- target_freq = freq;
- if (freq >= 2200000000) {
+ (void)drive;
+// if (channel == 0)
+ RFout=freq/1000000.0; // To MHz
+// else
+ // RFout=freq/1000002.764; // To MHz
+
+ if (RFout >= 2200) {
OutputDivider = 1;
bitWrite (registers[4], 22, 0);
bitWrite (registers[4], 21, 0);
bitWrite (registers[4], 20, 0);
- } else if (freq >= 1100000000) {
+ } else if (RFout >= 1100) {
OutputDivider = 2;
bitWrite (registers[4], 22, 0);
bitWrite (registers[4], 21, 0);
bitWrite (registers[4], 20, 1);
- } else if (freq >= 550000000) {
+ } else if (RFout >= 550) {
OutputDivider = 4;
bitWrite (registers[4], 22, 0);
bitWrite (registers[4], 21, 1);
bitWrite (registers[4], 20, 0);
- } else if (freq >= 275000000) {
+ } else if (RFout >= 275) {
OutputDivider = 8;
bitWrite (registers[4], 22, 0);
bitWrite (registers[4], 21, 1);
bitWrite (registers[4], 20, 1);
- } else { // > 137500000
+ } else if (RFout >= 137.5) {
OutputDivider = 16;
bitWrite (registers[4], 22, 1);
bitWrite (registers[4], 21, 0);
bitWrite (registers[4], 20, 0);
+ } else if (RFout >= 68.75) {
+ OutputDivider = 32;
+ bitWrite (registers[4], 22, 1);
+ bitWrite (registers[4], 21, 0);
+ bitWrite (registers[4], 20, 1);
+ } else {
+ OutputDivider = 64;
+ bitWrite (registers[4], 22, 1);
+ bitWrite (registers[4], 21, 1);
+ bitWrite (registers[4], 20, 0);
}
- volatile uint64_t PFDR = PFDRFout[channel];
- INTA = (((uint64_t)freq) * OutputDivider) / PFDR;
- MOD = ADF4350_modulo;
- uint64_t f_int = INTA *(uint64_t) MOD;
- uint64_t f_target = ((((uint64_t)freq) * OutputDivider) * (uint64_t) MOD) / PFDR;
- FRAC = f_target - f_int;
- if (FRAC >= MOD) {
- FRAC -= MOD;
- INTA++;
- }
-#if 0
- while (FRAC > 4095 || MOD > 4095) {
- FRAC = FRAC >> 1;
- MOD = MOD >> 1;
+ INTA = (RFout * OutputDivider) / PFDRFout[channel];
+ MOD = (PFDRFout[channel] / OutputChannelSpacing) + 0.01;
+// MOD = 3125;
+ FRACF = (((RFout * OutputDivider) / PFDRFout[channel]) - INTA) * MOD;
+ FRAC = round(FRACF);
+
+ while (FRAC > 4095 || MOD > 4095) {
+ FRAC = FRAC >> 1;
+ MOD = MOD >> 1;
// Serial.println( "MOD/FRAC reduced");
- }
-#endif
-#if 0
- uint32_t reduce = gcd(MOD, FRAC);
- if (reduce>1) {
- FRAC /= reduce;
- MOD /= reduce;
- if (MOD == 1)
- MOD=2;
- }
-#endif
- uint64_t actual_freq = (PFDR *(INTA * MOD +FRAC))/OutputDivider / MOD;
-#if 0
- volatile int max_delta = PFDRFout[channel]/OutputDivider/MOD/100;
- if (actual_freq < freq - max_delta || actual_freq > freq + max_delta ){
- while(1)
- my_microsecond_delay(10);
- }
- max_delta = freq - actual_freq;
- if (max_delta > 200000 || max_delta < -200000 || freq == 0) {
- while(1)
- my_microsecond_delay(10);
- }
-#endif
- if (FRAC >= MOD ){
- while(1)
- my_microsecond_delay(10);
- }
+ }
+ int32_t k = gcd(FRAC, MOD);
+ if (k > 1) {
+ FRAC /= k;
+ MOD /= k;
+// Serial.print( "MOD/FRAC gcd reduced");
+ }
+// while (denom >= (1<<20)) {
+// num >>= 1;
+// denom >>= 1;
+// }
+
+
+// if (INTA <= 75) Serial.println( "INTA <= 75");
+// if (FRAC > 4095) Serial.println( "FRAC > 4095");
+// if (MOD > 4095) Serial.println( "MOD > 4095");
+
+
+// if (FRAC > 4095) Serial.println( "FRAC > 4095");
+// if (MOD > 4095) Serial.println( "MOD > 4095");
+// if (INTA > 4095) Serial.println( "INT > 4095");
+
+ if (debug) {
+ DEBUG(" ODIV=");
+ DEBUG(OutputDivider);
+ DEBUG(" INT=");
+ DEBUG(INTA);
+ DEBUG(" FRAC=");
+ DEBUG(FRAC);
+ DEBUG(" MOD=");
+ DEBUG(MOD);
+ DEBUG( " CalF=");
+// DEBUGFLN(PFDRFout[channel] *(INTA + ((double)FRAC)/MOD)/OutputDivider,6);
+
+// DEBUG(" FRACF=");
+// DEBUGF(FRACF,6);
+ }
registers[0] = 0;
registers[0] = INTA << 15; // OK
- registers[0] = registers[0] + (FRAC << 3);
+ FRAC = FRAC << 3;
+ registers[0] = registers[0] + FRAC;
if (MOD == 1) MOD = 2;
registers[1] = 0;
registers[1] = MOD << 3;
registers[1] = registers[1] + 1 ; // restore address "001"
bitSet (registers[1], 27); // Prescaler at 8/9
- return actual_freq;
-}
-
-#endif
-
-void ADF4351_enable(int s)
-{
- if (s)
- bitClear(registers[4], 11); // Inverse logic!!!!!
- else
- bitSet(registers[4], 11);
- ADF4351_Set(0);
-}
-
-void ADF4351_enable_aux_out(int s)
-{
- if (s)
- bitSet(registers[4], 8);
- else
- bitClear(registers[4], 8);
- ADF4351_Set(0);
-}
-
-void ADF4351_enable_out(int s)
-{
- if (s) {
- bitClear(registers[2], 11); // Disable VCO power down
- bitClear(registers[2], 5); // Disable power down
- bitSet(registers[4], 5); // Enable output
- } else {
- bitClear(registers[4], 5); // Disable output
- bitSet(registers[2], 5); // Enable power down
- bitSet(registers[2], 11); // Enable VCO power down
- }
- ADF4351_Set(0);
-}
-
-
-// ------------------------------ SI4463 -------------------------------------
-
-
-int SI4463_frequency_changed = false;
-int SI4463_offset_changed = false;
-int SI4463_offset_value = 0;
-
-static int SI4463_band = -1;
-static int64_t SI4463_outdiv = -1;
-//static freq_t SI4463_prev_freq = 0;
-//static float SI4463_step_size = 100; // Will be recalculated once used
-static uint8_t SI4463_channel = 0;
-static uint8_t SI4463_in_tx_mode = false;
-int SI4463_R = 5;
-static int SI4463_output_level = 0x20;
-
-static si446x_state_t SI4463_get_state(void);
-static void SI4463_set_state(si446x_state_t);
-
-
-#define MIN_DELAY 2
-#define my_deleted_delay(T)
-
-#include
-
-#define SI4463_READ_CTS (palReadLine(LINE_RX_CTS))
-
-static int SI4463_wait_for_cts(void)
-{
-// set_SPI_mode(SPI_MODE_SI);
- while (!SI4463_READ_CTS) {
-// chThdSleepMicroseconds(100);
- my_microsecond_delay(1);
- }
- return 1;
-}
-
-#if 0 // not used
-static void SI4463_write_byte(uint8_t ADR, uint8_t DATA)
-{
- set_SPI_mode(SPI_MODE_SI);
- SI_CS_LOW;
- ADR |= 0x80 ; // RW = 1
- shiftOut( ADR );
- shiftOut( DATA );
- SI_CS_HIGH;
-}
-
-static void SI4463_write_buffer(uint8_t ADR, uint8_t *DATA, int len)
-{
- set_SPI_mode(SPI_MODE_SI);
- SI_CS_LOW;
- ADR |= 0x80 ; // RW = 1
- shiftOut( ADR );
- while (len-- > 0)
- shiftOut( *(DATA++) );
- SI_CS_HIGH;
-}
-#endif
-
-static uint8_t SI4463_read_byte( uint8_t ADR )
-{
- uint8_t DATA ;
- set_SPI_mode(SPI_MODE_SI);
- SI_CS_LOW;
- shiftOut( ADR );
- DATA = shiftIn();
- SI_CS_HIGH;
- return DATA ;
-}
-
-static uint8_t SI4463_get_response(void* buff, uint8_t len)
-{
- uint8_t cts = 0;
-// set_SPI_mode(SPI_MODE_SI);
- cts = SI4463_READ_CTS;
- if (!cts) {
- return false;
- }
-// __disable_irq();
- SI_CS_LOW;
- shiftOut( SI446X_CMD_READ_CMD_BUFF );
- cts = (shiftIn() == 0xFF);
- if (cts)
- {
- // Get response data
- for(uint8_t i=0;i>8),
- len,
- (uint8_t)prop
- };
-
- // Copy values into data, starting at index 4
- memcpy(data + 4, values, len);
-
- SI4463_do_api(data, len + 4, NULL, 0);
-}
-#endif
-
-#include "SI446x_cmd.h"
-
-#if 0
-#include "SI4463_radio_config.h"
-static const uint8_t SI4463_config[] = RADIO_CONFIGURATION_DATA_ARRAY;
-#endif
+ bitClear (registers[2], 8); // INT mode
+ bitSet (registers[2], 13); // Double buffered
-#ifdef __SI4468__
-#include "radio_config_Si4468_undef.h"
-#undef RADIO_CONFIGURATION_DATA_ARRAY
-#include "radio_config_Si4468_default.h"
+ bitSet (registers[2], 28); // Digital lock == "110" sur b28 b27 b26
+ bitSet (registers[2], 27); // digital lock
+ bitClear (registers[2], 26); // digital lock
-#define GLOBAL_GPIO_PIN_CFG 0x13, 0x07, 0x08, 0x00, 0x00, 0x00, 0x00, 0x00
-#define GLOBAL_CLK_CFG 0x11, 0x00, 0x01, 0x01, 0x00
-
-//#undef RF_MODEM_RAW_CONTROL_10 // Override RSSI averaging
-//#define RF_MODEM_RAW_CONTROL_10 0x11, 0x20, 0x0A, 0x45, 0x03, 0x00, 0x00, 0x01, 0x00, 0xFF, 0x06, 0x18, 0x10, 0x40
-
-//#undef RF_MODEM_AGC_CONTROL_1
-//#define RF_MODEM_AGC_CONTROL_1 0x11, 0x20, 0x01, 0x35, 0x92 // Override AGC gain increase
-#undef RF_MODEM_AGC_CONTROL_1
-#define RF_MODEM_AGC_CONTROL_1 0x11, 0x20, 0x01, 0x35, 0xE0 + 0x10 + 0x08 // slow AGC
-//#undef RF_MODEM_RSSI_JUMP_THRESH_4
-//#define RF_MODEM_RSSI_JUMP_THRESH_4 0x11, 0x20, 0x04, 0x4B, 0x06, 0x09, 0x10, 0x45 // Increase RSSI reported value with 2.5dB
-
-#undef RF_GPIO_PIN_CFG
-#define RF_GPIO_PIN_CFG GLOBAL_GPIO_PIN_CFG
-#undef RF_GLOBAL_CLK_CFG_1
-#define RF_GLOBAL_CLK_CFG_1 GLOBAL_CLK_CFG
-
-// Remember to change RF_MODEM_AFC_LIMITER_1_3_1 !!!!!!!!!
-
-static const uint8_t SI4468_config[] = RADIO_CONFIGURATION_DATA_ARRAY;
-#endif
-
-// Set new state
-static void SI4463_set_state(si446x_state_t newState)
-{
- uint8_t data[] = {
- SI446X_CMD_CHANGE_STATE,
- newState
- };
- SI4463_do_api(data, sizeof(data), NULL, 0);
+ //bitSet (registers[4], 10); // Mute till lock
+// bitSet (registers[3], 23); // Fast lock
+ #endif
+// bitSet (registers[4], 10); // Mute till lock
+// ADF4351_Set(channel);
}
-static uint8_t gpio_state[4] = { 7,8,0,0 };
-
-void SI4463_refresh_gpio(void)
-{
-#ifndef TINYSA4_PROTO // Force clock to max frequency for ADF
- uint8_t data[] =
- {
- 0x11, 0x00, 0x01, 0x01, 0x40 // GLOBAL_CLK_CFG Enable divided clock
- };
- SI4463_do_api(data, sizeof(data), NULL, 0);
-#endif
- uint8_t data2[] =
- {
- 0x13, gpio_state[0], gpio_state[1], gpio_state[2], gpio_state[3], 0, 0, 0
- };
- SI4463_do_api(data2, sizeof(data2), NULL, 0);
-}
-
-void SI4463_set_gpio(int i, int s)
-{
- gpio_state[i] = s;
-#if 0 // debug gpio
- gpio_state[2] = 3;
- gpio_state[3] = 2;
-#endif
- SI4463_refresh_gpio();
-}
-#if 0
-static void SI4463_clear_FIFO(void)
-{
- // 'static const' saves 20 bytes of flash here, but uses 2 bytes of RAM
- static const uint8_t clearFifo[] = {
- SI446X_CMD_FIFO_INFO,
- SI446X_FIFO_CLEAR_RX | SI446X_FIFO_CLEAR_TX
- };
- SI4463_do_api((uint8_t*)clearFifo, sizeof(clearFifo), NULL, 0);
-}
-#endif
-void SI4463_set_output_level(int t)
-{
- SI4463_output_level = t;
- if (SI4463_in_tx_mode)
- SI4463_start_tx(0); // Refresh output level
-}
-void SI4463_start_tx(uint8_t CHANNEL)
-{
-// volatile si446x_state_t s;
-#if 0
- s = SI4463_get_state();
- if (s == SI446X_STATE_RX){
- SI4463_set_state(SI446X_STATE_READY);
- my_microsecond_delay(200);
- s = SI4463_get_state();
- if (s != SI446X_STATE_READY){
- my_microsecond_delay(1000);
- }
- }
-#endif
-#if 1
- {
- uint8_t data[] =
- {
- 0x11, 0x20, 0x01, 0x00,
- 0x00, // CW mode
- };
- SI4463_do_api(data, sizeof(data), NULL, 0);
- }
-#endif
-#if 1
- {
- uint8_t data[] =
- {
- 0x11, 0x22, 0x04, 0x00, // PA_MODE
- 0x08, // Coarse PA mode and class E PA
- (uint8_t)SI4463_output_level, // Level
- 0x00, // Duty
- 0x00 // Ramp
- };
- SI4463_do_api(data, sizeof(data), NULL, 0);
- }
#endif
-// retry:
- {
- uint8_t data[] =
- {
- SI446X_CMD_ID_START_TX,
- CHANNEL,
- 0, // Stay in TX state
- 0, // TX len
- 0, // TX len
- 0,// TX delay
- 0// Num repeat
- };
- SI4463_do_api(data, sizeof(data), NULL, 0);
- }
- SI4463_in_tx_mode = true;
- my_microsecond_delay(1000);
-#if 0
- s = SI4463_get_state();
- if (s != SI446X_STATE_TX){
- my_microsecond_delay(1000);
- goto retry;
- }
-#endif
-
-}
-
-
-void SI4463_start_rx(uint8_t CHANNEL)
-{
- volatile si446x_state_t s = SI4463_get_state();
- if (s == SI446X_STATE_TX){
- SI4463_set_state(SI446X_STATE_READY);
- }
- SI4463_refresh_gpio();
-#if 0
- {
- uint8_t data[] =
- {
- 0x11, 0x20, 0x01, 0x00,
- 0x0A, // Restore 2FSK mode
- };
- SI4463_do_api(data, sizeof(data), NULL, 0);
- }
-#endif
- uint8_t data[] = {
- SI446X_CMD_ID_START_RX,
- CHANNEL,
- 0,
- 0,
- 0,
- 0,// 8,
- 0,// SI446X_CMD_START_RX_ARG_NEXT_STATE2_RXVALID_STATE_ENUM_RX,
- 0, //SI446X_CMD_START_RX_ARG_NEXT_STATE3_RXINVALID_STATE_ENUM_RX
- };
-//retry:
- SI4463_do_api(data, sizeof(data), NULL, 0);
-
-#if 0
- si446x_state_t s = SI4463_get_state();
- if (s != SI446X_STATE_RX) {
- my_microsecond_delay(1000);
- goto retry;
- }
-#endif
- SI4463_in_tx_mode = false;
-}
-
-
-
-void SI4463_short_start_rx(void)
-{
- uint8_t data[] = {
- SI446X_CMD_ID_START_RX,
- };
- SI4463_do_api(data, sizeof(data), NULL, 0);
- SI4463_in_tx_mode = false;
-}
-
-void SI4463_clear_int_status(void)
-{
- uint8_t data[9] = {
- SI446X_CMD_ID_GET_INT_STATUS
- };
- SI4463_do_api(data, 1, data, SI446X_CMD_REPLY_COUNT_GET_INT_STATUS);
-
-}
-
-void set_calibration_freq(int ref)
-{
-#ifndef TINYSA4_PROTO
- ref = 0; // <--------------------- DISABLED FOR PROTOTYPE!!!!!!!!!!!!!!!!!!!!!!!!!
-#endif
-
- if (ref >= 0) {
- SI4463_set_gpio(0, 7); // GPIO 0 dic clock out
-
- uint8_t data2[5] = {
- 0x11, 0x00, 0x01, 0x01, 0x40 // GLOBAL_CLK_CFG Clock config
- };
- data2[4] |= ref<<3;
- SI4463_do_api(data2, 5, NULL, 0);
- } else {
- SI4463_set_gpio(0, 1); // stop clock out
- }
-}
-
-si446x_info_t SI4463_info;
-
-void Si446x_getInfo(si446x_info_t* info)
-{
- uint8_t data[8] = {
- SI446X_CMD_PART_INFO
- };
- SI4463_do_api(data, 1, data, 8);
-
- info->chipRev = data[0];
- info->part = (data[1]<<8) | data[2];
- info->partBuild = data[3];
- info->id = (data[4]<<8) | data[5];
- info->customer = data[6];
- info->romId = data[7];
-
-
- data[0] = SI446X_CMD_FUNC_INFO;
- SI4463_do_api(data, 1, data, 6);
-
- info->revExternal = data[0];
- info->revBranch = data[1];
- info->revInternal = data[2];
- info->patch = (data[3]<<8) | data[4];
- info->func = data[5];
-}
-#ifdef notused
-static uint8_t SI4463_get_device_status(void)
-{
- uint8_t data[2] =
- {
- SI446X_CMD_ID_REQUEST_DEVICE_STATE, 0
- };
- SI4463_do_api(data, 1, data, SI446X_CMD_REPLY_COUNT_REQUEST_DEVICE_STATE);
- return(data[0]);
-}
-#endif
-
-
-// Read a fast response register
-uint8_t getFRR(uint8_t reg)
-{
- set_SPI_mode(SPI_MODE_SI);
- return SI4463_read_byte(reg);
-}
-
-// Get current radio state
-static si446x_state_t SI4463_get_state(void)
-{
-#if 0
-#if 0
- uint8_t data[2] = {
- SI446X_CMD_REQUEST_DEVICE_STATE
- };
- SI4463_do_api(data, 1, data, 2);
- uint8_t state = data[0] & 0x0F;
-#endif
- uint8_t state = SI4463_get_device_status();
-#else
-again:
- SI4463_wait_for_cts();
- uint8_t state = getFRR(SI446X_CMD_READ_FRR_B);
-#endif
- if (state == 255) {
- my_microsecond_delay(100);
- goto again;
- }
- if(state == SI446X_STATE_TX_TUNE)
- state = SI446X_STATE_TX;
- else if(state == SI446X_STATE_RX_TUNE)
- state = SI446X_STATE_RX;
- else if(state == SI446X_STATE_READY2)
- state = SI446X_STATE_READY;
- else
- state = state;
- return (si446x_state_t)state;
-}
-
-
-void set_RSSI_comp(void)
-{
- // Set properties: RF_MODEM_RSSI_COMP_1
- // Number of properties: 1
- // Group ID: 0x20
- // Start ID: 0x4E
- // Default values: 0x40,
- // Descriptions:
- // MODEM_RSSI_JUMP_THRESH - Configures the RSSI Jump Detection threshold.
- // MODEM_RSSI_CONTROL - Control of the averaging modes and latching time for reporting RSSI value(s).
- // MODEM_RSSI_CONTROL2 - RSSI Jump Detection control.
- // MODEM_RSSI_COMP - RSSI compensation value.
- //
- // #define RF_MODEM_RSSI_COMP_1 0x11, 0x20, 0x01, 0x4E, 0x40
-
- uint8_t data[5] = {
- 0x11,
- 0x20,
- 0x01,
- 0x4E,
- 0x40
- };
- SI4463_do_api(data, sizeof(data), NULL, 0);
-
-}
-
-int SI4463_offset_active = false;
-
-void si_set_offset(int16_t offset)
-{
- // Set properties: MODEM_FREQ_OFFSET
- // Number of properties: 2
- // Group ID: 0x20
- // Start ID: 0x0d
- // Default values: 0x00, 0x00
- // Descriptions:
- // MODEM_FREQ_OFFSET1 - High byte of the offset
- // MODEM_FREQ_OFFSET2 - Low byte of the offset
- //
- // #define RF_MODEM_RSSI_COMP_1 0x11, 0x20, 0x01, 0x4E, 0x40
- SI4463_offset_value = offset;
- uint8_t data[] = {
- 0x11,
- 0x20,
- 0x02,
- 0x0d,
- (uint8_t) ((offset>>8) & 0xff),
- (uint8_t) ((offset) & 0xff)
- };
- SI4463_do_api(data, sizeof(data), NULL, 0);
- SI4463_offset_changed = true;
- SI4463_offset_active = (offset != 0);
-}
-
-void si_fm_offset(int16_t offset)
-{
- // Set properties: MODEM_FREQ_OFFSET
- // Number of properties: 2
- // Group ID: 0x20
- // Start ID: 0x0d
- // Default values: 0x00, 0x00
- // Descriptions:
- // MODEM_FREQ_OFFSET1 - High byte of the offset
- // MODEM_FREQ_OFFSET2 - Low byte of the offset
- //
- // #define RF_MODEM_RSSI_COMP_1 0x11, 0x20, 0x01, 0x4E, 0x40
- offset = SI4463_offset_value + offset;
- uint8_t data[] = {
- 0x11,
- 0x20,
- 0x02,
- 0x0d,
- (uint8_t) ((offset>>8) & 0xff),
- (uint8_t) ((offset) & 0xff)
- };
- SI4463_do_api(data, sizeof(data), NULL, 0);
- SI4463_offset_changed = true;
- SI4463_offset_active = (offset != 0);
-}
-
-
-
-#ifdef __FAST_SWEEP__
-extern deviceRSSI_t age[POINTS_COUNT];
-static int buf_index = 0;
-static bool buf_read = false;
-
-void SI446x_Fill(int s, int start)
-{
- (void)s;
-#if 0
- set_SPI_mode(SPI_MODE_SI);
- SI4432_Sel = s;
- uint16_t sel = SI_nSEL[SI4432_Sel];
-#endif
-
- uint32_t t = setting.additional_step_delay_us;
- systime_t measure = chVTGetSystemTimeX();
- __disable_irq();
-
-#if 1
- int i = start;
- uint8_t data[3];
- do {
-again:
- data[0] = SI446X_CMD_GET_MODEM_STATUS;
- data[1] = 0xFF;
- SI4463_do_api(data, 1, data, 3); // TODO no clear of interrups
- if (data[2] == 0) goto again;
- if (data[2] == 255) goto again;
- age[i]=(char)data[2];
- if (++i >= sweep_points) break;
- if (t)
- my_microsecond_delay(t);
- } while(1);
-#else
- shiftInBuf(sel, SI4432_REG_RSSI, &age[start], sweep_points - start, t);
-#endif
- __enable_irq();
-
- setting.measure_sweep_time_us = (chVTGetSystemTimeX() - measure)*100;
- buf_index = start; // Is used to skip 1st entry during level triggering
- buf_read = true;
-}
-#endif
-
-
-
-int16_t Si446x_RSSI(void)
-{
-#ifdef __FAST_SWEEP__
- if (buf_read) {
- if (buf_index == sweep_points-1)
- buf_read = false;
- return DEVICE_TO_PURE_RSSI(age[buf_index++]);
- }
-#endif
-
- int i = setting.repeat;
- int32_t RSSI_RAW = 0;
- do{
- // if (MODE_INPUT(setting.mode) && RSSI_R
- uint8_t data[3] = {
- SI446X_CMD_GET_MODEM_STATUS,
- 0xFF
- };
- if (SI4432_step_delay && (ADF4351_frequency_changed || SI4463_frequency_changed)) {
- my_microsecond_delay(SI4432_step_delay * ((setting.R == 0 && old_R > 5 ) ? 8 : 1));
- ADF4351_frequency_changed = false;
- SI4463_frequency_changed = false;
- } else if (SI4432_offset_delay && SI4463_offset_changed) {
- my_microsecond_delay(SI4432_offset_delay);
- ADF4351_frequency_changed = false;
- SI4463_offset_changed = false;
- }
-#define SAMPLE_COUNT 1
- int j = SAMPLE_COUNT; //setting.repeat;
- int RSSI_RAW_ARRAY[3];
- do{
- again:
- __disable_irq();
- data[0] = SI446X_CMD_GET_MODEM_STATUS;
- data[1] = 0xFF;
- SI4463_do_api(data, 2, data, 3); // TODO no clear of interrupts
- __enable_irq();
-
- if (data[2] == 255) {
- my_microsecond_delay(10);
- goto again;
- }
-#if 0
- if (data[2] == 0) {
-// my_microsecond_delay(10);
- goto again;
- }
-#endif
- RSSI_RAW_ARRAY[--j] = data[2];
- if (j == 0) break;
-// my_microsecond_delay(20);
- }while(1);
-#if SAMPLE_COUNT == 3
- int t;
- if (RSSI_RAW_ARRAY[0] > RSSI_RAW_ARRAY[1]) {
- t = RSSI_RAW_ARRAY[1];
- RSSI_RAW_ARRAY[1] = RSSI_RAW_ARRAY[0];
- RSSI_RAW_ARRAY[0] = t;
- }
- if (RSSI_RAW_ARRAY[1] > RSSI_RAW_ARRAY[2]) {
- t = RSSI_RAW_ARRAY[2];
- RSSI_RAW_ARRAY[2] = RSSI_RAW_ARRAY[1];
- RSSI_RAW_ARRAY[1] = t;
- }
- if (RSSI_RAW_ARRAY[0] > RSSI_RAW_ARRAY[1]) {
- t = RSSI_RAW_ARRAY[1];
- RSSI_RAW_ARRAY[1] = RSSI_RAW_ARRAY[0];
- RSSI_RAW_ARRAY[0] = t;
- }
-
- RSSI_RAW += DEVICE_TO_PURE_RSSI(RSSI_RAW_ARRAY[1]);
-#else
- RSSI_RAW += DEVICE_TO_PURE_RSSI(RSSI_RAW_ARRAY[0]);
-#endif
- if (--i <= 0) break;
-// my_microsecond_delay(100);
- }while(1);
-
- if (setting.repeat > 1)
- RSSI_RAW = RSSI_RAW / setting.repeat;
-
- return RSSI_RAW;
-}
-
-
-
-void SI446x_set_AGC_LNA(uint8_t v)
-{
-
- uint8_t data[2] = {
- 0xd0, // AGC_OVERRIDE
- v
- };
- SI4463_do_api(data, sizeof(data), NULL, 0);
-#if 0
- if (v == 0) {
- data[0] = 0xd1; // Read AGC?????? NO
- SI4463_do_api(data, 1, data, 1);
- }
-#endif
-}
-
-
-#ifdef notused
-// Do an ADC conversion
-static uint16_t getADC(uint8_t adc_en, uint8_t adc_cfg, uint8_t part)
-{
- uint8_t data[6] = {
- SI446X_CMD_GET_ADC_READING,
- adc_en,
- adc_cfg
- };
- SI4463_do_api(data, 3, data, 6);
- return (data[part]<<8 | data[part + 1]);
-}
-#endif
-
-#ifndef __SI4468__
-// -------------- 0.2 kHz ----------------------------
-
-#undef RF_MODEM_TX_RAMP_DELAY_8_1
-#undef RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1
-#undef RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1
-#undef RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1
-
-#define RF_MODEM_TX_RAMP_DELAY_12_1 0x11, 0x20, 0x0C, 0x18, 0x01, 0x00, 0x08, 0x03, 0x80, 0x00, 0xF0, 0x10, 0x74, 0xE8, 0x00, 0xA9
-// #define RF_MODEM_TX_RAMP_DELAY_8_1 0x11, 0x20, 0x08, 0x18, 0x01, 0x00, 0x08, 0x03, 0x80, 0x00, 0xF0, 0x11
-#define RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1 0x11, 0x21, 0x0C, 0x00, 0x0C, 0x01, 0xE4, 0xB9, 0x86, 0x55, 0x2B, 0x0B, 0xF8, 0xEF, 0xEF, 0xF2
-//#define RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1 0x11, 0x21, 0x0C, 0x00, 0xC6, 0xC1, 0xB2, 0x9C, 0x80, 0x63, 0x47, 0x2F, 0x1B, 0x0E, 0x05, 0x00
-#define RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1 0x11, 0x21, 0x0C, 0x0C, 0xF8, 0xFC, 0x05, 0x00, 0xFF, 0x0F, 0x0C, 0x01, 0xE4, 0xB9, 0x86, 0x55
-//#define RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1 0x11, 0x21, 0x0C, 0x0C, 0xFF, 0xFE, 0x00, 0x00, 0x00, 0x0F, 0xC6, 0xC1, 0xB2, 0x9C, 0x80, 0x63
-#define RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1 0x11, 0x21, 0x0C, 0x18, 0x2B, 0x0B, 0xF8, 0xEF, 0xEF, 0xF2, 0xF8, 0xFC, 0x05, 0x00, 0xFF, 0x0F
-//#define RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1 0x11, 0x21, 0x0C, 0x18, 0x47, 0x2F, 0x1B, 0x0E, 0x05, 0x00, 0xFF, 0xFE, 0x00, 0x00, 0x00, 0x0F
-
-#define RF_MODEM_RAW_SEARCH2_2_1 0x11, 0x20, 0x02, 0x50, 0x94, 0x0A
-
-#define RF_GLOBAL_CONFIG_1_1 0x11, 0x00, 0x01, 0x03, 0x20
-
-uint8_t SI4463_RBW_02kHz[] =
-{
- 6, RF_MODEM_RAW_SEARCH2_2_1, \
- 5, RF_GLOBAL_CONFIG_1_1, \
- 0x0C, RF_MODEM_TX_RAMP_DELAY_12_1, \
- 0x10, RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1, \
- 0x10, RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1, \
- 0x10, RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1, \
- 0x00
-};
-// -------------- 1kHz ----------------------------
-
-#undef RF_MODEM_TX_RAMP_DELAY_8_1
-#undef RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1
-#undef RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1
-#undef RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1
-
-#define RF_MODEM_TX_RAMP_DELAY_8_1 0x11, 0x20, 0x08, 0x18, 0x01, 0x00, 0x08, 0x03, 0x80, 0x00, 0xF0, 0x11
-#define RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1 0x11, 0x21, 0x0C, 0x00, 0xC6, 0xC1, 0xB2, 0x9C, 0x80, 0x63, 0x47, 0x2F, 0x1B, 0x0E, 0x05, 0x00
-#define RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1 0x11, 0x21, 0x0C, 0x0C, 0xFF, 0xFE, 0x00, 0x00, 0x00, 0x0F, 0xC6, 0xC1, 0xB2, 0x9C, 0x80, 0x63
-#define RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1 0x11, 0x21, 0x0C, 0x18, 0x47, 0x2F, 0x1B, 0x0E, 0x05, 0x00, 0xFF, 0xFE, 0x00, 0x00, 0x00, 0x0F
-
-uint8_t SI4463_RBW_1kHz[] =
-{
- 0x0C, RF_MODEM_TX_RAMP_DELAY_8_1, \
- 0x10, RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1, \
- 0x10, RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1, \
- 0x10, RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1, \
- 0x00
-};
-
-// -------------- 3 kHz ----------------------------
-
-#undef RF_MODEM_TX_RAMP_DELAY_8_1
-#undef RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1
-#undef RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1
-#undef RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1
-
-#define RF_MODEM_TX_RAMP_DELAY_8_1 0x11, 0x20, 0x08, 0x18, 0x01, 0x80, 0x08, 0x03, 0x80, 0x00, 0xF0, 0x11
-#define RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1 0x11, 0x21, 0x0C, 0x00, 0xCC, 0xA1, 0x30, 0xA0, 0x21, 0xD1, 0xB9, 0xC9, 0xEA, 0x05, 0x12, 0x11
-#define RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1 0x11, 0x21, 0x0C, 0x0C, 0x0A, 0x04, 0x15, 0xFC, 0x03, 0x00, 0xCC, 0xA1, 0x30, 0xA0, 0x21, 0xD1
-#define RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1 0x11, 0x21, 0x0C, 0x18, 0xB9, 0xC9, 0xEA, 0x05, 0x12, 0x11, 0x0A, 0x04, 0x15, 0xFC, 0x03, 0x00
-
-uint8_t SI4463_RBW_3kHz[] =
-{
- 0x0C, RF_MODEM_TX_RAMP_DELAY_8_1, \
- 0x10, RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1, \
- 0x10, RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1, \
- 0x10, RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1, \
- 0x00
-};
-
-// -------------- 10 kHz ----------------------------
-
-#undef RF_MODEM_TX_RAMP_DELAY_8_1
-#undef RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1
-#undef RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1
-#undef RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1
-
-#define RF_MODEM_TX_RAMP_DELAY_8_1 0x11, 0x20, 0x08, 0x18, 0x01, 0x80, 0x08, 0x03, 0x80, 0x00, 0xB0, 0x20
-#define RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1 0x11, 0x21, 0x0C, 0x00, 0xCC, 0xA1, 0x30, 0xA0, 0x21, 0xD1, 0xB9, 0xC9, 0xEA, 0x05, 0x12, 0x11
-#define RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1 0x11, 0x21, 0x0C, 0x0C, 0x0A, 0x04, 0x15, 0xFC, 0x03, 0x00, 0xCC, 0xA1, 0x30, 0xA0, 0x21, 0xD1
-#define RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1 0x11, 0x21, 0x0C, 0x18, 0xB9, 0xC9, 0xEA, 0x05, 0x12, 0x11, 0x0A, 0x04, 0x15, 0xFC, 0x03, 0x00
-
-
-uint8_t SI4463_RBW_10kHz[] =
-{
- 0x0C, RF_MODEM_TX_RAMP_DELAY_8_1, \
- 0x10, RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1, \
- 0x10, RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1, \
- 0x10, RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1, \
- 0x00
-};
-
-// -------------- 30 kHz ----------------------------
-
-#undef RF_MODEM_TX_RAMP_DELAY_8_1
-#undef RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1
-#undef RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1
-#undef RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1
-
-#define RF_MODEM_TX_RAMP_DELAY_8_1 0x11, 0x20, 0x08, 0x18, 0x01, 0x80, 0x08, 0x03, 0x80, 0x00, 0x30, 0x10
-#define RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1 0x11, 0x21, 0x0C, 0x00, 0xFF, 0xBA, 0x0F, 0x51, 0xCF, 0xA9, 0xC9, 0xFC, 0x1B, 0x1E, 0x0F, 0x01
-#define RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1 0x11, 0x21, 0x0C, 0x0C, 0xFC, 0xFD, 0x15, 0xFF, 0x00, 0x0F, 0xFF, 0xBA, 0x0F, 0x51, 0xCF, 0xA9
-#define RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1 0x11, 0x21, 0x0C, 0x18, 0xC9, 0xFC, 0x1B, 0x1E, 0x0F, 0x01, 0xFC, 0xFD, 0x15, 0xFF, 0x00, 0x0F
-
-uint8_t SI4463_RBW_30kHz[] =
-{
- 0x0C, RF_MODEM_TX_RAMP_DELAY_8_1, \
- 0x10, RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1, \
- 0x10, RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1, \
- 0x10, RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1, \
- 0x00
-};
-
-// -------------- 100kHz ----------------------------
-
-#undef RF_MODEM_TX_RAMP_DELAY_8_1
-#undef RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1
-#undef RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1
-#undef RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1
-
-#define RF_MODEM_TX_RAMP_DELAY_8_1 0x11, 0x20, 0x08, 0x18, 0x01, 0x80, 0x08, 0x03, 0x80, 0x00, 0x20, 0x20
-#define RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1 0x11, 0x21, 0x0C, 0x00, 0xFF, 0xBA, 0x0F, 0x51, 0xCF, 0xA9, 0xC9, 0xFC, 0x1B, 0x1E, 0x0F, 0x01
-#define RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1 0x11, 0x21, 0x0C, 0x0C, 0xFC, 0xFD, 0x15, 0xFF, 0x00, 0x0F, 0xFF, 0xBA, 0x0F, 0x51, 0xCF, 0xA9
-#define RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1 0x11, 0x21, 0x0C, 0x18, 0xC9, 0xFC, 0x1B, 0x1E, 0x0F, 0x01, 0xFC, 0xFD, 0x15, 0xFF, 0x00, 0x0F
-
-uint8_t SI4463_RBW_100kHz[] =
-{
- 0x0C, RF_MODEM_TX_RAMP_DELAY_8_1, \
- 0x10, RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1, \
- 0x10, RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1, \
- 0x10, RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1, \
- 0x00
-};
-
-// -------------- 300kHz ----------------------------
-
-#undef RF_MODEM_TX_RAMP_DELAY_8_1
-#undef RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1
-#undef RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1
-#undef RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1
-
-#define RF_MODEM_TX_RAMP_DELAY_8_1 0x11, 0x20, 0x08, 0x18, 0x01, 0x80, 0x08, 0x03, 0x80, 0x00, 0x00, 0x20
-#define RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1 0x11, 0x21, 0x0C, 0x00, 0xCC, 0xA1, 0x30, 0xA0, 0x21, 0xD1, 0xB9, 0xC9, 0xEA, 0x05, 0x12, 0x11
-#define RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1 0x11, 0x21, 0x0C, 0x0C, 0x0A, 0x04, 0x15, 0xFC, 0x03, 0x00, 0xCC, 0xA1, 0x30, 0xA0, 0x21, 0xD1
-#define RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1 0x11, 0x21, 0x0C, 0x18, 0xB9, 0xC9, 0xEA, 0x05, 0x12, 0x11, 0x0A, 0x04, 0x15, 0xFC, 0x03, 0x00
-
-uint8_t SI4463_RBW_300kHz[] =
-{
- 0x0C, RF_MODEM_TX_RAMP_DELAY_8_1, \
- 0x10, RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1, \
- 0x10, RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1, \
- 0x10, RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1, \
- 0x00
-};
-
-
-
-// -------------- 850kHz ----------------------------
-
-#undef RF_MODEM_TX_RAMP_DELAY_8_1
-#undef RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1
-#undef RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1
-#undef RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1
-
-#define RF_MODEM_TX_RAMP_DELAY_8_1 0x11, 0x20, 0x08, 0x18, 0x01, 0x00, 0x08, 0x03, 0x80, 0x00, 0x00, 0x30
-#define RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1 0x11, 0x21, 0x0C, 0x00, 0xFF, 0xBA, 0x0F, 0x51, 0xCF, 0xA9, 0xC9, 0xFC, 0x1B, 0x1E, 0x0F, 0x01
-#define RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1 0x11, 0x21, 0x0C, 0x0C, 0xFC, 0xFD, 0x15, 0xFF, 0x00, 0x0F, 0xFF, 0xBA, 0x0F, 0x51, 0xCF, 0xA9
-#define RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1 0x11, 0x21, 0x0C, 0x18, 0xC9, 0xFC, 0x1B, 0x1E, 0x0F, 0x01, 0xFC, 0xFD, 0x15, 0xFF, 0x00, 0x0F
-
-uint8_t SI4463_RBW_850kHz[] =
-{
- 0x0C, RF_MODEM_TX_RAMP_DELAY_8_1, \
- 0x10, RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1, \
- 0x10, RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1, \
- 0x10, RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1, \
- 0x00
-};
-#else
-// -------------- 0.2 kHz ----------------------------
-
-#include "radio_config_Si4468_undef.h"
-#include "radio_config_Si4468_200Hz.h"
-#include "radio_config_Si4468_short.h"
-
-static const uint8_t SI4463_RBW_02kHz[] =
- RADIO_CONFIGURATION_DATA_ARRAY;
-
-// -------------- 1kHz ----------------------------
-
-#include "radio_config_Si4468_undef.h"
-#include "radio_config_Si4468_1kHz.h"
-#include "radio_config_Si4468_short.h"
-
-static const uint8_t SI4463_RBW_1kHz[] =
- RADIO_CONFIGURATION_DATA_ARRAY;
-
-// -------------- 3 kHz ----------------------------
-#include "radio_config_Si4468_undef.h"
-#include "radio_config_Si4468_3kHz.h"
-#include "radio_config_Si4468_short.h"
-
-static const uint8_t SI4463_RBW_3kHz[] =
- RADIO_CONFIGURATION_DATA_ARRAY;
-
-// -------------- 10 kHz ----------------------------
-#include "radio_config_Si4468_undef.h"
-#include "radio_config_Si4468_10kHz.h"
-#include "radio_config_Si4468_short.h"
-
-static const uint8_t SI4463_RBW_10kHz[] =
- RADIO_CONFIGURATION_DATA_ARRAY;
-
-// -------------- 30 kHz ----------------------------
-#include "radio_config_Si4468_undef.h"
-#include "radio_config_Si4468_30kHz.h"
-#include "radio_config_Si4468_short.h"
-
-static const uint8_t SI4463_RBW_30kHz[] =
- RADIO_CONFIGURATION_DATA_ARRAY;
-
-// -------------- 100kHz ----------------------------
-#include "radio_config_Si4468_undef.h"
-#include "radio_config_Si4468_100kHz.h"
-#include "radio_config_Si4468_short.h"
-
-static const uint8_t SI4463_RBW_100kHz[] =
- RADIO_CONFIGURATION_DATA_ARRAY;
-
-// -------------- 300kHz ----------------------------
-
-#include "radio_config_Si4468_undef.h"
-#include "radio_config_Si4468_300kHz.h"
-#include "radio_config_Si4468_short.h"
-
-static const uint8_t SI4463_RBW_300kHz[] =
- RADIO_CONFIGURATION_DATA_ARRAY;
-
-// -------------- 850kHz ----------------------------
-
-#include "radio_config_Si4468_undef.h"
-#include "radio_config_Si4468_850kHz.h"
-#include "radio_config_Si4468_short.h"
-
-static const uint8_t SI4463_RBW_850kHz[] =
- RADIO_CONFIGURATION_DATA_ARRAY;
-
-#endif
-// User asks for an RBW of WISH, go through table finding the last triple
-// for which WISH is greater than the first entry, use those values,
-// Return the first entry of the following triple for the RBW actually achieved
-#define IF_BW(dwn3, ndec, filset) (((dwn3)<<7)|((ndec)<<4)|(filset))
-typedef struct {
- const uint8_t *reg; // IF_BW(dwn3, ndec, filset)
- int16_t RSSI_correction_x_10; // Correction * 10
- int16_t RBWx10; // RBW in kHz
-}RBW_t; // sizeof(RBW_t) = 8 bytes
-
-static const RBW_t RBW_choices[] =
-{
-// BW register corr freq
- {SI4463_RBW_02kHz, 0,3},
- {SI4463_RBW_1kHz, 0,10},
- {SI4463_RBW_3kHz, 0,30},
- {SI4463_RBW_10kHz, 0,100},
- {SI4463_RBW_30kHz, 0,300},
- {SI4463_RBW_100kHz,0,1000},
- {SI4463_RBW_300kHz,0,3000},
- {SI4463_RBW_850kHz,0,6000},
-};
-
-const int SI4432_RBW_count = ((int)(sizeof(RBW_choices)/sizeof(RBW_t)));
-
-static pureRSSI_t SI4463_RSSI_correction = float_TO_PURE_RSSI(-120);
-static int prev_band = -1;
-
-pureRSSI_t getSI4463_RSSI_correction(void){
- return SI4463_RSSI_correction;
-};
-
-
-uint16_t force_rbw(int f)
-{
- if (SI4463_in_tx_mode)
- return(0);
- SI4463_set_state(SI446X_STATE_READY);
- const uint8_t *config = RBW_choices[f].reg;
- uint16_t i=0;
- while(config[i] != 0)
- {
- SI4463_do_api((void *)&config[i+1], config[i], NULL, 0);
- i += config[i]+1;
- }
- SI4463_clear_int_status();
- SI4463_short_start_rx(); // This can cause recalibration
- SI4463_wait_for_cts();
- set_RSSI_comp();
-// prev_band = -1;
- SI4463_RSSI_correction = float_TO_PURE_RSSI(RBW_choices[f].RSSI_correction_x_10 - 1200)/10; // Set RSSI correction
- return RBW_choices[f].RBWx10; // RBW achieved by SI4463 in kHz * 10
-}
-
-uint16_t set_rbw(uint16_t WISH) {
- int i;
- for (i=0; i < (int)(sizeof(RBW_choices)/sizeof(RBW_t)) - 1; i++)
- if (WISH <= RBW_choices[i].RBWx10)
- break;
- return force_rbw(i);
-}
-
-
-#define Npresc 1 // 0=low / 1=High performance mode
-
-static int refresh_count = 0;
-
-freq_t SI4463_set_freq(freq_t freq)
-{
-// SI4463_set_gpio(3,GPIO_HIGH);
- int S = 4 ; // Approx 100 Hz channels
- SI4463_channel = 0;
- if (freq >= 822000000 && freq <= 1130000000) { // 822 to 1130MHz
- SI4463_band = 0;
- SI4463_outdiv = 4;
- } else if (freq >= 411000000 && freq <= 566000000) { // 411 to 568MHz
- SI4463_band = 2;
- SI4463_outdiv = 8;
- } else if (freq >= 329000000 && freq <= 454000000) { // 329 to 454MHz
- SI4463_band = 1;
- SI4463_outdiv = 10;
- } else if (freq >= 274000000 && freq <= 378000000) { // 274 to 378
- SI4463_band = 3;
- SI4463_outdiv = 12;
- } else if (freq >= 137000000 && freq <= 189000000){ // 137 to 189
- SI4463_band = 5;
- SI4463_outdiv = 24;
-#if 0 // Band 4, 6 and 7 do not function
- } else if (freq >= 137000000 && freq <= 189000000){ // 220 to 266
- SI4463_band = 4;
- SI4463_outdiv = 12;
-#endif
- } else
- return 0;
- if (SI4463_offset_active) {
- si_set_offset(0);
- SI4463_offset_active = false;
- }
- int32_t R = (freq * SI4463_outdiv) / (Npresc ? 2*config.setting_frequency_30mhz : 4*config.setting_frequency_30mhz) - 1; // R between 0x00 and 0x7f (127)
- int64_t MOD = 524288; // = 2^19
- int32_t F = ((freq * SI4463_outdiv*MOD) / (Npresc ? 2*config.setting_frequency_30mhz : 4*config.setting_frequency_30mhz)) - R*MOD;
- freq_t actual_freq = (R*MOD + F) * (Npresc ? 2*config.setting_frequency_30mhz : 4*config.setting_frequency_30mhz)/ SI4463_outdiv/MOD;
- int delta = freq - actual_freq;
- if (delta < -100 || delta > 100 ){
- while(1)
- my_microsecond_delay(10);
- }
- if (F < MOD || F >= MOD*2){
- while(1)
- my_microsecond_delay(10);
- }
- if (false && (SI4463_band == prev_band)) {
- int vco = 2091 + ((((freq / 4 ) * SI4463_outdiv - 850000000)/1000) * 492) / 200000;
-
- if (SI4463_in_tx_mode) {
- uint8_t data[] = {
- 0x37,
- (uint8_t) R, // R data[4]
- (uint8_t) ((F>>16) & 255), // F2,F1,F0 data[5] .. data[7]
- (uint8_t) ((F>> 8) & 255), // F2,F1,F0 data[5] .. data[7]
- (uint8_t) ((F ) & 255), // F2,F1,F0 data[5] .. data[7]
- (vco>>8) & 0xff,
- vco & 0xff,
- 0x00,
- 0x32
- };
- SI4463_do_api(data, sizeof(data), NULL, 0);
- } else {
-
- uint8_t data[] = {
- 0x36,
- (uint8_t) R, // R data[4]
- (uint8_t) ((F>>16) & 255), // F2,F1,F0 data[5] .. data[7]
- (uint8_t) ((F>> 8) & 255), // F2,F1,F0 data[5] .. data[7]
- (uint8_t) ((F ) & 255), // F2,F1,F0 data[5] .. data[7]
- (vco>>8) & 0xff,
- vco & 0xff
- };
- SI4463_do_api(data, sizeof(data), NULL, 0);
- }
- SI4463_frequency_changed = true;
-// SI4463_set_gpio(3,GPIO_LOW);
- return actual_freq;
- }
-#if 0
- static int old_R = -1; // What about TX/RX switching?
- static int old_F = -1;
- if (old_R == R || old_F == F)
- return;
- old_R = R;
- old_F = f;
-#endif
- refresh_count=0;
- SI4463_set_state(SI446X_STATE_READY);
- my_deleted_delay(100);
-
- /*
- // Set properties: RF_FREQ_CONTROL_INTE_8
- // Number of properties: 8
- // Group ID: 0x40
- // Start ID: 0x00
- // Default values: 0x3C, 0x08, 0x00, 0x00, 0x00, 0x00, 0x20, 0xFF,
- // Descriptions:
- // FREQ_CONTROL_INTE - Frac-N PLL Synthesizer integer divide number.
- // FREQ_CONTROL_FRAC_2 - Frac-N PLL fraction number.
- // FREQ_CONTROL_FRAC_1 - Frac-N PLL fraction number.
- // FREQ_CONTROL_FRAC_0 - Frac-N PLL fraction number.
- // FREQ_CONTROL_CHANNEL_STEP_SIZE_1 - EZ Frequency Programming channel step size.
- // FREQ_CONTROL_CHANNEL_STEP_SIZE_0 - EZ Frequency Programming channel step size.
- // FREQ_CONTROL_W_SIZE - Set window gating period (in number of crystal reference clock cycles) for counting VCO frequency during calibration.
- // FREQ_CONTROL_VCOCNT_RX_ADJ - Adjust target count for VCO calibration in RX mode.
- */
- // #define RF_FREQ_CONTROL_INTE_8_1 0x11, 0x40, 0x08, 0x00, 0x41, 0x0D, 0xA9, 0x5A, 0x4E, 0xC5, 0x20, 0xFE
- uint8_t data[] = {
- 0x11, 0x40, 0x08, 0x00,
- (uint8_t) R, // R data[4]
- (uint8_t) ((F>>16) & 255), // F2,F1,F0 data[5] .. data[7]
- (uint8_t) ((F>> 8) & 255), // F2,F1,F0 data[5] .. data[7]
- (uint8_t) ((F ) & 255), // F2,F1,F0 data[5] .. data[7]
- (uint8_t) ((S>> 8) & 255), // Step size data[8] .. data[9]
- (uint8_t) ((S ) & 255), // Step size data[8] .. data[9]
- 0x20, // Window gate
- 0xFF // Adj count
- };
- SI4463_do_api(data, sizeof(data), NULL, 0);
-
- if (SI4463_band != prev_band) {
- /*
- // Set properties: RF_MODEM_CLKGEN_BAND_1
- // Number of properties: 1
- // Group ID: 0x20
- // Start ID: 0x51
- // Default values: 0x08,
- // Descriptions:
- // MODEM_CLKGEN_BAND - Select PLL Synthesizer output divider ratio as a function of frequency band.
- */
- // #define RF_MODEM_CLKGEN_BAND_1 0x11, 0x20, 0x01, 0x51, 0x0A
- uint8_t data2[] = {
- 0x11, 0x20, 0x01, 0x51,
- 0x10 + (uint8_t)(SI4463_band + (Npresc ? 0x08 : 0)) // 0x08 for high performance mode, 0x10 to skip recal
- };
- SI4463_do_api(data2, sizeof(data2), NULL, 0);
-// my_microsecond_delay(30000);
- }
-
-
-
-
- // SI4463_clear_int_status();
-#if 0
- retry:
-#endif
- if (SI4463_in_tx_mode)
- SI4463_start_tx(0);
- else {
- SI4463_start_rx(SI4463_channel);
-#if 0
- si446x_state_t s = SI4463_get_state();
- if (s != SI446X_STATE_RX) {
- SI4463_start_rx(SI4463_channel);
- my_microsecond_delay(1000);
-#if 1
- si446x_state_t s = SI4463_get_state();
- if (s != SI446X_STATE_RX) {
- my_microsecond_delay(3000);
- goto retry;
- }
-#endif
- }
-#endif
- }
- SI4463_wait_for_cts();
-// SI4463_set_gpio(3,GPIO_LOW);
- SI4463_frequency_changed = true;
- prev_band = SI4463_band;
- return actual_freq;
-}
-
-void SI4463_init_rx(void)
-{
-// reset:
- SI_SDN_LOW;
- my_microsecond_delay(100);
- SI_SDN_HIGH;
- my_microsecond_delay(1000);
- SI_SDN_LOW;
- my_microsecond_delay(1000);
-#ifdef __SI4468__
- for(uint16_t i=0;i
+#include "si4432.h"
+#include "spi.h"
+
+#pragma GCC push_options
+#pragma GCC optimize ("Og")
+
+// Define for use hardware SPI mode
+#define USE_HARDWARE_SPI_MODE
+
+// 10MHz clock
+#define SI4432_10MHZ 10000000U
+// !!!! FROM ili9341.c for disable it !!!!
+//#define LCD_CS_HIGH palSetPad(GPIOB, GPIOB_LCD_CS)
+#define SI_CS_LOW palClearLine(LINE_RX_SEL)
+#define SI_CS_HIGH palSetLine(LINE_RX_SEL)
+
+#define SI_SDN_LOW palClearLine(LINE_RX_SDN)
+#define SI_SDN_HIGH palSetLine(LINE_RX_SDN)
+
+
+// Hardware or software SPI use
+#ifdef USE_HARDWARE_SPI_MODE
+#define SI4432_SPI SPI1
+//#define SI4432_SPI_SPEED SPI_BR_DIV64
+//#define SI4432_SPI_SPEED SPI_BR_DIV32
+#define SI4432_SPI_SPEED SPI_BR_DIV16
+
+//#define ADF_SPI_SPEED SPI_BR_DIV64
+//#define ADF_SPI_SPEED SPI_BR_DIV32
+#define ADF_SPI_SPEED SPI_BR_DIV4
+
+#define PE_SPI_SPEED SPI_BR_DIV32
+
+static uint32_t old_spi_settings;
+#else
+static uint32_t old_port_moder;
+static uint32_t new_port_moder;
+#endif
+
+#define SPI1_CLK_HIGH palSetPad(GPIOB, GPIOB_SPI_SCLK)
+#define SPI1_CLK_LOW palClearPad(GPIOB, GPIOB_SPI_SCLK)
+
+#define SPI1_SDI_HIGH palSetPad(GPIOB, GPIOB_SPI_MOSI)
+#define SPI1_SDI_LOW palClearPad(GPIOB, GPIOB_SPI_MOSI)
+#define SPI1_RESET palClearPort(GPIOB, (1<>GPIOB_SPI_MISO)&1)
+#define SPI1_portSDO (palReadPort(GPIOB)&(1<CR1;
+ SPI_BR_SET(SI4432_SPI, SI4432_SPI_SPEED);
+#else
+ // Init legs mode for software bitbang
+ old_port_moder = GPIOB->MODER;
+ new_port_moder = old_port_moder & ~(PIN_MODE_ANALOG(GPIOB_SPI_SCLK)|PIN_MODE_ANALOG(GPIOB_SPI_MISO)|PIN_MODE_ANALOG(GPIOB_SPI_MOSI));
+ new_port_moder|= PIN_MODE_OUTPUT(GPIOB_SPI_SCLK)|PIN_MODE_INPUT(GPIOB_SPI_MISO)|PIN_MODE_OUTPUT(GPIOB_SPI_MOSI);
+ GPIOB->MODER = new_port_moder;
+ // Pull down SPI
+ SPI1_SDI_LOW;
+ SPI1_CLK_LOW;
+#endif
+}
+
+void stop_SI4432_SPI_mode(void){
+#ifdef USE_HARDWARE_SPI_MODE
+ SI4432_SPI->CR1 = old_spi_settings;
+#else
+ // Restore hardware SPI
+ GPIOB->MODER = old_port_moder;
+#endif
+}
+
+static void shiftOut(uint8_t val)
+{
+#ifdef USE_HARDWARE_SPI_MODE
+ SPI_WRITE_8BIT(SI4432_SPI, val);
+ while (SPI_IS_BUSY(SI4432_SPI)) // drop rx and wait tx
+ (void)SPI_READ_8BIT(SI4432_SPI);
+#else
+ SI4432_log(SI4432_Sel);
+ SI4432_log(val);
+ uint8_t i = 0;
+ do {
+ SPI1_SDI_HIGH;
+ SPI1_CLK_HIGH;
+ SPI1_RESET;
+ val<<=1;
+ }while((++i) & 0x07);
+#endif
+}
+
+static uint8_t shiftIn(void)
+{
+#ifdef USE_HARDWARE_SPI_MODE
+ SPI_WRITE_8BIT(SI4432_SPI, 0xFF);
+ while (SPI_IS_BUSY(SI4432_SPI)) // drop rx and wait tx
+ while (SPI_RX_IS_EMPTY(SI4432_SPI)); //wait rx data in buffer
+ return SPI_READ_8BIT(SI4432_SPI);
+#else
+ uint32_t value = 0;
+ uint8_t i = 0;
+ do {
+ value<<=1;
+ SPI1_CLK_HIGH;
+ value|=SPI1_portSDO;
+ SPI1_CLK_LOW;
+ }while((++i) & 0x07);
+ return value>>GPIOB_SPI_MISO;
+#endif
+}
+
+static inline void shiftInBuf(uint16_t sel, uint8_t addr, deviceRSSI_t *buf, uint16_t size, uint16_t delay) {
+#ifdef USE_HARDWARE_SPI_MODE
+ do{
+ palClearPad(GPIOB, sel);
+ SPI_WRITE_8BIT(SI4432_SPI, addr);
+ while (SPI_IS_BUSY(SI4432_SPI)) // drop rx and wait tx
+ (void)SPI_READ_8BIT(SI4432_SPI);
+
+ SPI_WRITE_8BIT(SI4432_SPI, 0xFF);
+ while (SPI_RX_IS_EMPTY(SI4432_SPI)); //wait rx data in buffer
+ *buf++=SPI_READ_8BIT(SI4432_SPI);
+ palSetPad(GPIOB, sel);
+ if (delay)
+ my_microsecond_delay(delay);
+ }while(--size);
+#else
+ uint8_t i = 0;
+ do{
+ uint32_t value = addr;
+ palClearPad(GPIOB, sel);
+ do {
+ if (value & 0x80)
+ SPI1_SDI_HIGH;
+ SPI1_CLK_HIGH;
+ SPI1_RESET;
+ value<<=1;
+ }while((++i) & 0x07);
+ value = 0;
+ do {
+ SPI1_CLK_HIGH;
+ value<<=1;
+ value|=SPI1_portSDO;
+ SPI1_CLK_LOW;
+ }while((++i) & 0x07);
+ palSetPad(GPIOB, sel);
+ *buf++=value>>GPIOB_SPI_MISO;
+ if (delay)
+ my_microsecond_delay(delay);
+ }while(--size);
+#endif
+}
+#if 0
+static void shiftOutBuf(uint8_t *buf, uint16_t size) {
+ uint8_t i = 0;
+ do{
+ uint8_t val = *buf++;
+ do{
+ if (val & 0x80)
+ SPI1_SDI_HIGH;
+ else
+ SPI1_SDI_LOW;
+ val<<=1;
+ SPI1_CLK_HIGH;
+ SPI1_CLK_LOW;
+ }while((++i) & 0x07);
+ }while(--size);
+}
+#endif
+
+int SI4432_step_delay = 1500;
+int SI4432_offset_delay = 1500;
+#define MINIMUM_WAIT_FOR_RSSI 280
+
+#ifdef __SI4432__
+#define CS_SI0_HIGH palSetPad(GPIOC, GPIO_RX_SEL)
+#define CS_SI1_HIGH palSetPad(GPIOC, GPIO_LO_SEL)
+
+#define RF_POWER_HIGH palSetPad(GPIOB, GPIO_RF_PWR)
+
+
+#define CS_SI0_LOW palClearPad(GPIOC, GPIO_RX_SEL)
+#define CS_SI1_LOW palClearPad(GPIOC, GPIO_LO_SEL)
+
+
+const uint16_t SI_nSEL[MAX_SI4432+1] = { GPIO_RX_SEL, GPIO_LO_SEL, 0}; // #3 is dummy!!!!!!
+
+volatile int SI4432_Sel = 0; // currently selected SI4432
+// volatile int SI4432_guard = 0;
+
+#ifdef __SI4432_H__
+#define SELECT_DELAY 10
+void SI4432_Write_Byte(uint8_t ADR, uint8_t DATA )
+{
+ set_SPI_mode(SPI_MODE_SI);
+// if (SI4432_guard)
+// while(1) ;
+// SI4432_guard = 1;
+// SPI1_CLK_LOW;
+ palClearPad(GPIOB, SI_nSEL[SI4432_Sel]);
+// my_microsecond_delay(SELECT_DELAY);
+ ADR |= 0x80 ; // RW = 1
+ shiftOut( ADR );
+ shiftOut( DATA );
+ palSetPad(GPIOB, SI_nSEL[SI4432_Sel]);
+// SI4432_guard = 0;
+}
+
+void SI4432_Write_2_Byte(uint8_t ADR, uint8_t DATA1, uint8_t DATA2)
+{
+// if (SI4432_guard)
+// while(1) ;
+// SI4432_guard = 1;
+// SPI2_CLK_LOW;
+ palClearPad(GPIOC, SI_nSEL[SI4432_Sel]);
+// chThdSleepMicroseconds(SELECT_DELAY);
+ ADR |= 0x80 ; // RW = 1
+ shiftOut( ADR );
+ shiftOut( DATA1 );
+ shiftOut( DATA2 );
+ palSetPad(GPIOC, SI_nSEL[SI4432_Sel]);
+// SI4432_guard = 0;
+}
+
+void SI4432_Write_3_Byte(uint8_t ADR, uint8_t DATA1, uint8_t DATA2, uint8_t DATA3 )
+{
+ set_SPI_mode(SPI_MODE_SI);
+// if (SI4432_guard)
+// while(1) ;
+// SI4432_guard = 1;
+// SPI1_CLK_LOW;
+ palClearPad(GPIOB, SI_nSEL[SI4432_Sel]);
+// my_microsecond_delay(SELECT_DELAY);
+ ADR |= 0x80 ; // RW = 1
+ shiftOut( ADR );
+ shiftOut( DATA1 );
+ shiftOut( DATA2 );
+ shiftOut( DATA3 );
+ palSetPad(GPIOB, SI_nSEL[SI4432_Sel]);
+// SI4432_guard = 0;
+}
+
+uint8_t SI4432_Read_Byte( uint8_t ADR )
+{
+ set_SPI_mode(SPI_MODE_SI);
+ uint8_t DATA ;
+// if (SI4432_guard)
+// while(1) ;
+// SI4432_guard = 1;
+// SPI1_CLK_LOW;
+ palClearPad(GPIOB, SI_nSEL[SI4432_Sel]);
+ shiftOut( ADR );
+ DATA = shiftIn();
+ palSetPad(GPIOB, SI_nSEL[SI4432_Sel]);
+// SI4432_guard = 0;
+ return DATA ;
+}
+
+
+
+void SI4432_Reset(void)
+{
+ int count = 0;
+ SI4432_Read_Byte (SI4432_INT_STATUS1); // Clear pending interrupts
+ SI4432_Read_Byte (SI4432_INT_STATUS2);
+ // always perform a system reset (don't send 0x87)
+ SI4432_Write_Byte(SI4432_STATE, 0x80);
+ chThdSleepMilliseconds(10);
+ // wait for chiprdy bit
+ while (count++ < 100 && ( SI4432_Read_Byte (SI4432_INT_STATUS2) & 0x02 ) == 0) {
+ chThdSleepMilliseconds(10);
+ }
+}
+
+void SI4432_Drive(int d)
+{
+ SI4432_Write_Byte(SI4432_TX_POWER, (uint8_t) (0x18+(d & 7)));
+}
+
+void SI4432_Transmit(int d)
+{
+ int count = 0;
+ SI4432_Drive(d);
+ if (( SI4432_Read_Byte(SI4432_DEV_STATUS) & 0x03 ) == 2)
+ return; // Already in transmit mode
+ chThdSleepMilliseconds(3);
+ SI4432_Write_Byte(SI4432_STATE, 0x02);
+ chThdSleepMilliseconds(3);
+ SI4432_Write_Byte(SI4432_STATE, 0x0b);
+ chThdSleepMilliseconds(10);
+ while (count++ < 100 && ( SI4432_Read_Byte(SI4432_DEV_STATUS) & 0x03 ) != 2) {
+ chThdSleepMilliseconds(10);
+ }
+}
+
+void SI4432_Receive(void)
+{
+ int count = 0;
+ if (( SI4432_Read_Byte (SI4432_DEV_STATUS) & 0x03 ) == 1)
+ return; // Already in receive mode
+ chThdSleepMilliseconds(3);
+ SI4432_Write_Byte(SI4432_STATE, 0x02);
+ chThdSleepMilliseconds(3);
+ SI4432_Write_Byte(SI4432_STATE, 0x07);
+ chThdSleepMilliseconds(10);
+ while (count++ < 100 && ( SI4432_Read_Byte(SI4432_DEV_STATUS) & 0x03 ) != 1) {
+ chThdSleepMilliseconds(5);
+ }
+}
+
+// User asks for an RBW of WISH, go through table finding the last triple
+// for which WISH is greater than the first entry, use those values,
+// Return the first entry of the following triple for the RBW actually achieved
+#define IF_BW(dwn3, ndec, filset) (((dwn3)<<7)|((ndec)<<4)|(filset))
+typedef struct {
+ uint8_t reg; // IF_BW(dwn3, ndec, filset)
+ int8_t RSSI_correction_x_10; // Correction * 10
+ uint16_t RBWx10; // RBW * 10 in kHz
+}RBW_t; // sizeof(RBW_t) = 4 bytes
+RBW_t RBW_choices[] = {
+// BW register corr freq
+// {IF_BW(0,5,1),0,26},
+// {IF_BW(0,5,2),0,28},
+ {IF_BW(0,5,3),3,31},
+ {IF_BW(0,5,4),-3,32},
+ {IF_BW(0,5,5),6,37},
+ {IF_BW(0,5,6),5,42},
+ {IF_BW(0,5,7),5,45},
+ {IF_BW(0,4,1),0,49},
+ {IF_BW(0,4,2),0,54},
+ {IF_BW(0,4,3),0,59},
+ {IF_BW(0,4,4),0,61},
+ {IF_BW(0,4,5),5,72},
+ {IF_BW(0,4,6),5,82},
+ {IF_BW(0,4,7),5,88},
+ {IF_BW(0,3,1),0,95},
+ {IF_BW(0,3,2),0,106},
+ {IF_BW(0,3,3),2,115},
+ {IF_BW(0,3,4),0,121},
+ {IF_BW(0,3,5),5,142},
+ {IF_BW(0,3,6),5,162},
+ {IF_BW(0,3,7),5,175},
+ {IF_BW(0,2,1),0,189},
+ {IF_BW(0,2,2),0,210},
+ {IF_BW(0,2,3),3,227},
+ {IF_BW(0,2,4),0,240},
+ {IF_BW(0,2,5),5,282},
+ {IF_BW(0,2,6),5,322},
+ {IF_BW(0,2,7),5,347},
+ {IF_BW(0,1,1),0,377},
+ {IF_BW(0,1,2),0,417},
+ {IF_BW(0,1,3),1,452},
+ {IF_BW(0,1,4),0,479},
+ {IF_BW(0,1,5),5,562},
+ {IF_BW(0,1,6),5,641},
+ {IF_BW(0,1,7),5,692},
+ {IF_BW(0,0,1),0,752},
+ {IF_BW(0,0,2),0,832},
+ {IF_BW(0,0,3),0,900},
+ {IF_BW(0,0,4),-1,953},
+ {IF_BW(0,0,5),9,1121},
+ {IF_BW(0,0,6),2,1279},
+ {IF_BW(0,0,7),5,1379},
+ {IF_BW(1,1,4),20,1428},
+ {IF_BW(1,1,5),26,1678},
+ {IF_BW(1,1,9),-50,1811},
+ {IF_BW(1,0,15),-100,1915},
+ {IF_BW(1,0,1),20,2251},
+ {IF_BW(1,0,2),22,2488},
+ {IF_BW(1,0,3),21,2693},
+ {IF_BW(1,0,4),15,2849},
+ {IF_BW(1,0,8),-15,3355},
+ {IF_BW(1,0,9),-53,3618},
+ {IF_BW(1,0,10),-15,4202},
+ {IF_BW(1,0,11),-13,4684},
+ {IF_BW(1,0,12),-20,5188},
+ {IF_BW(1,0,13),-14,5770},
+ {IF_BW(1,0,14),-9,6207},
+
+
+};
+
+const int SI4432_RBW_count = ((int)(sizeof(RBW_choices)/sizeof(RBW_t)));
+
+static pureRSSI_t SI4432_RSSI_correction = float_TO_PURE_RSSI(-120);
+
+uint16_t force_rbw(int i)
+{
+ SI4432_Write_Byte(SI4432_IF_FILTER_BW, RBW_choices[i].reg); // Write RBW settings to Si4432
+ SI4432_RSSI_correction = float_TO_PURE_RSSI(RBW_choices[i].RSSI_correction_x_10 - 1200)/10; // Set RSSI correction
+// SI4432_RSSI_correction = float_TO_PURE_RSSI( - 1200)/10; // Set RSSI correction
+ return RBW_choices[i].RBWx10; // RBW achieved by Si4432 in kHz * 10
+}
+
+uint16_t set_rbw(uint16_t WISH) {
+ int i;
+ for (i=0; i < SI4432_RBW_count - 1; i++)
+ if (WISH <= RBW_choices[i].RBWx10)
+ break;
+ return force_rbw(i);
+}
+
+
+int SI4432_frequency_changed = false;
+int SI4432_offset_changed = false;
+
+// #define __CACHE_BAND__ // Is not reliable!!!!!!
+
+#ifdef __CACHE_BAND__
+static int old_freq_band[2] = {-1,-1};
+static int written[2]= {0,0};
+#endif
+
+void SI4432_Set_Frequency ( freq_t Freq ) {
+// int mode = SI4432_Read_Byte(0x02) & 0x03; // Disabled as unreliable
+// SI4432_Write_Byte(0x07, 0x02); // Switch to tune mode
+
+// Freq = (Freq / 1000 ) * 1000; // force freq to 1000 grid
+
+ uint8_t hbsel;
+ if (0) shell_printf("%d: Freq %q\r\n", SI4432_Sel, Freq);
+ if (Freq >= 480000000U) {
+ hbsel = 1<<5;
+ Freq>>=1;
+ } else {
+ hbsel = 0;
+ }
+ uint8_t sbsel = 1 << 6;
+ uint32_t N = (Freq / config.setting_frequency_10mhz - 24)&0x1F;
+ uint32_t K = Freq % config.setting_frequency_10mhz;
+ uint32_t Carrier = (K<<2) / 625;
+ uint8_t Freq_Band = N | hbsel | sbsel;
+// int count = 0;
+// my_microsecond_delay(200);
+// int s;
+// while (count++ < 100 && ( (s = SI4432_Read_Byte ( 0x02 )) & 0x03 ) != 0) {
+// my_microsecond_delay(100);
+// }
+
+#ifdef __CACHE_BAND__
+ if (old_freq_band[SI4432_Sel] == Freq_Band) {
+ if (written[SI4432_Sel] < 4) {
+ SI4432_Write_Byte ( 0x75, Freq_Band );
+ written[SI4432_Sel]++;
+ }
+ SI4432_Write_Byte(SI4432_FREQCARRIER_H, (Carrier>>8) & 0xFF );
+ SI4432_Write_Byte(SI4432_FREQCARRIER_L, Carrier & 0xFF );
+ } else {
+#endif
+#if 0 // Do not use multi byte write
+ SI4432_Write_Byte ( 0x75, Freq_Band ); // Freq band must be written first !!!!!!!!!!!!
+ SI4432_Write_Byte(SI4432_FREQCARRIER_H, (Carrier>>8) & 0xFF );
+ SI4432_Write_Byte(SI4432_FREQCARRIER_L, Carrier & 0xFF );
+#else
+ SI4432_Write_3_Byte (SI4432_FREQBAND, Freq_Band, (Carrier>>8) & 0xFF, Carrier & 0xFF);
+#endif
+#ifdef __CACHE_BAND__
+ old_freq_band[SI4432_Sel] = Freq_Band;
+ written[SI4432_Sel] = 0;
+ }
+#endif
+ SI4432_frequency_changed = true;
+// if (mode == 1) // RX mode Disabled as unreliable
+// SI4432_Write_Byte( 0x07, 0x07);
+// else
+// SI4432_Write_Byte( 0x07, 0x0B);
+}
+
+//extern int setting.repeat;
+
+#ifdef __FAST_SWEEP__
+extern deviceRSSI_t age[POINTS_COUNT];
+static int buf_index = 0;
+static int buf_end = 0;
+static bool buf_read = false;
+
+#if 0
+int SI4432_is_fast_mode(void)
+{
+ return buf_read;
+}
+#endif
+
+
+//--------------------------- Trigger -------------------
+// ************** trigger mode if need
+// trigger on measure 4 point
+#define T_POINTS 4
+#define T_LEVEL_UNDEF (1<<(16-T_POINTS)) // should drop after 4 shifts left
+#define T_LEVEL_BELOW 1
+#define T_LEVEL_ABOVE 0
+// Trigger mask, should have width T_POINTS bit
+#define T_DOWN_MASK (0b0011) // 2 from up 2 to bottom
+#define T_UP_MASK (0b1100) // 2 from bottom 2 to up
+#define T_LEVEL_CLEAN ~(1<= sweep_points)
+ i = 0;
+ switch (waiting) {
+ case ST_ARMING:
+ if (i == sweep_points-1) {
+ waiting = ST_WAITING;
+ setting.measure_sweep_time_us = (chVTGetSystemTimeX() - measure)*100;
+ }
+ break;
+ case ST_WAITING:
+#if 1
+ if (rssi < trigger_lvl) {
+ data_level = ((data_level<<1) | (T_LEVEL_BELOW))&(T_LEVEL_CLEAN);
+ } else {
+ data_level = ((data_level<<1) | (T_LEVEL_ABOVE))&(T_LEVEL_CLEAN);
+ }
+#else
+ data_level = ((data_level<<1) | (rssi < trigger_lvl ? T_LEVEL_BELOW : T_LEVEL_ABOVE))&(T_LEVEL_CLEAN);
+#endif
+ if (data_level == t_mode) { // wait trigger
+ // if (i == 128) { // wait trigger
+ waiting = ST_FILLING;
+ switch (trigger_mode) {
+ case T_PRE: // Trigger at the begin of the scan
+ buf_index = i;
+ goto fill_rest;
+ break;
+ case T_POST: // Trigger at the end of the scan
+ buf_index = i;
+ goto done;
+ break;
+ case T_MID: // Trigger in the middle of the scan
+ buf_index = i + sweep_points/2;
+ if (buf_index >= sweep_points)
+ buf_index -= sweep_points;
+ break;
+ }
+ }
+ break;
+ case ST_FILLING:
+ if (i == buf_index)
+ goto done;
+ }
+fill_rest:
+ if (t)
+ my_microsecond_delay(t);
+ }while(1);
+done:
+ buf_end = buf_index;
+ buf_read = true;
+}
+
+void SI4432_Fill(int s, int start)
+{
+ set_SPI_mode(SPI_MODE_SI);
+ SI4432_Sel = s;
+ uint16_t sel = SI_nSEL[SI4432_Sel];
+#if 0
+ uint32_t t = calc_min_sweep_time_us(); // Time to delay in uS for all sweep
+ if (t < setting.sweep_time_us){
+ t = setting.sweep_time_us - t;
+ t = t / (sweep_points - 1); // Now in uS per point
+ }
+ else
+ t = 0;
+#endif
+ uint32_t t = setting.additional_step_delay_us;
+ systime_t measure = chVTGetSystemTimeX();
+// __disable_irq();
+#if 1
+ SPI2_CLK_LOW;
+ int i = start;
+ do {
+ palClearPad(GPIOC, sel);
+ shiftOut(SI4432_REG_RSSI);
+ age[i]=(char)shiftIn();
+ palSetPad(GPIOC, sel);
+ if (++i >= sweep_points) break;
+ if (t)
+ my_microsecond_delay(t);
+ } while(1);
+#else
+ shiftInBuf(sel, SI4432_REG_RSSI, &age[start], sweep_points - start, t);
+#endif
+// __enable_irq();
+ setting.measure_sweep_time_us = (chVTGetSystemTimeX() - measure)*100;
+ buf_index = start; // Is used to skip 1st entry during level triggering
+ buf_end = sweep_points - 1;
+ buf_read = true;
+}
+#endif
+
+
+pureRSSI_t getSI4432_RSSI_correction(void){
+ return SI4432_RSSI_correction;
+};
+
+pureRSSI_t SI4432_RSSI(uint32_t i, int s)
+{
+ (void) i;
+ int32_t RSSI_RAW;
+ (void) i;
+ // SEE DATASHEET PAGE 61
+#ifdef USE_SI4463 // Not used!!!!!!!
+ if (SI4432_Sel == 2) {
+ RSSI_RAW = Si446x_getRSSI();
+ } else
+#endif
+//START_PROFILE
+#ifdef __FAST_SWEEP__
+ if (buf_read) {
+ pureRSSI_t val = DEVICE_TO_PURE_RSSI(age[buf_index++]);
+ if (buf_index >= sweep_points)
+ buf_index = 0;
+ if (buf_index == buf_end)
+ buf_read = false;
+ return val;
+ }
+#endif
+ SI4432_Sel = s;
+ int stepdelay = SI4432_step_delay;
+ if (SI4432_frequency_changed) {
+ if (stepdelay < MINIMUM_WAIT_FOR_RSSI) {
+ stepdelay = MINIMUM_WAIT_FOR_RSSI;
+ }
+ SI4432_frequency_changed = false;
+ } else if (SI4432_offset_changed) {
+// stepdelay = MINIMUM_WAIT_FOR_RSSI + (stepdelay - MINIMUM_WAIT_FOR_RSSI)/8;
+ stepdelay = SI4432_offset_delay;
+ SI4432_offset_changed = false;
+ }
+ if (stepdelay)
+ my_microsecond_delay(stepdelay);
+ // my_microsecond_delay(SI4432_step_delay);
+ i = setting.repeat;
+ RSSI_RAW = 0;
+ do{
+ RSSI_RAW += DEVICE_TO_PURE_RSSI((deviceRSSI_t)SI4432_Read_Byte(SI4432_REG_RSSI));
+ if (--i == 0) break;
+// my_microsecond_delay(100);
+ }while(1);
+
+ if (setting.repeat > 1)
+ RSSI_RAW = RSSI_RAW / setting.repeat;
+ // if (MODE_INPUT(setting.mode) && RSSI_RAW == 0)
+ // SI4432_Init();
+#ifdef __SIMULATION__
+#error "Fixme!!! add correct simulation in pureRSSI_t type"
+ RSSI_RAW = Simulated_SI4432_RSSI(i,s);
+#endif
+//STOP_PROFILE
+ // Serial.println(dBm,2);
+ return RSSI_RAW;
+}
+
+static uint8_t SI4432_init_script[] =
+{
+ SI4432_INT_ENABLE1, 0x0,
+ SI4432_INT_ENABLE2, 0x0,
+ SI4432_CLOCK_RECOVERY_GEARSHIFT, 0x00,
+ SI4432_AGC_OVERRIDE, 0x60,
+ SI4432_AFC_LOOP_GEARSHIFT_OVERRIDE, 0x00,
+ SI4432_AFC_TIMING_CONTROL, 0x02,
+ SI4432_CLOCK_RECOVERY_GEARSHIFT, 0x03,
+ SI4432_CLOCK_RECOVERY_OFFSET2, 0x01,
+ SI4432_CLOCK_RECOVERY_OFFSET1, 0x11,
+ SI4432_CLOCK_RECOVERY_OFFSET0, 0x11,
+ SI4432_CLOCK_RECOVERY_TIMING_GAIN1, 0x01,
+ SI4432_CLOCK_RECOVERY_TIMING_GAIN0, 0x13,
+ SI4432_AFC_LIMITER, 0xFF,
+ SI4432_DATAACCESS_CONTROL, 0x61, // Disable all packet handling
+ SI4432_AGC_OVERRIDE, 0x60, // AGC, no LNA, fast gain increment
+ SI4432_GPIO0_CONF, 0x12, // Normal
+ SI4432_GPIO1_CONF, 0x15,
+ SI4432_GPIO2_CONF, 0x1F
+};
+
+
+void SI4432_Sub_Init(void)
+{
+ SI4432_Reset();
+ uint8_t *p = SI4432_init_script;
+ while (*p) {
+ uint8_t r = *p++;
+ uint8_t v = *p++;
+ SI4432_Write_Byte (r,v);
+ }
+ // IF Filter Bandwidth
+// set_rbw(100) ;
+
+// SI4432_Receive();
+
+}
+
+#define V0_XTAL_CAPACITANCE 0x64
+#define V1_XTAL_CAPACITANCE 0x64
+
+
+
+void SI4432_Init()
+{
+ return;
+#if 1
+
+ CS_SI0_LOW; // Drop CS so power can be removed
+ CS_SI1_LOW; // Drop CS so power can be removed
+ CS_PE_LOW; // low is the default safe state
+ SPI1_CLK_LOW; // low is the default safe state
+ SPI1_SDI_LOW; // will be set with any data out
+
+ palClearPad(GPIOA, GPIOA_RF_PWR); // Drop power
+ chThdSleepMilliseconds(10); // Wait
+ palSetPad(GPIOA, GPIOA_RF_PWR); // Restore power
+ CS_SI0_HIGH; // And set chip select lines back to inactive
+ CS_SI1_HIGH;
+ chThdSleepMilliseconds(10); // Wait
+#endif
+ SPI1_CLK_LOW;
+ //DebugLine("IO set");
+ SI4432_Sel = SI4432_RX;
+ SI4432_Sub_Init();
+
+ SI4432_Sel = SI4432_LO;
+ SI4432_Sub_Init();
+//DebugLine("1 init done");
+}
+
+void set_calibration_freq(int freq)
+{
+ SI4432_Sel = SI4432_LO; //Select Lo module
+ if (freq < 0 || freq > 7 ) {
+ SI4432_Write_Byte(SI4432_GPIO2_CONF, 0x1F) ; // Set GPIO2 to GND
+ } else {
+ SI4432_Write_Byte(SI4432_GPIO2_CONF, 0xC0) ; // Set GPIO2 maximumdrive and clock output
+ SI4432_Write_Byte(Si4432_UC_OUTPUT_CLOCK, freq & 0x07) ; // Set GPIO2 frequency
+ }
+}
+#endif
+#endif
+
+//------------PE4302 -----------------------------------------------
+#ifdef __PE4302__
+
+// Comment out this define to use parallel mode PE4302
+
+#define PE4302_en 10
+
+void PE4302_init(void) {
+ CS_PE_LOW;
+}
+
+#define PE4302_DELAY 100
+#if 0
+void PE4302_shiftOut(uint8_t val)
+{
+ uint8_t i;
+ SI4432_log(SI4432_Sel);
+ SI4432_log(val);
+ for (i = 0; i < 8; i++) {
+ if (val & (1 << (7 - i)))
+ SPI1_SDI_HIGH;
+ else
+ SPI1_SDI_LOW;
+// my_microsecond_delay(PE4302_DELAY);
+ SPI1_CLK_HIGH;
+// my_microsecond_delay(PE4302_DELAY);
+ SPI1_CLK_LOW;
+// my_microsecond_delay(PE4302_DELAY);
+ }
+}
+#endif
+
+static unsigned char old_attenuation = 255;
+bool PE4302_Write_Byte(unsigned char DATA )
+{
+ if (old_attenuation == DATA)
+ return false;
+// my_microsecond_delay(PE4302_DELAY);
+// SPI1_CLK_LOW;
+// my_microsecond_delay(PE4302_DELAY);
+// PE4302_shiftOut(DATA);
+
+ set_SPI_mode(SPI_MODE_SI);
+ SPI_BR_SET(SI4432_SPI, PE_SPI_SPEED);
+
+ shiftOut(DATA);
+// my_microsecond_delay(PE4302_DELAY);
+ CS_PE_HIGH;
+// my_microsecond_delay(PE4302_DELAY);
+ CS_PE_LOW;
+// my_microsecond_delay(PE4302_DELAY);
+ SPI_BR_SET(SI4432_SPI, SI4432_SPI_SPEED);
+ return true;
+}
+
+#endif
+
+#if 0
+//-----------------SI4432 dummy------------------
+void SI4432_Write_Byte(unsigned char ADR, unsigned char DATA ) {}
+unsigned char SI4432_Read_Byte(unsigned char ADR) {return ADR;}
+float set_rbw(float WISH) {return (WISH > 600.0?600: (WISH<3.0?3:WISH));}
+void set_calibration_freq(int p) {}
+void SI4432_Set_Frequency(long f) {}
+void PE4302_Write_Byte(unsigned char DATA ) {}
+void PE4302_init(void) {}
+#endif
+
+#ifdef __SIMULATION__
+unsigned long seed = 123456789;
+extern float actual_rbw;
+float myfrand(void)
+{
+ seed = (unsigned int) (1103515245 * seed + 12345) ;
+ return ((float) seed) / 1000000000.0;
+}
+#define NOISE ((myfrand()-2) * 2) // +/- 4 dBm noise
+extern int settingAttenuate;
+
+//#define LEVEL(i, f, v) (v * (1-(fabs(f - frequencies[i])/actual_rbw/1000)))
+
+float LEVEL(uint32_t i, freq_t f, int v)
+{
+ float dv;
+ float df = fabs((float)f - (float)i);
+ if (df < actual_rbw*1000)
+ dv = df/(actual_rbw*1000);
+ else
+ dv = 1 + 50*(df - actual_rbw*1000)/(actual_rbw*1000);
+ return (v - dv - settingAttenuate);
+}
+
+float Simulated_SI4432_RSSI(uint32_t i, int s)
+{
+ SI4432_Sel = s;
+ float v = -100 + log10(actual_rbw)*10 + NOISE;
+ if(s == 0) {
+ v = fmax(LEVEL(i,10000000,-20),v);
+ v = fmax(LEVEL(i,20000000,-40),v);
+ v = fmax(LEVEL(i,30000000,-30),v);
+ v = fmax(LEVEL(i,40000000,-90),v);
+ } else {
+ v = fmax(LEVEL(i,320000000,-20),v);
+ v = fmax(LEVEL(i,340000000,-40),v);
+ v = fmax(LEVEL(i,360000000,-30),v);
+ v = fmax(LEVEL(i,380000000,-90),v);
+ }
+ return(v);
+}
+
+#endif
+//------------------------------- ADF4351 -------------------------------------
+
+#ifdef __ADF4351__
+
+#define bitRead(value, bit) (((value) >> (bit)) & 0x01)
+#define bitSet(value, bit) ((value) |= (1UL << (bit)))
+#define bitClear(value, bit) ((value) &= ~(1UL << (bit)))
+#define bitWrite(value, bit, bitvalue) (bitvalue ? bitSet(value, bit) : bitClear(value, bit))
+
+#define CS_ADF0_HIGH palSetLine(LINE_LO_SEL)
+#define CS_ADF1_HIGH palSetLine(LINE_LO_SEL)
+
+#define CS_ADF0_LOW palClearLine(LINE_LO_SEL)
+#define CS_ADF1_LOW palClearLine(LINE_LO_SEL)
+
+//uint32_t t_R[6] = {0x320000, 0x8008011, 0x4E42, 0x4B3,0x8C803C , 0x580005} ; //25 MHz ref
+#ifdef TINYSA4_PROTO
+uint32_t registers[6] = {0xC80000, 0x8008011, 0x1800C642, 0x48963,0xA5003C , 0x580005} ; //10 MHz ref
+#else
+uint32_t registers[6] = {0xA00000, 0x8000011, 0x4E42, 0x4B3,0xDC003C , 0x580005} ; //10 MHz ref
+#endif
+int debug = 0;
+ioline_t ADF4351_LE[2] = { LINE_LO_SEL, LINE_LO_SEL};
+//int ADF4351_Mux = 7;
+
+int ADF4351_frequency_changed = false;
+
+//#define DEBUG(X) // Serial.print( X )
+//#define DEBUGLN(X) Serial.println( X )
+//#define DEBUGFLN(X,Y) Serial.println( X,Y )
+//#define DEBUGF(X,Y) Serial.print( X,Y )
+#define DEBUG(X)
+#define DEBUGLN(X)
+
+#ifdef TINYSA4_PROTO
+#define XTAL 29999960
+#else
+#define XTAL 26000000
+#endif
+//double RFout; //Output freq in MHz
+uint64_t PFDRFout[6] = {XTAL,XTAL,XTAL,10000000,10000000,10000000}; //Reference freq in MHz
+//uint64_t Chrystal[6] = {XTAL,XTAL,XTAL,10000000,10000000,10000000};
+//double FRACF; // Temp
+
+volatile int64_t
+ INTA, // Temp
+ ADF4350_modulo = 60, // Linked to spur table!!!!!
+ MOD,
+ target_freq,
+ FRAC; //Temp
+
+uint8_t OutputDivider; // Temp
+uint8_t lock=2; //Not used
+static int old_R = 0;
+
+// Lock = A4
+
+void ADF4351_Setup(void)
+{
+// palSetPadMode(GPIOA, 1, PAL_MODE_OUTPUT_PUSHPULL );
+// palSetPadMode(GPIOA, 2, PAL_MODE_OUTPUT_PUSHPULL );
+
+// SPI3_CLK_HIGH;
+// SPI3_SDI_HIGH;
+ CS_ADF0_HIGH;
+// CS_ADF1_HIGH;
+
+ // bitSet (registers[2], 17); // R set to 8
+// bitClear (registers[2], 14); // R set to 8
+
+// while(1) {
+//
+
+ ADF4351_R_counter(1);
+
+ ADF4351_CP(0);
+
+ ADF4351_fastlock(1); // Fastlock enabled
+ ADF4351_csr(1); //Cycle slip enabled
+
+ ADF4351_set_frequency(0,200000000);
+
+ ADF4351_mux(2); // No led
+// ADF4351_mux(6); // Show lock on led
+
+// ADF4351_set_frequency(1,150000000,0);
+// ADF4351_Set(0);
+// ADF4351_Set(1);
+// chThdSleepMilliseconds(1000);
+// }
+// bitSet (registers[2], 17); // R set to 8
+// bitClear (registers[2], 14); // R set to 8
+// for (int i=0; i<6; i++) pinMode(ADF4351_LE[i], OUTPUT); // Setup pins
+// for (int i=0; i<6; i++) digitalWrite(ADF4351_LE[i], HIGH);
+// pinMode(ADF4351_Mux, INPUT);
+// SPI.begin(); // Init SPI bus
+// SPI.beginTransaction(SPISettings(8000000, MSBFIRST, SPI_MODE0));
+ //SPI.setDataMode(SPI_MODE0); // CPHA = 0 Clock positive
+ //SPI.setBitOrder(MSBFIRST);
+}
+
+void ADF4351_WriteRegister32(int channel, const uint32_t value)
+{
+ registers[value & 0x07] = value;
+ for (int i = 3; i >= 0; i--) shiftOut((value >> (8 * i)) & 0xFF);
+ palSetLine(ADF4351_LE[channel]);
+ my_microsecond_delay(1); // Must
+ palClearLine(ADF4351_LE[channel]);
+}
+
+void ADF4351_Set(int channel)
+{
+ set_SPI_mode(SPI_MODE_SI);
+ SPI_BR_SET(SI4432_SPI, ADF_SPI_SPEED);
+// my_microsecond_delay(1);
+ palClearLine(ADF4351_LE[channel]);
+// my_microsecond_delay(1);
+
+ for (int i = 5; i >= 0; i--) {
+ ADF4351_WriteRegister32(channel, registers[i]);
+ }
+ SPI_BR_SET(SI4432_SPI, SI4432_SPI_SPEED);
+}
+
+#if 0
+void ADF4351_disable_output(void)
+{
+ bitClear (registers[4], 5); // main output
+ ADF4351_Set(0);
+}
+
+void ADF4351_enable_output(void)
+{
+ bitSet (registers[4], 5); // main output
+ ADF4351_Set(0);
+}
+#endif
+
+static freq_t prev_actual_freq = 0;
+
+void ADF4351_force_refresh(void) {
+ prev_actual_freq = 0;
+}
+
+void ADF4351_modulo(int m)
+{
+ ADF4350_modulo = m;
+// ADF4351_set_frequency(0, (uint64_t)prev_actual_freq);
+}
+
+uint64_t ADF4351_set_frequency(int channel, uint64_t freq) // freq / 10Hz
+{
+// freq -= 71000;
+// SI4463_set_gpio(3,GPIO_HIGH);
+
+// uint32_t offs = ((freq / 1000)* ( 0) )/ 1000;
+ uint32_t offs = 0;
+ uint64_t actual_freq = ADF4351_prepare_frequency(channel,freq + offs);
+// SI4463_set_gpio(3,GPIO_LOW);
+ if (actual_freq != prev_actual_freq) {
+//START_PROFILE;
+ ADF4351_frequency_changed = true;
+ ADF4351_Set(channel);
+ prev_actual_freq = actual_freq;
+ }
+//STOP_PROFILE;
+ return actual_freq;
+}
+
+void ADF4351_spur_mode(int S)
+{
+ if (S & 1) {
+ bitSet (registers[2], 29); // R set to 8
+ } else {
+ bitClear (registers[2], 29); // R set to 8
+ }
+ if (S & 2)
+ bitSet (registers[2], 30); // R set to 8
+ else
+ bitClear (registers[2], 30); // R set to 8
+ ADF4351_Set(0);
+}
+
+void ADF4351_R_counter(int R)
+{
+ if (R == old_R)
+ return;
+ old_R = R;
+ int dbl = false;
+ if (R < 0) {
+ dbl = true;
+ R = -R;
+ }
+ if (R<1)
+ return;
+ if (dbl) {
+ bitSet (registers[2], 25); // Reference doubler
+ } else {
+ bitClear (registers[2], 25); // Reference doubler
+ }
+ for (int channel=0; channel < 6; channel++) {
+ PFDRFout[channel] = (config.setting_frequency_30mhz * (dbl?2:1)) / R;
+ }
+ clear_frequency_cache(); // When R changes the possible frequencies will change
+ registers[2] &= ~ (((unsigned long)0x3FF) << 14);
+ registers[2] |= (((unsigned long)R) << 14);
+ ADF4351_Set(0);
+}
+
+void ADF4351_mux(int R)
+{
+ registers[2] &= ~ (((unsigned long)0x7) << 26);
+ registers[2] |= (((unsigned long)R & (unsigned long)0x07) << 26);
+ ADF4351_Set(0);
+}
+
+void ADF4351_csr(int c)
+{
+ registers[3] &= ~ (((unsigned long)0x1) << 18);
+ registers[3] |= (((unsigned long)c & (unsigned long)0x01) << 18);
+ ADF4351_Set(0);
+}
+
+void ADF4351_fastlock(int c)
+{
+ registers[3] &= ~ (((unsigned long)0x3) << 15);
+ registers[3] |= (((unsigned long)c & (unsigned long)0x03) << 15);
+ ADF4351_Set(0);
+}
+
+void ADF4351_CP(int p)
+{
+ registers[2] &= ~ (((unsigned long)0xF) << 9);
+ registers[2] |= (((unsigned long)p) << 9);
+ ADF4351_Set(0);
+}
+
+void ADF4351_drive(int p)
+{
+ registers[4] &= ~ (((unsigned long)0x3) << 3);
+ registers[4] |= (((unsigned long)p) << 3);
+ ADF4351_Set(0);
+}
+
+void ADF4351_aux_drive(int p)
+{
+ registers[4] &= ~ (((unsigned long)0x3) << 6);
+ registers[4] |= (((unsigned long)p) << 6);
+ ADF4351_Set(0);
+}
+#if 0
+static uint32_t gcd(uint32_t x, uint32_t y)
+{
+ uint32_t z;
+ while (y != 0) {
+ z = x % y;
+ x = y;
+ y = z;
+ }
+ return x;
+}
+#endif
+
+#if 0
+#endif
+
+uint64_t ADF4351_prepare_frequency(int channel, uint64_t freq) // freq / 10Hz
+{
+ target_freq = freq;
+ if (freq >= 2200000000) {
+ OutputDivider = 1;
+ bitWrite (registers[4], 22, 0);
+ bitWrite (registers[4], 21, 0);
+ bitWrite (registers[4], 20, 0);
+ } else if (freq >= 1100000000) {
+ OutputDivider = 2;
+ bitWrite (registers[4], 22, 0);
+ bitWrite (registers[4], 21, 0);
+ bitWrite (registers[4], 20, 1);
+ } else if (freq >= 550000000) {
+ OutputDivider = 4;
+ bitWrite (registers[4], 22, 0);
+ bitWrite (registers[4], 21, 1);
+ bitWrite (registers[4], 20, 0);
+ } else if (freq >= 275000000) {
+ OutputDivider = 8;
+ bitWrite (registers[4], 22, 0);
+ bitWrite (registers[4], 21, 1);
+ bitWrite (registers[4], 20, 1);
+ } else { // > 137500000
+ OutputDivider = 16;
+ bitWrite (registers[4], 22, 1);
+ bitWrite (registers[4], 21, 0);
+ bitWrite (registers[4], 20, 0);
+ }
+
+ volatile uint64_t PFDR = PFDRFout[channel];
+ INTA = (((uint64_t)freq) * OutputDivider) / PFDR;
+ MOD = ADF4350_modulo;
+ uint64_t f_int = INTA *(uint64_t) MOD;
+ uint64_t f_target = ((((uint64_t)freq) * OutputDivider) * (uint64_t) MOD) / PFDR;
+ FRAC = f_target - f_int;
+ if (FRAC >= MOD) {
+ FRAC -= MOD;
+ INTA++;
+ }
+#if 0
+ while (FRAC > 4095 || MOD > 4095) {
+ FRAC = FRAC >> 1;
+ MOD = MOD >> 1;
+ // Serial.println( "MOD/FRAC reduced");
+ }
+#endif
+#if 0
+ uint32_t reduce = gcd(MOD, FRAC);
+ if (reduce>1) {
+ FRAC /= reduce;
+ MOD /= reduce;
+ if (MOD == 1)
+ MOD=2;
+ }
+#endif
+ uint64_t actual_freq = (PFDR *(INTA * MOD +FRAC))/OutputDivider / MOD;
+#if 0
+ volatile int max_delta = PFDRFout[channel]/OutputDivider/MOD/100;
+ if (actual_freq < freq - max_delta || actual_freq > freq + max_delta ){
+ while(1)
+ my_microsecond_delay(10);
+ }
+ max_delta = freq - actual_freq;
+ if (max_delta > 200000 || max_delta < -200000 || freq == 0) {
+ while(1)
+ my_microsecond_delay(10);
+ }
+#endif
+ if (FRAC >= MOD ){
+ while(1)
+ my_microsecond_delay(10);
+ }
+
+ registers[0] = 0;
+ registers[0] = INTA << 15; // OK
+ registers[0] = registers[0] + (FRAC << 3);
+ if (MOD == 1) MOD = 2;
+ registers[1] = 0;
+ registers[1] = MOD << 3;
+ registers[1] = registers[1] + 1 ; // restore address "001"
+ bitSet (registers[1], 27); // Prescaler at 8/9
+ return actual_freq;
+}
+
+#endif
+
+void ADF4351_enable(int s)
+{
+ if (s)
+ bitClear(registers[4], 11); // Inverse logic!!!!!
+ else
+ bitSet(registers[4], 11);
+ ADF4351_Set(0);
+}
+
+void ADF4351_enable_aux_out(int s)
+{
+ if (s)
+ bitSet(registers[4], 8);
+ else
+ bitClear(registers[4], 8);
+ ADF4351_Set(0);
+}
+
+void ADF4351_enable_out(int s)
+{
+ if (s) {
+ bitClear(registers[2], 11); // Disable VCO power down
+ bitClear(registers[2], 5); // Disable power down
+ bitSet(registers[4], 5); // Enable output
+ } else {
+ bitClear(registers[4], 5); // Disable output
+ bitSet(registers[2], 5); // Enable power down
+ bitSet(registers[2], 11); // Enable VCO power down
+ }
+ ADF4351_Set(0);
+}
+
+
+// ------------------------------ SI4463 -------------------------------------
+
+
+int SI4463_frequency_changed = false;
+int SI4463_offset_changed = false;
+int SI4463_offset_value = 0;
+
+static int SI4463_band = -1;
+static int64_t SI4463_outdiv = -1;
+//static freq_t SI4463_prev_freq = 0;
+//static float SI4463_step_size = 100; // Will be recalculated once used
+static uint8_t SI4463_channel = 0;
+static uint8_t SI4463_in_tx_mode = false;
+int SI4463_R = 5;
+static int SI4463_output_level = 0x20;
+
+static si446x_state_t SI4463_get_state(void);
+static void SI4463_set_state(si446x_state_t);
+
+
+#define MIN_DELAY 2
+#define my_deleted_delay(T)
+
+#include
+
+#define SI4463_READ_CTS (palReadLine(LINE_RX_CTS))
+
+static int SI4463_wait_for_cts(void)
+{
+// set_SPI_mode(SPI_MODE_SI);
+ while (!SI4463_READ_CTS) {
+// chThdSleepMicroseconds(100);
+ my_microsecond_delay(1);
+ }
+ return 1;
+}
+
+#if 0 // not used
+static void SI4463_write_byte(uint8_t ADR, uint8_t DATA)
+{
+ set_SPI_mode(SPI_MODE_SI);
+ SI_CS_LOW;
+ ADR |= 0x80 ; // RW = 1
+ shiftOut( ADR );
+ shiftOut( DATA );
+ SI_CS_HIGH;
+}
+
+static void SI4463_write_buffer(uint8_t ADR, uint8_t *DATA, int len)
+{
+ set_SPI_mode(SPI_MODE_SI);
+ SI_CS_LOW;
+ ADR |= 0x80 ; // RW = 1
+ shiftOut( ADR );
+ while (len-- > 0)
+ shiftOut( *(DATA++) );
+ SI_CS_HIGH;
+}
+#endif
+
+static uint8_t SI4463_read_byte( uint8_t ADR )
+{
+ uint8_t DATA ;
+ set_SPI_mode(SPI_MODE_SI);
+ SI_CS_LOW;
+ shiftOut( ADR );
+ DATA = shiftIn();
+ SI_CS_HIGH;
+ return DATA ;
+}
+
+static uint8_t SI4463_get_response(void* buff, uint8_t len)
+{
+ uint8_t cts = 0;
+// set_SPI_mode(SPI_MODE_SI);
+ cts = SI4463_READ_CTS;
+ if (!cts) {
+ return false;
+ }
+// __disable_irq();
+ SI_CS_LOW;
+ shiftOut( SI446X_CMD_READ_CMD_BUFF );
+ cts = (shiftIn() == 0xFF);
+ if (cts)
+ {
+ // Get response data
+ for(uint8_t i=0;i>8),
+ len,
+ (uint8_t)prop
+ };
+
+ // Copy values into data, starting at index 4
+ memcpy(data + 4, values, len);
+
+ SI4463_do_api(data, len + 4, NULL, 0);
+}
+#endif
+
+#include "SI446x_cmd.h"
+
+#if 0
+#include "SI4463_radio_config.h"
+static const uint8_t SI4463_config[] = RADIO_CONFIGURATION_DATA_ARRAY;
+#endif
+
+#ifdef __SI4468__
+#include "radio_config_Si4468_undef.h"
+#undef RADIO_CONFIGURATION_DATA_ARRAY
+#include "radio_config_Si4468_default.h"
+
+#define GLOBAL_GPIO_PIN_CFG 0x13, 0x07, 0x08, 0x00, 0x00, 0x00, 0x00, 0x00
+#define GLOBAL_CLK_CFG 0x11, 0x00, 0x01, 0x01, 0x00
+
+//#undef RF_MODEM_RAW_CONTROL_10 // Override RSSI averaging
+//#define RF_MODEM_RAW_CONTROL_10 0x11, 0x20, 0x0A, 0x45, 0x03, 0x00, 0x00, 0x01, 0x00, 0xFF, 0x06, 0x18, 0x10, 0x40
+
+//#undef RF_MODEM_AGC_CONTROL_1
+//#define RF_MODEM_AGC_CONTROL_1 0x11, 0x20, 0x01, 0x35, 0x92 // Override AGC gain increase
+#undef RF_MODEM_AGC_CONTROL_1
+#define RF_MODEM_AGC_CONTROL_1 0x11, 0x20, 0x01, 0x35, 0xE0 + 0x10 + 0x08 // slow AGC
+//#undef RF_MODEM_RSSI_JUMP_THRESH_4
+//#define RF_MODEM_RSSI_JUMP_THRESH_4 0x11, 0x20, 0x04, 0x4B, 0x06, 0x09, 0x10, 0x45 // Increase RSSI reported value with 2.5dB
+
+#undef RF_GPIO_PIN_CFG
+#define RF_GPIO_PIN_CFG GLOBAL_GPIO_PIN_CFG
+#undef RF_GLOBAL_CLK_CFG_1
+#define RF_GLOBAL_CLK_CFG_1 GLOBAL_CLK_CFG
+
+// Remember to change RF_MODEM_AFC_LIMITER_1_3_1 !!!!!!!!!
+
+static const uint8_t SI4468_config[] = RADIO_CONFIGURATION_DATA_ARRAY;
+#endif
+
+// Set new state
+static void SI4463_set_state(si446x_state_t newState)
+{
+ uint8_t data[] = {
+ SI446X_CMD_CHANGE_STATE,
+ newState
+ };
+ SI4463_do_api(data, sizeof(data), NULL, 0);
+}
+
+static uint8_t gpio_state[4] = { 7,8,0,0 };
+
+void SI4463_refresh_gpio(void)
+{
+#ifndef TINYSA4_PROTO // Force clock to max frequency for ADF
+ uint8_t data[] =
+ {
+ 0x11, 0x00, 0x01, 0x01, 0x40 // GLOBAL_CLK_CFG Enable divided clock
+ };
+ SI4463_do_api(data, sizeof(data), NULL, 0);
+#endif
+ uint8_t data2[] =
+ {
+ 0x13, gpio_state[0], gpio_state[1], gpio_state[2], gpio_state[3], 0, 0, 0
+ };
+ SI4463_do_api(data2, sizeof(data2), NULL, 0);
+}
+
+void SI4463_set_gpio(int i, int s)
+{
+ gpio_state[i] = s;
+#if 0 // debug gpio
+ gpio_state[2] = 3;
+ gpio_state[3] = 2;
+#endif
+ SI4463_refresh_gpio();
+}
+
+#if 0
+static void SI4463_clear_FIFO(void)
+{
+ // 'static const' saves 20 bytes of flash here, but uses 2 bytes of RAM
+ static const uint8_t clearFifo[] = {
+ SI446X_CMD_FIFO_INFO,
+ SI446X_FIFO_CLEAR_RX | SI446X_FIFO_CLEAR_TX
+ };
+ SI4463_do_api((uint8_t*)clearFifo, sizeof(clearFifo), NULL, 0);
+}
+#endif
+
+void SI4463_set_output_level(int t)
+{
+ SI4463_output_level = t;
+ if (SI4463_in_tx_mode)
+ SI4463_start_tx(0); // Refresh output level
+}
+void SI4463_start_tx(uint8_t CHANNEL)
+{
+// volatile si446x_state_t s;
+#if 0
+ s = SI4463_get_state();
+ if (s == SI446X_STATE_RX){
+ SI4463_set_state(SI446X_STATE_READY);
+ my_microsecond_delay(200);
+ s = SI4463_get_state();
+ if (s != SI446X_STATE_READY){
+ my_microsecond_delay(1000);
+ }
+ }
+#endif
+#if 1
+ {
+ uint8_t data[] =
+ {
+ 0x11, 0x20, 0x01, 0x00,
+ 0x00, // CW mode
+ };
+ SI4463_do_api(data, sizeof(data), NULL, 0);
+ }
+#endif
+#if 1
+ {
+ uint8_t data[] =
+ {
+ 0x11, 0x22, 0x04, 0x00, // PA_MODE
+ 0x08, // Coarse PA mode and class E PA
+ (uint8_t)SI4463_output_level, // Level
+ 0x00, // Duty
+ 0x00 // Ramp
+ };
+ SI4463_do_api(data, sizeof(data), NULL, 0);
+ }
+#endif
+// retry:
+ {
+ uint8_t data[] =
+ {
+ SI446X_CMD_ID_START_TX,
+ CHANNEL,
+ 0, // Stay in TX state
+ 0, // TX len
+ 0, // TX len
+ 0,// TX delay
+ 0// Num repeat
+ };
+ SI4463_do_api(data, sizeof(data), NULL, 0);
+ }
+ SI4463_in_tx_mode = true;
+ my_microsecond_delay(1000);
+#if 0
+ s = SI4463_get_state();
+ if (s != SI446X_STATE_TX){
+ my_microsecond_delay(1000);
+ goto retry;
+ }
+#endif
+
+}
+
+
+void SI4463_start_rx(uint8_t CHANNEL)
+{
+ volatile si446x_state_t s = SI4463_get_state();
+ if (s == SI446X_STATE_TX){
+ SI4463_set_state(SI446X_STATE_READY);
+ }
+ SI4463_refresh_gpio();
+#if 0
+ {
+ uint8_t data[] =
+ {
+ 0x11, 0x20, 0x01, 0x00,
+ 0x0A, // Restore 2FSK mode
+ };
+ SI4463_do_api(data, sizeof(data), NULL, 0);
+ }
+#endif
+ uint8_t data[] = {
+ SI446X_CMD_ID_START_RX,
+ CHANNEL,
+ 0,
+ 0,
+ 0,
+ 0,// 8,
+ 0,// SI446X_CMD_START_RX_ARG_NEXT_STATE2_RXVALID_STATE_ENUM_RX,
+ 0, //SI446X_CMD_START_RX_ARG_NEXT_STATE3_RXINVALID_STATE_ENUM_RX
+ };
+//retry:
+ SI4463_do_api(data, sizeof(data), NULL, 0);
+
+#if 0
+ si446x_state_t s = SI4463_get_state();
+ if (s != SI446X_STATE_RX) {
+ my_microsecond_delay(1000);
+ goto retry;
+ }
+#endif
+ SI4463_in_tx_mode = false;
+}
+
+
+
+void SI4463_short_start_rx(void)
+{
+ uint8_t data[] = {
+ SI446X_CMD_ID_START_RX,
+ };
+ SI4463_do_api(data, sizeof(data), NULL, 0);
+ SI4463_in_tx_mode = false;
+}
+
+void SI4463_clear_int_status(void)
+{
+ uint8_t data[9] = {
+ SI446X_CMD_ID_GET_INT_STATUS
+ };
+ SI4463_do_api(data, 1, data, SI446X_CMD_REPLY_COUNT_GET_INT_STATUS);
+
+}
+
+void set_calibration_freq(int ref)
+{
+#ifndef TINYSA4_PROTO
+ ref = 0; // <--------------------- DISABLED FOR PROTOTYPE!!!!!!!!!!!!!!!!!!!!!!!!!
+#endif
+
+ if (ref >= 0) {
+ SI4463_set_gpio(0, 7); // GPIO 0 dic clock out
+
+ uint8_t data2[5] = {
+ 0x11, 0x00, 0x01, 0x01, 0x40 // GLOBAL_CLK_CFG Clock config
+ };
+ data2[4] |= ref<<3;
+ SI4463_do_api(data2, 5, NULL, 0);
+ } else {
+ SI4463_set_gpio(0, 1); // stop clock out
+ }
+}
+
+si446x_info_t SI4463_info;
+
+void Si446x_getInfo(si446x_info_t* info)
+{
+ uint8_t data[8] = {
+ SI446X_CMD_PART_INFO
+ };
+ SI4463_do_api(data, 1, data, 8);
+
+ info->chipRev = data[0];
+ info->part = (data[1]<<8) | data[2];
+ info->partBuild = data[3];
+ info->id = (data[4]<<8) | data[5];
+ info->customer = data[6];
+ info->romId = data[7];
+
+
+ data[0] = SI446X_CMD_FUNC_INFO;
+ SI4463_do_api(data, 1, data, 6);
+
+ info->revExternal = data[0];
+ info->revBranch = data[1];
+ info->revInternal = data[2];
+ info->patch = (data[3]<<8) | data[4];
+ info->func = data[5];
+}
+#ifdef notused
+static uint8_t SI4463_get_device_status(void)
+{
+ uint8_t data[2] =
+ {
+ SI446X_CMD_ID_REQUEST_DEVICE_STATE, 0
+ };
+ SI4463_do_api(data, 1, data, SI446X_CMD_REPLY_COUNT_REQUEST_DEVICE_STATE);
+ return(data[0]);
+}
+#endif
+
+
+// Read a fast response register
+uint8_t getFRR(uint8_t reg)
+{
+ set_SPI_mode(SPI_MODE_SI);
+ return SI4463_read_byte(reg);
+}
+
+// Get current radio state
+static si446x_state_t SI4463_get_state(void)
+{
+#if 0
+#if 0
+ uint8_t data[2] = {
+ SI446X_CMD_REQUEST_DEVICE_STATE
+ };
+ SI4463_do_api(data, 1, data, 2);
+ uint8_t state = data[0] & 0x0F;
+#endif
+ uint8_t state = SI4463_get_device_status();
+#else
+again:
+ SI4463_wait_for_cts();
+ uint8_t state = getFRR(SI446X_CMD_READ_FRR_B);
+#endif
+ if (state == 255) {
+ my_microsecond_delay(100);
+ goto again;
+ }
+ if(state == SI446X_STATE_TX_TUNE)
+ state = SI446X_STATE_TX;
+ else if(state == SI446X_STATE_RX_TUNE)
+ state = SI446X_STATE_RX;
+ else if(state == SI446X_STATE_READY2)
+ state = SI446X_STATE_READY;
+ else
+ state = state;
+ return (si446x_state_t)state;
+}
+
+
+void set_RSSI_comp(void)
+{
+ // Set properties: RF_MODEM_RSSI_COMP_1
+ // Number of properties: 1
+ // Group ID: 0x20
+ // Start ID: 0x4E
+ // Default values: 0x40,
+ // Descriptions:
+ // MODEM_RSSI_JUMP_THRESH - Configures the RSSI Jump Detection threshold.
+ // MODEM_RSSI_CONTROL - Control of the averaging modes and latching time for reporting RSSI value(s).
+ // MODEM_RSSI_CONTROL2 - RSSI Jump Detection control.
+ // MODEM_RSSI_COMP - RSSI compensation value.
+ //
+ // #define RF_MODEM_RSSI_COMP_1 0x11, 0x20, 0x01, 0x4E, 0x40
+
+ uint8_t data[5] = {
+ 0x11,
+ 0x20,
+ 0x01,
+ 0x4E,
+ 0x40
+ };
+ SI4463_do_api(data, sizeof(data), NULL, 0);
+
+}
+
+int SI4463_offset_active = false;
+
+void si_set_offset(int16_t offset)
+{
+ // Set properties: MODEM_FREQ_OFFSET
+ // Number of properties: 2
+ // Group ID: 0x20
+ // Start ID: 0x0d
+ // Default values: 0x00, 0x00
+ // Descriptions:
+ // MODEM_FREQ_OFFSET1 - High byte of the offset
+ // MODEM_FREQ_OFFSET2 - Low byte of the offset
+ //
+ // #define RF_MODEM_RSSI_COMP_1 0x11, 0x20, 0x01, 0x4E, 0x40
+ SI4463_offset_value = offset;
+ uint8_t data[] = {
+ 0x11,
+ 0x20,
+ 0x02,
+ 0x0d,
+ (uint8_t) ((offset>>8) & 0xff),
+ (uint8_t) ((offset) & 0xff)
+ };
+ SI4463_do_api(data, sizeof(data), NULL, 0);
+ SI4463_offset_changed = true;
+ SI4463_offset_active = (offset != 0);
+}
+
+void si_fm_offset(int16_t offset)
+{
+ // Set properties: MODEM_FREQ_OFFSET
+ // Number of properties: 2
+ // Group ID: 0x20
+ // Start ID: 0x0d
+ // Default values: 0x00, 0x00
+ // Descriptions:
+ // MODEM_FREQ_OFFSET1 - High byte of the offset
+ // MODEM_FREQ_OFFSET2 - Low byte of the offset
+ //
+ // #define RF_MODEM_RSSI_COMP_1 0x11, 0x20, 0x01, 0x4E, 0x40
+ offset = SI4463_offset_value + offset;
+ uint8_t data[] = {
+ 0x11,
+ 0x20,
+ 0x02,
+ 0x0d,
+ (uint8_t) ((offset>>8) & 0xff),
+ (uint8_t) ((offset) & 0xff)
+ };
+ SI4463_do_api(data, sizeof(data), NULL, 0);
+ SI4463_offset_changed = true;
+ SI4463_offset_active = (offset != 0);
+}
+
+
+
+#ifdef __FAST_SWEEP__
+extern deviceRSSI_t age[POINTS_COUNT];
+static int buf_index = 0;
+static bool buf_read = false;
+
+void SI446x_Fill(int s, int start)
+{
+ (void)s;
+#if 0
+ set_SPI_mode(SPI_MODE_SI);
+ SI4432_Sel = s;
+ uint16_t sel = SI_nSEL[SI4432_Sel];
+#endif
+
+ uint32_t t = setting.additional_step_delay_us;
+ systime_t measure = chVTGetSystemTimeX();
+ __disable_irq();
+
+#if 1
+ int i = start;
+ uint8_t data[3];
+ do {
+again:
+ data[0] = SI446X_CMD_GET_MODEM_STATUS;
+ data[1] = 0xFF;
+ SI4463_do_api(data, 1, data, 3); // TODO no clear of interrups
+ if (data[2] == 0) goto again;
+ if (data[2] == 255) goto again;
+ age[i]=(char)data[2];
+ if (++i >= sweep_points) break;
+ if (t)
+ my_microsecond_delay(t);
+ } while(1);
+#else
+ shiftInBuf(sel, SI4432_REG_RSSI, &age[start], sweep_points - start, t);
+#endif
+ __enable_irq();
+
+ setting.measure_sweep_time_us = (chVTGetSystemTimeX() - measure)*100;
+ buf_index = start; // Is used to skip 1st entry during level triggering
+ buf_read = true;
+}
+#endif
+
+
+
+int16_t Si446x_RSSI(void)
+{
+#ifdef __FAST_SWEEP__
+ if (buf_read) {
+ if (buf_index == sweep_points-1)
+ buf_read = false;
+ return DEVICE_TO_PURE_RSSI(age[buf_index++]);
+ }
+#endif
+
+ int i = setting.repeat;
+ int32_t RSSI_RAW = 0;
+ do{
+ // if (MODE_INPUT(setting.mode) && RSSI_R
+ uint8_t data[3] = {
+ SI446X_CMD_GET_MODEM_STATUS,
+ 0xFF
+ };
+ if (SI4432_step_delay && (ADF4351_frequency_changed || SI4463_frequency_changed)) {
+ my_microsecond_delay(SI4432_step_delay * ((setting.R == 0 && old_R > 5 ) ? 8 : 1));
+ ADF4351_frequency_changed = false;
+ SI4463_frequency_changed = false;
+ } else if (SI4432_offset_delay && SI4463_offset_changed) {
+ my_microsecond_delay(SI4432_offset_delay);
+ ADF4351_frequency_changed = false;
+ SI4463_offset_changed = false;
+ }
+#define SAMPLE_COUNT 1
+ int j = SAMPLE_COUNT; //setting.repeat;
+ int RSSI_RAW_ARRAY[3];
+ do{
+ again:
+ __disable_irq();
+ data[0] = SI446X_CMD_GET_MODEM_STATUS;
+ data[1] = 0xFF;
+ SI4463_do_api(data, 2, data, 3); // TODO no clear of interrupts
+ __enable_irq();
+
+ if (data[2] == 255) {
+ my_microsecond_delay(10);
+ goto again;
+ }
+#if 0
+ if (data[2] == 0) {
+// my_microsecond_delay(10);
+ goto again;
+ }
+#endif
+ RSSI_RAW_ARRAY[--j] = data[2];
+ if (j == 0) break;
+// my_microsecond_delay(20);
+ }while(1);
+#if SAMPLE_COUNT == 3
+ int t;
+ if (RSSI_RAW_ARRAY[0] > RSSI_RAW_ARRAY[1]) {
+ t = RSSI_RAW_ARRAY[1];
+ RSSI_RAW_ARRAY[1] = RSSI_RAW_ARRAY[0];
+ RSSI_RAW_ARRAY[0] = t;
+ }
+ if (RSSI_RAW_ARRAY[1] > RSSI_RAW_ARRAY[2]) {
+ t = RSSI_RAW_ARRAY[2];
+ RSSI_RAW_ARRAY[2] = RSSI_RAW_ARRAY[1];
+ RSSI_RAW_ARRAY[1] = t;
+ }
+ if (RSSI_RAW_ARRAY[0] > RSSI_RAW_ARRAY[1]) {
+ t = RSSI_RAW_ARRAY[1];
+ RSSI_RAW_ARRAY[1] = RSSI_RAW_ARRAY[0];
+ RSSI_RAW_ARRAY[0] = t;
+ }
+
+ RSSI_RAW += DEVICE_TO_PURE_RSSI(RSSI_RAW_ARRAY[1]);
+#else
+ RSSI_RAW += DEVICE_TO_PURE_RSSI(RSSI_RAW_ARRAY[0]);
+#endif
+ if (--i <= 0) break;
+// my_microsecond_delay(100);
+ }while(1);
+
+ if (setting.repeat > 1)
+ RSSI_RAW = RSSI_RAW / setting.repeat;
+
+ return RSSI_RAW;
+}
+
+
+
+void SI446x_set_AGC_LNA(uint8_t v)
+{
+
+ uint8_t data[2] = {
+ 0xd0, // AGC_OVERRIDE
+ v
+ };
+ SI4463_do_api(data, sizeof(data), NULL, 0);
+#if 0
+ if (v == 0) {
+ data[0] = 0xd1; // Read AGC?????? NO
+ SI4463_do_api(data, 1, data, 1);
+ }
+#endif
+}
+
+
+#ifdef notused
+// Do an ADC conversion
+static uint16_t getADC(uint8_t adc_en, uint8_t adc_cfg, uint8_t part)
+{
+ uint8_t data[6] = {
+ SI446X_CMD_GET_ADC_READING,
+ adc_en,
+ adc_cfg
+ };
+ SI4463_do_api(data, 3, data, 6);
+ return (data[part]<<8 | data[part + 1]);
+}
+#endif
+
+#ifndef __SI4468__
+// -------------- 0.2 kHz ----------------------------
+
+#undef RF_MODEM_TX_RAMP_DELAY_8_1
+#undef RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1
+#undef RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1
+#undef RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1
+
+#define RF_MODEM_TX_RAMP_DELAY_12_1 0x11, 0x20, 0x0C, 0x18, 0x01, 0x00, 0x08, 0x03, 0x80, 0x00, 0xF0, 0x10, 0x74, 0xE8, 0x00, 0xA9
+// #define RF_MODEM_TX_RAMP_DELAY_8_1 0x11, 0x20, 0x08, 0x18, 0x01, 0x00, 0x08, 0x03, 0x80, 0x00, 0xF0, 0x11
+#define RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1 0x11, 0x21, 0x0C, 0x00, 0x0C, 0x01, 0xE4, 0xB9, 0x86, 0x55, 0x2B, 0x0B, 0xF8, 0xEF, 0xEF, 0xF2
+//#define RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1 0x11, 0x21, 0x0C, 0x00, 0xC6, 0xC1, 0xB2, 0x9C, 0x80, 0x63, 0x47, 0x2F, 0x1B, 0x0E, 0x05, 0x00
+#define RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1 0x11, 0x21, 0x0C, 0x0C, 0xF8, 0xFC, 0x05, 0x00, 0xFF, 0x0F, 0x0C, 0x01, 0xE4, 0xB9, 0x86, 0x55
+//#define RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1 0x11, 0x21, 0x0C, 0x0C, 0xFF, 0xFE, 0x00, 0x00, 0x00, 0x0F, 0xC6, 0xC1, 0xB2, 0x9C, 0x80, 0x63
+#define RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1 0x11, 0x21, 0x0C, 0x18, 0x2B, 0x0B, 0xF8, 0xEF, 0xEF, 0xF2, 0xF8, 0xFC, 0x05, 0x00, 0xFF, 0x0F
+//#define RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1 0x11, 0x21, 0x0C, 0x18, 0x47, 0x2F, 0x1B, 0x0E, 0x05, 0x00, 0xFF, 0xFE, 0x00, 0x00, 0x00, 0x0F
+
+#define RF_MODEM_RAW_SEARCH2_2_1 0x11, 0x20, 0x02, 0x50, 0x94, 0x0A
+
+#define RF_GLOBAL_CONFIG_1_1 0x11, 0x00, 0x01, 0x03, 0x20
+
+uint8_t SI4463_RBW_02kHz[] =
+{
+ 6, RF_MODEM_RAW_SEARCH2_2_1, \
+ 5, RF_GLOBAL_CONFIG_1_1, \
+ 0x0C, RF_MODEM_TX_RAMP_DELAY_12_1, \
+ 0x10, RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1, \
+ 0x10, RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1, \
+ 0x10, RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1, \
+ 0x00
+};
+// -------------- 1kHz ----------------------------
+
+#undef RF_MODEM_TX_RAMP_DELAY_8_1
+#undef RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1
+#undef RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1
+#undef RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1
+
+#define RF_MODEM_TX_RAMP_DELAY_8_1 0x11, 0x20, 0x08, 0x18, 0x01, 0x00, 0x08, 0x03, 0x80, 0x00, 0xF0, 0x11
+#define RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1 0x11, 0x21, 0x0C, 0x00, 0xC6, 0xC1, 0xB2, 0x9C, 0x80, 0x63, 0x47, 0x2F, 0x1B, 0x0E, 0x05, 0x00
+#define RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1 0x11, 0x21, 0x0C, 0x0C, 0xFF, 0xFE, 0x00, 0x00, 0x00, 0x0F, 0xC6, 0xC1, 0xB2, 0x9C, 0x80, 0x63
+#define RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1 0x11, 0x21, 0x0C, 0x18, 0x47, 0x2F, 0x1B, 0x0E, 0x05, 0x00, 0xFF, 0xFE, 0x00, 0x00, 0x00, 0x0F
+
+uint8_t SI4463_RBW_1kHz[] =
+{
+ 0x0C, RF_MODEM_TX_RAMP_DELAY_8_1, \
+ 0x10, RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1, \
+ 0x10, RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1, \
+ 0x10, RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1, \
+ 0x00
+};
+
+// -------------- 3 kHz ----------------------------
+
+#undef RF_MODEM_TX_RAMP_DELAY_8_1
+#undef RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1
+#undef RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1
+#undef RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1
+
+#define RF_MODEM_TX_RAMP_DELAY_8_1 0x11, 0x20, 0x08, 0x18, 0x01, 0x80, 0x08, 0x03, 0x80, 0x00, 0xF0, 0x11
+#define RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1 0x11, 0x21, 0x0C, 0x00, 0xCC, 0xA1, 0x30, 0xA0, 0x21, 0xD1, 0xB9, 0xC9, 0xEA, 0x05, 0x12, 0x11
+#define RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1 0x11, 0x21, 0x0C, 0x0C, 0x0A, 0x04, 0x15, 0xFC, 0x03, 0x00, 0xCC, 0xA1, 0x30, 0xA0, 0x21, 0xD1
+#define RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1 0x11, 0x21, 0x0C, 0x18, 0xB9, 0xC9, 0xEA, 0x05, 0x12, 0x11, 0x0A, 0x04, 0x15, 0xFC, 0x03, 0x00
+
+uint8_t SI4463_RBW_3kHz[] =
+{
+ 0x0C, RF_MODEM_TX_RAMP_DELAY_8_1, \
+ 0x10, RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1, \
+ 0x10, RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1, \
+ 0x10, RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1, \
+ 0x00
+};
+
+// -------------- 10 kHz ----------------------------
+
+#undef RF_MODEM_TX_RAMP_DELAY_8_1
+#undef RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1
+#undef RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1
+#undef RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1
+
+#define RF_MODEM_TX_RAMP_DELAY_8_1 0x11, 0x20, 0x08, 0x18, 0x01, 0x80, 0x08, 0x03, 0x80, 0x00, 0xB0, 0x20
+#define RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1 0x11, 0x21, 0x0C, 0x00, 0xCC, 0xA1, 0x30, 0xA0, 0x21, 0xD1, 0xB9, 0xC9, 0xEA, 0x05, 0x12, 0x11
+#define RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1 0x11, 0x21, 0x0C, 0x0C, 0x0A, 0x04, 0x15, 0xFC, 0x03, 0x00, 0xCC, 0xA1, 0x30, 0xA0, 0x21, 0xD1
+#define RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1 0x11, 0x21, 0x0C, 0x18, 0xB9, 0xC9, 0xEA, 0x05, 0x12, 0x11, 0x0A, 0x04, 0x15, 0xFC, 0x03, 0x00
+
+
+uint8_t SI4463_RBW_10kHz[] =
+{
+ 0x0C, RF_MODEM_TX_RAMP_DELAY_8_1, \
+ 0x10, RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1, \
+ 0x10, RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1, \
+ 0x10, RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1, \
+ 0x00
+};
+
+// -------------- 30 kHz ----------------------------
+
+#undef RF_MODEM_TX_RAMP_DELAY_8_1
+#undef RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1
+#undef RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1
+#undef RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1
+
+#define RF_MODEM_TX_RAMP_DELAY_8_1 0x11, 0x20, 0x08, 0x18, 0x01, 0x80, 0x08, 0x03, 0x80, 0x00, 0x30, 0x10
+#define RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1 0x11, 0x21, 0x0C, 0x00, 0xFF, 0xBA, 0x0F, 0x51, 0xCF, 0xA9, 0xC9, 0xFC, 0x1B, 0x1E, 0x0F, 0x01
+#define RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1 0x11, 0x21, 0x0C, 0x0C, 0xFC, 0xFD, 0x15, 0xFF, 0x00, 0x0F, 0xFF, 0xBA, 0x0F, 0x51, 0xCF, 0xA9
+#define RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1 0x11, 0x21, 0x0C, 0x18, 0xC9, 0xFC, 0x1B, 0x1E, 0x0F, 0x01, 0xFC, 0xFD, 0x15, 0xFF, 0x00, 0x0F
+
+uint8_t SI4463_RBW_30kHz[] =
+{
+ 0x0C, RF_MODEM_TX_RAMP_DELAY_8_1, \
+ 0x10, RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1, \
+ 0x10, RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1, \
+ 0x10, RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1, \
+ 0x00
+};
+
+// -------------- 100kHz ----------------------------
+
+#undef RF_MODEM_TX_RAMP_DELAY_8_1
+#undef RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1
+#undef RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1
+#undef RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1
+
+#define RF_MODEM_TX_RAMP_DELAY_8_1 0x11, 0x20, 0x08, 0x18, 0x01, 0x80, 0x08, 0x03, 0x80, 0x00, 0x20, 0x20
+#define RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1 0x11, 0x21, 0x0C, 0x00, 0xFF, 0xBA, 0x0F, 0x51, 0xCF, 0xA9, 0xC9, 0xFC, 0x1B, 0x1E, 0x0F, 0x01
+#define RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1 0x11, 0x21, 0x0C, 0x0C, 0xFC, 0xFD, 0x15, 0xFF, 0x00, 0x0F, 0xFF, 0xBA, 0x0F, 0x51, 0xCF, 0xA9
+#define RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1 0x11, 0x21, 0x0C, 0x18, 0xC9, 0xFC, 0x1B, 0x1E, 0x0F, 0x01, 0xFC, 0xFD, 0x15, 0xFF, 0x00, 0x0F
+
+uint8_t SI4463_RBW_100kHz[] =
+{
+ 0x0C, RF_MODEM_TX_RAMP_DELAY_8_1, \
+ 0x10, RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1, \
+ 0x10, RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1, \
+ 0x10, RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1, \
+ 0x00
+};
+
+// -------------- 300kHz ----------------------------
+
+#undef RF_MODEM_TX_RAMP_DELAY_8_1
+#undef RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1
+#undef RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1
+#undef RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1
+
+#define RF_MODEM_TX_RAMP_DELAY_8_1 0x11, 0x20, 0x08, 0x18, 0x01, 0x80, 0x08, 0x03, 0x80, 0x00, 0x00, 0x20
+#define RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1 0x11, 0x21, 0x0C, 0x00, 0xCC, 0xA1, 0x30, 0xA0, 0x21, 0xD1, 0xB9, 0xC9, 0xEA, 0x05, 0x12, 0x11
+#define RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1 0x11, 0x21, 0x0C, 0x0C, 0x0A, 0x04, 0x15, 0xFC, 0x03, 0x00, 0xCC, 0xA1, 0x30, 0xA0, 0x21, 0xD1
+#define RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1 0x11, 0x21, 0x0C, 0x18, 0xB9, 0xC9, 0xEA, 0x05, 0x12, 0x11, 0x0A, 0x04, 0x15, 0xFC, 0x03, 0x00
+
+uint8_t SI4463_RBW_300kHz[] =
+{
+ 0x0C, RF_MODEM_TX_RAMP_DELAY_8_1, \
+ 0x10, RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1, \
+ 0x10, RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1, \
+ 0x10, RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1, \
+ 0x00
+};
+
+
+
+// -------------- 850kHz ----------------------------
+
+#undef RF_MODEM_TX_RAMP_DELAY_8_1
+#undef RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1
+#undef RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1
+#undef RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1
+
+#define RF_MODEM_TX_RAMP_DELAY_8_1 0x11, 0x20, 0x08, 0x18, 0x01, 0x00, 0x08, 0x03, 0x80, 0x00, 0x00, 0x30
+#define RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1 0x11, 0x21, 0x0C, 0x00, 0xFF, 0xBA, 0x0F, 0x51, 0xCF, 0xA9, 0xC9, 0xFC, 0x1B, 0x1E, 0x0F, 0x01
+#define RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1 0x11, 0x21, 0x0C, 0x0C, 0xFC, 0xFD, 0x15, 0xFF, 0x00, 0x0F, 0xFF, 0xBA, 0x0F, 0x51, 0xCF, 0xA9
+#define RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1 0x11, 0x21, 0x0C, 0x18, 0xC9, 0xFC, 0x1B, 0x1E, 0x0F, 0x01, 0xFC, 0xFD, 0x15, 0xFF, 0x00, 0x0F
+
+uint8_t SI4463_RBW_850kHz[] =
+{
+ 0x0C, RF_MODEM_TX_RAMP_DELAY_8_1, \
+ 0x10, RF_MODEM_CHFLT_RX1_CHFLT_COE13_7_0_12_1, \
+ 0x10, RF_MODEM_CHFLT_RX1_CHFLT_COE1_7_0_12_1, \
+ 0x10, RF_MODEM_CHFLT_RX2_CHFLT_COE7_7_0_12_1, \
+ 0x00
+};
+#else
+// -------------- 0.2 kHz ----------------------------
+
+#include "radio_config_Si4468_undef.h"
+#include "radio_config_Si4468_200Hz.h"
+#include "radio_config_Si4468_short.h"
+
+static const uint8_t SI4463_RBW_02kHz[] =
+ RADIO_CONFIGURATION_DATA_ARRAY;
+
+// -------------- 1kHz ----------------------------
+
+#include "radio_config_Si4468_undef.h"
+#include "radio_config_Si4468_1kHz.h"
+#include "radio_config_Si4468_short.h"
+
+static const uint8_t SI4463_RBW_1kHz[] =
+ RADIO_CONFIGURATION_DATA_ARRAY;
+
+// -------------- 3 kHz ----------------------------
+#include "radio_config_Si4468_undef.h"
+#include "radio_config_Si4468_3kHz.h"
+#include "radio_config_Si4468_short.h"
+
+static const uint8_t SI4463_RBW_3kHz[] =
+ RADIO_CONFIGURATION_DATA_ARRAY;
+
+// -------------- 10 kHz ----------------------------
+#include "radio_config_Si4468_undef.h"
+#include "radio_config_Si4468_10kHz.h"
+#include "radio_config_Si4468_short.h"
+
+static const uint8_t SI4463_RBW_10kHz[] =
+ RADIO_CONFIGURATION_DATA_ARRAY;
+
+// -------------- 30 kHz ----------------------------
+#include "radio_config_Si4468_undef.h"
+#include "radio_config_Si4468_30kHz.h"
+#include "radio_config_Si4468_short.h"
+
+static const uint8_t SI4463_RBW_30kHz[] =
+ RADIO_CONFIGURATION_DATA_ARRAY;
+
+// -------------- 100kHz ----------------------------
+#include "radio_config_Si4468_undef.h"
+#include "radio_config_Si4468_100kHz.h"
+#include "radio_config_Si4468_short.h"
+
+static const uint8_t SI4463_RBW_100kHz[] =
+ RADIO_CONFIGURATION_DATA_ARRAY;
+
+// -------------- 300kHz ----------------------------
+
+#include "radio_config_Si4468_undef.h"
+#include "radio_config_Si4468_300kHz.h"
+#include "radio_config_Si4468_short.h"
+
+static const uint8_t SI4463_RBW_300kHz[] =
+ RADIO_CONFIGURATION_DATA_ARRAY;
+
+// -------------- 850kHz ----------------------------
+
+#include "radio_config_Si4468_undef.h"
+#include "radio_config_Si4468_850kHz.h"
+#include "radio_config_Si4468_short.h"
+
+static const uint8_t SI4463_RBW_850kHz[] =
+ RADIO_CONFIGURATION_DATA_ARRAY;
+
+#endif
+// User asks for an RBW of WISH, go through table finding the last triple
+// for which WISH is greater than the first entry, use those values,
+// Return the first entry of the following triple for the RBW actually achieved
+#define IF_BW(dwn3, ndec, filset) (((dwn3)<<7)|((ndec)<<4)|(filset))
+typedef struct {
+ const uint8_t *reg; // IF_BW(dwn3, ndec, filset)
+ int16_t RSSI_correction_x_10; // Correction * 10
+ int16_t RBWx10; // RBW in kHz
+}RBW_t; // sizeof(RBW_t) = 8 bytes
+
+static const RBW_t RBW_choices[] =
+{
+// BW register corr freq
+ {SI4463_RBW_02kHz, 0,3},
+ {SI4463_RBW_1kHz, 0,10},
+ {SI4463_RBW_3kHz, 0,30},
+ {SI4463_RBW_10kHz, 0,100},
+ {SI4463_RBW_30kHz, 0,300},
+ {SI4463_RBW_100kHz,0,1000},
+ {SI4463_RBW_300kHz,0,3000},
+ {SI4463_RBW_850kHz,0,6000},
+};
+
+const int SI4432_RBW_count = ((int)(sizeof(RBW_choices)/sizeof(RBW_t)));
+
+static pureRSSI_t SI4463_RSSI_correction = float_TO_PURE_RSSI(-120);
+static int prev_band = -1;
+
+pureRSSI_t getSI4463_RSSI_correction(void){
+ return SI4463_RSSI_correction;
+};
+
+
+uint16_t force_rbw(int f)
+{
+ if (SI4463_in_tx_mode)
+ return(0);
+ SI4463_set_state(SI446X_STATE_READY);
+ const uint8_t *config = RBW_choices[f].reg;
+ uint16_t i=0;
+ while(config[i] != 0)
+ {
+ SI4463_do_api((void *)&config[i+1], config[i], NULL, 0);
+ i += config[i]+1;
+ }
+ SI4463_clear_int_status();
+ SI4463_short_start_rx(); // This can cause recalibration
+ SI4463_wait_for_cts();
+ set_RSSI_comp();
+// prev_band = -1;
+ SI4463_RSSI_correction = float_TO_PURE_RSSI(RBW_choices[f].RSSI_correction_x_10 - 1200)/10; // Set RSSI correction
+ return RBW_choices[f].RBWx10; // RBW achieved by SI4463 in kHz * 10
+}
+
+uint16_t set_rbw(uint16_t WISH) {
+ int i;
+ for (i=0; i < (int)(sizeof(RBW_choices)/sizeof(RBW_t)) - 1; i++)
+ if (WISH <= RBW_choices[i].RBWx10)
+ break;
+ return force_rbw(i);
+}
+
+
+#define Npresc 1 // 0=low / 1=High performance mode
+
+static int refresh_count = 0;
+
+freq_t SI4463_set_freq(freq_t freq)
+{
+// SI4463_set_gpio(3,GPIO_HIGH);
+ int S = 4 ; // Approx 100 Hz channels
+ SI4463_channel = 0;
+ if (freq >= 822000000 && freq <= 1130000000) { // 822 to 1130MHz
+ SI4463_band = 0;
+ SI4463_outdiv = 4;
+ } else if (freq >= 411000000 && freq <= 566000000) { // 411 to 568MHz
+ SI4463_band = 2;
+ SI4463_outdiv = 8;
+ } else if (freq >= 329000000 && freq <= 454000000) { // 329 to 454MHz
+ SI4463_band = 1;
+ SI4463_outdiv = 10;
+ } else if (freq >= 274000000 && freq <= 378000000) { // 274 to 378
+ SI4463_band = 3;
+ SI4463_outdiv = 12;
+ } else if (freq >= 137000000 && freq <= 189000000){ // 137 to 189
+ SI4463_band = 5;
+ SI4463_outdiv = 24;
+#if 0 // Band 4, 6 and 7 do not function
+ } else if (freq >= 137000000 && freq <= 189000000){ // 220 to 266
+ SI4463_band = 4;
+ SI4463_outdiv = 12;
+#endif
+ } else
+ return 0;
+ if (SI4463_offset_active) {
+ si_set_offset(0);
+ SI4463_offset_active = false;
+ }
+ int32_t R = (freq * SI4463_outdiv) / (Npresc ? 2*config.setting_frequency_30mhz : 4*config.setting_frequency_30mhz) - 1; // R between 0x00 and 0x7f (127)
+ int64_t MOD = 524288; // = 2^19
+ int32_t F = ((freq * SI4463_outdiv*MOD) / (Npresc ? 2*config.setting_frequency_30mhz : 4*config.setting_frequency_30mhz)) - R*MOD;
+ freq_t actual_freq = (R*MOD + F) * (Npresc ? 2*config.setting_frequency_30mhz : 4*config.setting_frequency_30mhz)/ SI4463_outdiv/MOD;
+ int delta = freq - actual_freq;
+ if (delta < -100 || delta > 100 ){
+ while(1)
+ my_microsecond_delay(10);
+ }
+ if (F < MOD || F >= MOD*2){
+ while(1)
+ my_microsecond_delay(10);
+ }
+ if (false && (SI4463_band == prev_band)) {
+ int vco = 2091 + ((((freq / 4 ) * SI4463_outdiv - 850000000)/1000) * 492) / 200000;
+
+ if (SI4463_in_tx_mode) {
+ uint8_t data[] = {
+ 0x37,
+ (uint8_t) R, // R data[4]
+ (uint8_t) ((F>>16) & 255), // F2,F1,F0 data[5] .. data[7]
+ (uint8_t) ((F>> 8) & 255), // F2,F1,F0 data[5] .. data[7]
+ (uint8_t) ((F ) & 255), // F2,F1,F0 data[5] .. data[7]
+ (vco>>8) & 0xff,
+ vco & 0xff,
+ 0x00,
+ 0x32
+ };
+ SI4463_do_api(data, sizeof(data), NULL, 0);
+ } else {
+
+ uint8_t data[] = {
+ 0x36,
+ (uint8_t) R, // R data[4]
+ (uint8_t) ((F>>16) & 255), // F2,F1,F0 data[5] .. data[7]
+ (uint8_t) ((F>> 8) & 255), // F2,F1,F0 data[5] .. data[7]
+ (uint8_t) ((F ) & 255), // F2,F1,F0 data[5] .. data[7]
+ (vco>>8) & 0xff,
+ vco & 0xff
+ };
+ SI4463_do_api(data, sizeof(data), NULL, 0);
+ }
+ SI4463_frequency_changed = true;
+// SI4463_set_gpio(3,GPIO_LOW);
+ return actual_freq;
+ }
+#if 0
+ static int old_R = -1; // What about TX/RX switching?
+ static int old_F = -1;
+ if (old_R == R || old_F == F)
+ return;
+ old_R = R;
+ old_F = f;
+#endif
+ refresh_count=0;
+ SI4463_set_state(SI446X_STATE_READY);
+ my_deleted_delay(100);
+
+ /*
+ // Set properties: RF_FREQ_CONTROL_INTE_8
+ // Number of properties: 8
+ // Group ID: 0x40
+ // Start ID: 0x00
+ // Default values: 0x3C, 0x08, 0x00, 0x00, 0x00, 0x00, 0x20, 0xFF,
+ // Descriptions:
+ // FREQ_CONTROL_INTE - Frac-N PLL Synthesizer integer divide number.
+ // FREQ_CONTROL_FRAC_2 - Frac-N PLL fraction number.
+ // FREQ_CONTROL_FRAC_1 - Frac-N PLL fraction number.
+ // FREQ_CONTROL_FRAC_0 - Frac-N PLL fraction number.
+ // FREQ_CONTROL_CHANNEL_STEP_SIZE_1 - EZ Frequency Programming channel step size.
+ // FREQ_CONTROL_CHANNEL_STEP_SIZE_0 - EZ Frequency Programming channel step size.
+ // FREQ_CONTROL_W_SIZE - Set window gating period (in number of crystal reference clock cycles) for counting VCO frequency during calibration.
+ // FREQ_CONTROL_VCOCNT_RX_ADJ - Adjust target count for VCO calibration in RX mode.
+ */
+ // #define RF_FREQ_CONTROL_INTE_8_1 0x11, 0x40, 0x08, 0x00, 0x41, 0x0D, 0xA9, 0x5A, 0x4E, 0xC5, 0x20, 0xFE
+ uint8_t data[] = {
+ 0x11, 0x40, 0x08, 0x00,
+ (uint8_t) R, // R data[4]
+ (uint8_t) ((F>>16) & 255), // F2,F1,F0 data[5] .. data[7]
+ (uint8_t) ((F>> 8) & 255), // F2,F1,F0 data[5] .. data[7]
+ (uint8_t) ((F ) & 255), // F2,F1,F0 data[5] .. data[7]
+ (uint8_t) ((S>> 8) & 255), // Step size data[8] .. data[9]
+ (uint8_t) ((S ) & 255), // Step size data[8] .. data[9]
+ 0x20, // Window gate
+ 0xFF // Adj count
+ };
+ SI4463_do_api(data, sizeof(data), NULL, 0);
+
+ if (SI4463_band != prev_band) {
+ /*
+ // Set properties: RF_MODEM_CLKGEN_BAND_1
+ // Number of properties: 1
+ // Group ID: 0x20
+ // Start ID: 0x51
+ // Default values: 0x08,
+ // Descriptions:
+ // MODEM_CLKGEN_BAND - Select PLL Synthesizer output divider ratio as a function of frequency band.
+ */
+ // #define RF_MODEM_CLKGEN_BAND_1 0x11, 0x20, 0x01, 0x51, 0x0A
+ uint8_t data2[] = {
+ 0x11, 0x20, 0x01, 0x51,
+ 0x10 + (uint8_t)(SI4463_band + (Npresc ? 0x08 : 0)) // 0x08 for high performance mode, 0x10 to skip recal
+ };
+ SI4463_do_api(data2, sizeof(data2), NULL, 0);
+// my_microsecond_delay(30000);
+ }
+
+
+
+
+ // SI4463_clear_int_status();
+#if 0
+ retry:
+#endif
+ if (SI4463_in_tx_mode)
+ SI4463_start_tx(0);
+ else {
+ SI4463_start_rx(SI4463_channel);
+#if 0
+ si446x_state_t s = SI4463_get_state();
+ if (s != SI446X_STATE_RX) {
+ SI4463_start_rx(SI4463_channel);
+ my_microsecond_delay(1000);
+#if 1
+ si446x_state_t s = SI4463_get_state();
+ if (s != SI446X_STATE_RX) {
+ my_microsecond_delay(3000);
+ goto retry;
+ }
+#endif
+ }
+#endif
+ }
+ SI4463_wait_for_cts();
+// SI4463_set_gpio(3,GPIO_LOW);
+ SI4463_frequency_changed = true;
+ prev_band = SI4463_band;
+ return actual_freq;
+}
+
+void SI4463_init_rx(void)
+{
+// reset:
+ SI_SDN_LOW;
+ my_microsecond_delay(100);
+ SI_SDN_HIGH;
+ my_microsecond_delay(1000);
+ SI_SDN_LOW;
+ my_microsecond_delay(1000);
+#ifdef __SI4468__
+ for(uint16_t i=0;iDR)
#define SPI_READ_16BIT(spi) *(__IO uint16_t*)(&spi->DR)
+#ifdef TINYSA4
#define SPI_MODE_LCD 0x00
#define SPI_MODE_SD_CARD 0x01
#define SPI_MODE_SI 0x02
-
void set_SPI_mode(uint16_t mode);
+void start_SI4432_SPI_mode(void);
+void stop_SI4432_SPI_mode(void);
+#endif
\ No newline at end of file
diff --git a/ui.c b/ui.c
index e9b32d4..83370a3 100644
--- a/ui.c
+++ b/ui.c
@@ -284,7 +284,11 @@ void
touch_start_watchdog(void)
{
touch_prepare_sense();
+#ifdef TINYSA4
adc_start_analog_watchdogd();
+#else
+ adc_start_analog_watchdogd(ADC_TOUCH_Y);
+#endif
}
static inline int
@@ -431,15 +435,12 @@ touch_draw_test(void)
do {
if (touch_check() == EVT_TOUCH_PRESSED){
touch_position(&x0, &y0);
- ili9341_line(x0, y0, x0, y0);
do {
chThdSleepMilliseconds(50);
touch_position(&x1, &y1);
- if (x0!= x1 || y0 != y1) {
- ili9341_line(x0, y0, x1, y1);
- x0 = x1;
- y0 = y1;
- }
+ ili9341_line(x0, y0, x1, y1);
+ x0 = x1;
+ y0 = y1;
} while (touch_check() != EVT_TOUCH_RELEASED);
}
}while (!(btn_check() & EVT_BUTTON_SINGLE_CLICK));
@@ -459,7 +460,6 @@ touch_position(int *x, int *y)
#endif
}
-
void
show_version(void)
{
@@ -475,7 +475,7 @@ show_version(void)
do {shift>>=1; y+=5;} while (shift&1);
ili9341_drawstring(info_about[i++], x, y+=5);
}
-
+#ifdef TINYSA4
static char buf[96];
extern const char *states[];
#define ENABLE_THREADS_COMMAND
@@ -503,7 +503,7 @@ extern const char *states[];
#endif
-
+#endif // TINYSA4
while (true) {
if (touch_check() == EVT_TOUCH_PRESSED)
@@ -881,7 +881,7 @@ static UI_FUNCTION_CALLBACK(menu_marker_op_cb)
{
float l = actual_t[markers[active_marker].index];
float s_max = value(l)/setting.scale;
- user_set_reflevel(setting.scale*(floor(s_max)+2));
+ user_set_reflevel(setting.scale*(floorf(s_max)+2));
}
break;
#ifdef __VNA__
@@ -1894,7 +1894,7 @@ draw_menu_buttons(const menuitem_t *menu)
}
goto draw_divider;
} else if (menu[i].data == KM_LOWOUTLEVEL) {
- local_slider_positions = ((get_level() - SL_GENLOW_LEVEL_MIN - config.low_level_output_offset ) * (MENU_FORM_WIDTH-8)) / SL_GENLOW_LEVEL_RANGE + OFFSETX+4;
+ local_slider_positions = ((get_level() - level_min()) * (MENU_FORM_WIDTH-8)) / level_range() + OFFSETX+4;
for (int i=0; i <= 4; i++) {
ili9341_drawstring(step_text[i], button_start+12 + i * MENU_FORM_WIDTH/5, y+button_height-9);
}
@@ -1905,7 +1905,7 @@ draw_menu_buttons(const menuitem_t *menu)
draw_slider:
blit8BitWidthBitmap(local_slider_positions - 4, y, 7, 5, slider_bitmap);
} else if (menu[i].data == KM_HIGHOUTLEVEL) {
- local_slider_positions = ((get_level() - SL_GENHIGH_LEVEL_MIN ) * (MENU_FORM_WIDTH-8)) / SL_GENHIGH_LEVEL_RANGE + OFFSETX+4;
+ local_slider_positions = ((get_level() - level_min() ) * (MENU_FORM_WIDTH-8)) / level_range() + OFFSETX+4;
goto draw_slider;
}
}
@@ -2071,7 +2071,7 @@ menu_select_touch(int i, int pos)
check_frequency_slider(slider_freq);
}
} else if (menu_is_form(menu) && MT_MASK(menu[i].type) == MT_KEYPAD && keypad == KM_LOWOUTLEVEL) {
- uistat.value = setting.offset + ((touch_x - OFFSETX+4) * SL_GENLOW_LEVEL_RANGE ) / (MENU_FORM_WIDTH-8) + SL_GENLOW_LEVEL_MIN + config.low_level_output_offset;
+ uistat.value = setting.offset + ((touch_x - OFFSETX+4) * level_range() ) / (MENU_FORM_WIDTH-8) + level_min() ;
apply_step:
set_keypad_value(keypad);
apply:
@@ -2080,7 +2080,7 @@ menu_select_touch(int i, int pos)
// }
// } else if (MT_MASK(menu[i].type) == MT_ADV_CALLBACK && menu[i].reference == menu_sdrive_acb) {
} else if (menu_is_form(menu) && MT_MASK(menu[i].type) == MT_KEYPAD && keypad == KM_HIGHOUTLEVEL) {
- set_level( (touch_x - OFFSETX+4) *(SL_GENHIGH_LEVEL_RANGE) / (MENU_FORM_WIDTH-8) + SL_GENHIGH_LEVEL_MIN );
+ set_level( (touch_x - OFFSETX+4) *(level_range()) / (MENU_FORM_WIDTH-8) + level_min() );
goto apply;
}
keypad_mode = old_keypad_mode;
diff --git a/ui_sa.c b/ui_sa.c
index 872eba9..566b3c4 100644
--- a/ui_sa.c
+++ b/ui_sa.c
@@ -405,15 +405,22 @@ enum {
KM_START, KM_STOP, KM_CENTER, KM_SPAN, KM_CW, // These must be first to share common help text
KM_REFLEVEL, KM_SCALE, KM_ATTENUATION,
KM_ACTUALPOWER, KM_IF, KM_SAMPLETIME, KM_DRIVE, KM_LOWOUTLEVEL, KM_DECAY, KM_NOISE,
- KM_30MHZ, KM_REPEAT, KM_OFFSET, KM_TRIGGER, KM_LEVELSWEEP, KM_SWEEP_TIME, KM_OFFSET_DELAY,
+#ifdef TINYSA4
+ KM_30MHZ,
+#else
+ KM_10MHZ,
+#endif
+ KM_REPEAT, KM_OFFSET, KM_TRIGGER, KM_LEVELSWEEP, KM_SWEEP_TIME, KM_OFFSET_DELAY,
KM_FAST_SPEEDUP, KM_GRIDLINES, KM_MARKER, KM_MODULATION, KM_HIGHOUTLEVEL,
+#ifdef TINYSA4
KM_R,KM_MOD,KM_CP,
-#if 1
KM_COR_AM,KM_COR_WFM, KM_COR_NFM,
#endif
KM_ATTACK,
+#ifdef TINYSA4
KM_IF2,
KM_LPF,
+#endif
KM_NONE // always at enum end
};
@@ -436,7 +443,7 @@ static const struct {
{keypads_plusmin , "LEVEL"}, // KM_LOWOUTLEVEL
{keypads_positive , "DECAY"}, // KM_DECAY
{keypads_positive , "NOISE\nLEVEL"}, // KM_NOISE
- {keypads_freq , "FREQ"}, // KM_30MHz
+ {keypads_freq , "FREQ"}, // KM_30MHz | KM_10MHz
{keypads_positive , "SAMPLE\nREPEAT"}, // KM_REPEA
{keypads_plusmin , "OFFSET"}, // KM_OFFSET
{keypads_plusmin_unit, "TRIGGER\nLEVEL"}, // KM_TRIGGER
@@ -448,17 +455,19 @@ static const struct {
{keypads_freq , "MARKER\nFREQ"}, // KM_MARKER
{keypads_freq , "MODULATION\nFREQ"}, // KM_MODULATION
{keypads_plusmin , "LEVEL"}, // KM_HIGHOUTLEVEL
-#if 1
+#ifdef TINYSA
{keypads_plusmin , "COR\nAM"}, // KM_COR_AM
{keypads_plusmin , "COR\nWFM"}, // KM_COR_WFM
{keypads_plusmin , "COR\nNFM"}, // KM_COR_NFM
-#endif
{keypads_freq , "IF2"}, // KM_IF2
{keypads_positive , "R"}, // KM_R
{keypads_positive , "MODULO"}, // KM_MOD
{keypads_positive , "CP"}, // KM_CP
+#endif
{keypads_positive , "ATTACK"}, // KM_ATTACK
+#ifdef TINYSA4
{keypads_freq , "ULTRA\nSTART"}, // KM_LPF
+#endif
};
#if 0 // Not used
@@ -482,12 +491,10 @@ static const menuitem_t menu_top[];
static const menuitem_t menu_reffer[];
static const menuitem_t menu_modulation[];
static const menuitem_t menu_drive_wide[];
+#ifdef TINYSA4
static const menuitem_t menu_settings3[];
-static const menuitem_t menu_sweep[];
-#ifdef __ULTRA__
-static const menuitem_t menu_tophigh[];
-static const menuitem_t menu_topultra[];
#endif
+static const menuitem_t menu_sweep[];
#define AUTO_ICON(S) (S>=2?BUTTON_ICON_CHECK_AUTO:S) // Depends on order of ICONs!!!!!
@@ -543,11 +550,6 @@ static UI_FUNCTION_ADV_CALLBACK(menu_mode_acb)
case 3:
menu_push_submenu(menu_highoutputmode);
break;
-#ifdef __ULTRA__
- case 7:
- menu_push_submenu(menu_topultra);
- break;
-#endif
}
redraw_request |= REDRAW_CAL_STATUS;
}
@@ -745,40 +747,27 @@ static UI_FUNCTION_ADV_CALLBACK(menu_sreffer_acb){
menu_push_submenu(menu_reffer);
}
-#ifdef TINYSA4
-const int8_t menu_drive_value[]={-38,-35,-33,-30,-27,-24,-21,-19, -7,-4,-2,1,4,7,10,13};
-#else
-const int8_t menu_drive_value[]={-38,-35,-33,-30,-27,-24,-21,-19, -7,-4,-2,1,4,7,10,13};
-#endif
-#if 0
+#ifdef TINYSA3
static UI_FUNCTION_ADV_CALLBACK(menu_lo_drive_acb)
{
(void)item;
if(b){
-#ifdef TINYSA4
- b->param_1.i = data+20;
-#else
- b->param_1.i = menu_drive_value[data] + (setting.mode==M_GENHIGH ? setting.offset : 0);
-#endif
+ b->param_1.i = drive_dBm[data];
b->icon = data == setting.lo_drive ? BUTTON_ICON_GROUP_CHECKED : BUTTON_ICON_GROUP;
return;
}
//Serial.println(item);
- set_lo_drive(data+20);
+ set_lo_drive(data);
menu_move_back();
// ui_mode_normal();
// draw_cal_status();
}
-#endif
+#else
static UI_FUNCTION_ADV_CALLBACK(menu_mixer_drive_acb)
{
(void)item;
if(b){
-#ifdef TINYSA4
b->param_1.i = data;
-#else
- b->param_1.i = menu_drive_value[data] + (setting.mode==M_GENHIGH ? setting.offset : 0);
-#endif
b->icon = data == setting.lo_drive ? BUTTON_ICON_GROUP_CHECKED : BUTTON_ICON_GROUP;
return;
}
@@ -788,6 +777,7 @@ static UI_FUNCTION_ADV_CALLBACK(menu_mixer_drive_acb)
// ui_mode_normal();
// draw_cal_status();
}
+#endif
#if 0
static UI_FUNCTION_ADV_CALLBACK(menu_sdrive_acb){
@@ -797,7 +787,7 @@ static UI_FUNCTION_ADV_CALLBACK(menu_sdrive_acb){
#ifdef TINYSA4
b->param_1.i = setting.lo_drive;
#else
- b->param_1.i = menu_drive_value[setting.lo_drive] + (setting.mode==M_GENHIGH ? setting.offset : 0);
+ b->param_1.i = drive_dBm[setting.lo_drive] + (setting.mode==M_GENHIGH ? setting.offset : 0);
#endif
return;
}
@@ -805,8 +795,6 @@ static UI_FUNCTION_ADV_CALLBACK(menu_sdrive_acb){
}
#endif
-
-
#ifdef __SPUR__
static UI_FUNCTION_ADV_CALLBACK(menu_spur_acb)
{
@@ -818,7 +806,11 @@ static UI_FUNCTION_ADV_CALLBACK(menu_spur_acb)
b->icon = AUTO_ICON(setting.spur_removal);
} else {
b->param_1.text = "MIRROR\nMASKING";
+#ifdef TINYSA4
b->icon = AUTO_ICON(setting.mirror_masking);
+#else
+ b->icon = setting.mirror_masking == 0 ? BUTTON_ICON_NOCHECK : BUTTON_ICON_CHECK;
+#endif
}
return;
}
@@ -831,6 +823,7 @@ static UI_FUNCTION_ADV_CALLBACK(menu_spur_acb)
}
#endif
+#ifdef TINYSA4
static UI_FUNCTION_ADV_CALLBACK(menu_extra_lna_acb)
{
(void)data;
@@ -870,7 +863,7 @@ static UI_FUNCTION_ADV_CALLBACK(menu_debug_freq_acb)
// menu_move_back();
ui_mode_normal();
}
-
+#endif
static UI_FUNCTION_ADV_CALLBACK(menu_measure_acb)
{
@@ -1210,15 +1203,23 @@ static UI_FUNCTION_CALLBACK(menu_marker_delete_cb)
}
}
+#ifdef TINYSA4
static const uint16_t rbwsel_x10[]={0,3,10,30,100,300,1000,3000,6000};
static const char* rbwsel_text[]={"auto","300","1k","3k","10k","30k","100k","300k","600k"};
+#else
+static const uint16_t rbwsel_x10[]={0,30,100,300,1000,3000,6000};
+#endif
static UI_FUNCTION_ADV_CALLBACK(menu_rbw_acb)
{
(void)item;
if (b){
- b->param_1.text = rbwsel_text[data];
- b->icon = setting.rbw_x10 == rbwsel_x10[data] ? BUTTON_ICON_GROUP_CHECKED : BUTTON_ICON_GROUP;
+#ifdef TINYSA4
+ b->param_1.text = rbwsel_text[data];
+#else
+ b->param_1.u = rbwsel_x10[data]/10;
+#endif
+ b->icon = setting.rbw_x10 == rbwsel_x10[data] ? BUTTON_ICON_GROUP_CHECKED : BUTTON_ICON_GROUP;
return;
}
set_RBW(rbwsel_x10[data]);
@@ -1390,6 +1391,7 @@ static UI_FUNCTION_ADV_CALLBACK(menu_settings_below_if_acb){
draw_menu();
}
+#ifdef TINYSA4
static UI_FUNCTION_ADV_CALLBACK(menu_settings_ultra_acb){
(void)item;
(void)data;
@@ -1403,6 +1405,7 @@ static UI_FUNCTION_ADV_CALLBACK(menu_settings_ultra_acb){
toggle_ultra();
draw_menu();
}
+#endif
static UI_FUNCTION_ADV_CALLBACK(menu_lo_output_acb){
(void)item;
@@ -1552,7 +1555,7 @@ static const menuitem_t menu_load_preset[] =
{ MT_CANCEL, 255, S_LARROW" BACK", NULL },
{ MT_NONE, 0, NULL, NULL } // sentinel
};
-
+#ifdef TINYSA4
static const menuitem_t menu_mixer_drive[] = {
{ MT_ADV_CALLBACK, 3, "%+ddBm", menu_mixer_drive_acb},
{ MT_ADV_CALLBACK, 2, "%+ddBm", menu_mixer_drive_acb},
@@ -1561,39 +1564,14 @@ static const menuitem_t menu_mixer_drive[] = {
{ MT_CANCEL, 255, S_LARROW" BACK", NULL },
{ MT_NONE, 0, NULL, NULL } // sentinel
};
-
-#if 0
-static const menuitem_t menu_drive_wide3[] = {
- { MT_FORM | MT_ADV_CALLBACK, 5, "%+ddBm", menu_lo_drive_acb},
- { MT_FORM | MT_ADV_CALLBACK, 4, "%+ddBm", menu_lo_drive_acb},
- { MT_FORM | MT_ADV_CALLBACK, 3, "%+ddBm", menu_lo_drive_acb},
- { MT_FORM | MT_ADV_CALLBACK, 2, "%+ddBm", menu_lo_drive_acb},
- { MT_FORM | MT_ADV_CALLBACK, 1, "%+ddBm", menu_lo_drive_acb},
- { MT_FORM | MT_ADV_CALLBACK, 0, "%+ddBm", menu_lo_drive_acb},
- { MT_FORM | MT_CANCEL, 255, S_LARROW" BACK", NULL },
- { MT_FORM | MT_NONE, 0, NULL, NULL } // sentinel
-};
-
-static const menuitem_t menu_drive_wide2[] = {
- { MT_FORM | MT_ADV_CALLBACK, 10, "%+ddBm", menu_lo_drive_acb},
- { MT_FORM | MT_ADV_CALLBACK, 9, "%+ddBm", menu_lo_drive_acb},
- { MT_FORM | MT_ADV_CALLBACK, 8, "%+ddBm", menu_lo_drive_acb},
- { MT_FORM | MT_ADV_CALLBACK, 7, "%+ddBm", menu_lo_drive_acb},
- { MT_FORM | MT_ADV_CALLBACK, 6, "%+ddBm", menu_lo_drive_acb},
- { MT_FORM | MT_SUBMENU, 255, S_RARROW" MORE", menu_drive_wide3},
- { MT_FORM | MT_CANCEL, 255, S_LARROW" BACK", NULL },
- { MT_FORM | MT_NONE, 0, NULL, NULL } // sentinel
-};
-
-static const menuitem_t menu_drive_wide[] = {
- { MT_FORM | MT_ADV_CALLBACK, 15, "%+ddBm", menu_lo_drive_acb},
- { MT_FORM | MT_ADV_CALLBACK, 14, "%+ddBm", menu_lo_drive_acb},
- { MT_FORM | MT_ADV_CALLBACK, 13, "%+ddBm", menu_lo_drive_acb},
- { MT_FORM | MT_ADV_CALLBACK, 12, "%+ddBm", menu_lo_drive_acb},
- { MT_FORM | MT_ADV_CALLBACK, 11, "%+ddBm", menu_lo_drive_acb},
- { MT_FORM | MT_SUBMENU, 255, S_RARROW" MORE", menu_drive_wide2},
- { MT_FORM | MT_CANCEL, 255, S_LARROW" BACK", NULL },
- { MT_FORM | MT_NONE, 0, NULL, NULL } // sentinel
+#else
+static const menuitem_t menu_lo_drive[] = {
+ { MT_ADV_CALLBACK, 15, "%+ddBm", menu_lo_drive_acb},
+ { MT_ADV_CALLBACK, 14, "%+ddBm", menu_lo_drive_acb},
+ { MT_ADV_CALLBACK, 13, "%+ddBm", menu_lo_drive_acb},
+ { MT_ADV_CALLBACK, 12, "%+ddBm", menu_lo_drive_acb},
+ { MT_CANCEL, 255, S_LARROW" BACK", NULL },
+ { MT_NONE, 0, NULL, NULL } // sentinel
};
#endif
@@ -1623,7 +1601,9 @@ char center_text[18] = "FREQ: %s";
static const menuitem_t menu_lowoutputmode[] = {
{ MT_FORM | MT_ADV_CALLBACK, 0, "LOW OUTPUT %s", menu_outputmode_acb},
// { MT_FORM | MT_ADV_CALLBACK, 0, "MOD: %s", menu_smodulation_acb},
+#ifdef TINYSA4
{ MT_FORM | MT_SUBMENU, 255, S_RARROW" Settings", menu_settings3},
+#endif
{ MT_FORM | MT_KEYPAD, KM_CENTER, center_text, "10kHz..350MHz"},
{ MT_FORM | MT_KEYPAD, KM_LOWOUTLEVEL, "LEVEL: %s", low_level_help_text},
{ MT_FORM | MT_ADV_CALLBACK, 0, "MOD: %s", menu_smodulation_acb},
@@ -1638,12 +1618,19 @@ static const menuitem_t menu_lowoutputmode[] = {
static const menuitem_t menu_highoutputmode[] = {
{ MT_FORM | MT_ADV_CALLBACK, 0, "HIGH OUTPUT %s", menu_outputmode_acb},
+#ifdef TINYSA4
{ MT_FORM | MT_SUBMENU, 255, S_RARROW" Settings", menu_settings3},
+#endif
{ MT_FORM | MT_KEYPAD, KM_CENTER, center_text, "240MHz..960MHz"},
// { MT_FORM | MT_ADV_CALLBACK, 0, "LEVEL: %+ddBm", menu_sdrive_acb},
{ MT_FORM | MT_KEYPAD, KM_HIGHOUTLEVEL, "LEVEL: %s", low_level_help_text /* "-76..-6" */},
{ MT_FORM | MT_ADV_CALLBACK, 0, "MOD: %s", menu_smodulation_acb},
+#ifdef TINYSA4
{ MT_FORM | MT_ADV_CALLBACK, 0, "%s", menu_sweep_acb},
+#else
+ { MT_FORM | MT_KEYPAD, KM_SPAN, "SPAN: %s", NULL},
+ { MT_FORM | MT_KEYPAD, KM_SWEEP_TIME,"SWEEP TIME: %s", "0..600 seconds"},
+#endif
{ MT_FORM | MT_KEYPAD, KM_OFFSET, "EXTERNAL AMP: %s", "-100..+100"},
{ MT_FORM | MT_CANCEL, 0, "MODE", NULL },
{ MT_FORM | MT_NONE, 0, NULL, NULL } // sentinel
@@ -1665,6 +1652,7 @@ static const menuitem_t menu_average[] = {
static const menuitem_t menu_rbw[] = {
{ MT_ADV_CALLBACK, 0, " AUTO", menu_rbw_acb},
+#ifdef TINYSA4
{ MT_ADV_CALLBACK, 1, "%sHz", menu_rbw_acb},
{ MT_ADV_CALLBACK, 2, "%sHz", menu_rbw_acb},
{ MT_ADV_CALLBACK, 3, "%sHz", menu_rbw_acb},
@@ -1673,6 +1661,14 @@ static const menuitem_t menu_rbw[] = {
{ MT_ADV_CALLBACK, 6, "%sHz", menu_rbw_acb},
{ MT_ADV_CALLBACK, 7, "%sHz", menu_rbw_acb},
{ MT_ADV_CALLBACK, 8, "%sHz", menu_rbw_acb},
+#else
+ { MT_ADV_CALLBACK, 1, "%4dkHz", menu_rbw_acb},
+ { MT_ADV_CALLBACK, 2, "%4dkHz", menu_rbw_acb},
+ { MT_ADV_CALLBACK, 3, "%4dkHz", menu_rbw_acb},
+ { MT_ADV_CALLBACK, 4, "%4dkHz", menu_rbw_acb},
+ { MT_ADV_CALLBACK, 5, "%4dkHz", menu_rbw_acb},
+ { MT_ADV_CALLBACK, 6, "%4dkHz", menu_rbw_acb},
+#endif
{ MT_CANCEL, 0, S_LARROW" BACK", NULL },
{ MT_NONE, 0, NULL, NULL } // sentinel
};
@@ -1847,7 +1843,9 @@ static const menuitem_t menu_sweep_points[] = {
{ MT_ADV_CALLBACK, 1, "%3d point", menu_points_acb },
{ MT_ADV_CALLBACK, 2, "%3d point", menu_points_acb },
{ MT_ADV_CALLBACK, 3, "%3d point", menu_points_acb },
+#ifdef TINYSA4
{ MT_ADV_CALLBACK, 4, "%3d point", menu_points_acb },
+#endif
{ MT_CANCEL, 0, S_LARROW" BACK", NULL },
{ MT_NONE, 0, NULL, NULL } // sentinel
};
@@ -1856,32 +1854,29 @@ static const menuitem_t menu_sweep_speed[] =
{
{ MT_ADV_CALLBACK, SD_NORMAL, "NORMAL", menu_scanning_speed_acb}, // order must match definition of enum
{ MT_ADV_CALLBACK, SD_PRECISE, "PRECISE", menu_scanning_speed_acb},
+#ifdef TINYSA4
{ MT_ADV_CALLBACK, SD_FAST, "FAST", menu_scanning_speed_acb},
+#else
+ { MT_ADV_CALLBACK | MT_LOW,SD_FAST, "FAST", menu_scanning_speed_acb},
+#endif
{ MT_KEYPAD, KM_SWEEP_TIME, "SWEEP\nTIME", "0..600s, 0=disable"}, // This must be item 3 to match highlighting
{ MT_SUBMENU, 0, "SWEEP\nPOINTS", menu_sweep_points},
+#ifdef TINYSA4
{ MT_KEYPAD, KM_FAST_SPEEDUP,"FAST\nSPEEDUP", "2..20, 0=disable"},
+#else
+ { MT_KEYPAD | MT_LOW,KM_FAST_SPEEDUP,"FAST\nSPEEDUP", "2..20, 0=disable"},
+#endif
{ MT_CANCEL, 0, S_LARROW" BACK", NULL },
{ MT_NONE, 0, NULL, NULL } // sentinel
};
-static const menuitem_t menu_settings4[] =
-{
- { MT_ADV_CALLBACK, 0, "DEBUG\nFREQ", menu_debug_freq_acb},
-#if 1 // only used during development
- { MT_KEYPAD, KM_COR_AM, "COR\nAM", "Enter AM modulation correction"},
- { MT_KEYPAD, KM_COR_WFM, "COR\nWFM", "Enter WFM modulation correction"},
- { MT_KEYPAD, KM_COR_NFM, "COR\nNFM", "Enter NFM modulation correction"},
-#endif
-#ifdef __HARMONIC__
- { MT_SUBMENU,0, "HARMONIC", menu_harmonic},
+#ifdef TINYSA4
+static const menuitem_t menu_settings4[];
#endif
- { MT_SUBMENU, 0, S_RARROW" MORE", menu_settings3},
- { MT_CANCEL, 0, S_LARROW" BACK", NULL },
- { MT_NONE, 0, NULL, NULL } // sentinel
-};
static const menuitem_t menu_settings3[] =
{
+#ifdef TINYSA4
// { MT_KEYPAD, KM_GRIDLINES, "MINIMUM\nGRIDLINES", "Enter minimum horizontal grid divisions"},
{ MT_ADV_CALLBACK, 0, "ADF OUT", menu_adf_out_acb},
{ MT_KEYPAD, KM_LPF, "ULTRA\nSTART", "Enter ULTRA mode start freq"},
@@ -1890,15 +1885,37 @@ static const menuitem_t menu_settings3[] =
{ MT_KEYPAD, KM_MOD, "MODULO", "Set MODULO"},
{ MT_KEYPAD, KM_CP, "CP", "Set CP"},
{ MT_ADV_CALLBACK | MT_LOW, 0, "ULTRA\nMODE", menu_settings_ultra_acb},
-
#ifdef __HAM_BAND__
{ MT_ADV_CALLBACK, 0, "HAM\nBANDS", menu_settings_ham_bands},
#endif
{ MT_SUBMENU, 0, S_RARROW" MORE", menu_settings4},
+#else
+ { MT_KEYPAD, KM_10MHZ, "CORRECT\nFREQUENCY", "Enter actual l0MHz frequency"},
+ { MT_KEYPAD, KM_GRIDLINES, "MINIMUM\nGRIDLINES", "Enter minimum horizontal grid divisions"},
+#ifdef __HAM_BAND__
+ { MT_ADV_CALLBACK, 0, "HAM\nBANDS", menu_settings_ham_bands},
+#endif
+#endif // TINYSA4
+ { MT_CANCEL, 0, S_LARROW" BACK", NULL },
+ { MT_NONE, 0, NULL, NULL } // sentinel
+};
+#ifdef TINYSA4
+static const menuitem_t menu_settings4[] =
+{
+ { MT_ADV_CALLBACK, 0, "DEBUG\nFREQ", menu_debug_freq_acb},
+#if 1 // only used during development
+ { MT_KEYPAD, KM_COR_AM, "COR\nAM", "Enter AM modulation correction"},
+ { MT_KEYPAD, KM_COR_WFM, "COR\nWFM", "Enter WFM modulation correction"},
+ { MT_KEYPAD, KM_COR_NFM, "COR\nNFM", "Enter NFM modulation correction"},
+#endif
+#ifdef __HARMONIC__
+ { MT_SUBMENU,0, "HARMONIC", menu_harmonic},
+#endif
+ { MT_SUBMENU, 0, S_RARROW" MORE", menu_settings3},
{ MT_CANCEL, 0, S_LARROW" BACK", NULL },
{ MT_NONE, 0, NULL, NULL } // sentinel
};
-
+#endif
static const menuitem_t menu_settings2[] =
{
@@ -1912,10 +1929,9 @@ static const menuitem_t menu_settings2[] =
#else
{ MT_KEYPAD, KM_NOISE, "NOISE\nLEVEL", "2..20 dB"},
#endif
-#ifdef __ULTRA__
- { MT_SUBMENU,0, "HARMONIC", menu_harmonic},
-#endif
+#ifdef TINYSA4
{ MT_KEYPAD, KM_30MHZ, "ACTUAL\n30MHz", "Enter actual l0MHz frequency"},
+#endif
{ MT_SUBMENU, 0, S_RARROW" MORE", menu_settings3},
{ MT_CANCEL, 0, S_LARROW" BACK", NULL },
{ MT_NONE, 0, NULL, NULL } // sentinel
@@ -1928,7 +1944,11 @@ static const menuitem_t menu_settings[] =
{ MT_KEYPAD | MT_LOW, KM_IF, "IF FREQ", "0=auto IF"},
{ MT_SUBMENU,0, "SCAN SPEED", menu_scanning_speed},
{ MT_KEYPAD, KM_REPEAT, "SAMPLE\nREPEAT", "1..100"},
+#ifdef TINYSA4
{ MT_SUBMENU | MT_LOW,0, "MIXER\nDRIVE", menu_mixer_drive},
+#else
+ { MT_SUBMENU | MT_LOW,0, "MIXER\nDRIVE", menu_lo_drive},
+#endif
{ MT_SUBMENU, 0, S_RARROW" MORE", menu_settings2},
{ MT_CANCEL, 0, S_LARROW" BACK", NULL },
{ MT_NONE, 0, NULL, NULL } // sentinel
@@ -2085,7 +2105,9 @@ static const menuitem_t menu_level[] = {
// { MT_SUBMENU,0, "CALC", menu_average},
{ MT_SUBMENU, 0, "UNIT", menu_unit},
{ MT_KEYPAD, KM_OFFSET, "EXTERNAL\nAMP",NULL},
+#ifdef TINYSA4
{ MT_ADV_CALLBACK | MT_LOW ,0,"LNA", menu_extra_lna_acb},
+ #endif
{ MT_SUBMENU, 0, "TRIGGER", menu_trigger},
{ MT_CANCEL, 0, S_LARROW" BACK",NULL },
{ MT_NONE, 0, NULL, NULL } // sentinel
@@ -2114,28 +2136,10 @@ static const menuitem_t menu_mode[] = {
{ MT_FORM | MT_ADV_CALLBACK | MT_ICON, I_CONNECT+I_GEN, "Cal. output: %s", menu_sreffer_acb},
// { MT_SUBMENU, 0, "EXPERT\nCONFIG", menu_settings3},
-#ifdef __ULTRA__
- { MT_FORM | MT_CALLBACK | MT_ICON, I_LOW_INPUT+I_SA, "ULTRA HIGH INPUT",menu_mode_cb},
-#endif
// { MT_FORM | MT_CANCEL, 0, S_RARROW" BACK", NULL },
{ MT_FORM | MT_NONE, 0, NULL, NULL } // sentinel
};
-#ifdef __ULTRA__
-const menuitem_t menu_topultra[] = {
- { MT_CALLBACK, 0, "RESET", menu_autosettings_cb},
- { MT_SUBMENU, 0, "FREQ", menu_stimulus},
- { MT_SUBMENU, 0, "LEVEL", menu_level},
- { MT_SUBMENU, 0, "DISPLAY", menu_display},
- { MT_SUBMENU, 0, "MARKER", menu_marker},
- { MT_SUBMENU, 0, "MEASURE", menu_measure},
- { MT_SUBMENU, 0, "SETTINGS", menu_settings},
- { MT_CANCEL, 0, "MODE",NULL},
- { MT_NONE, 0, NULL, NULL } // sentinel,
- // MENUITEM_CLOSE,
-};
-#endif
-
static const menuitem_t menu_top[] = {
{ MT_SUBMENU, 0, "PRESET", menu_load_preset},
{ MT_SUBMENU, 0, "FREQUENCY", menu_stimulus},
@@ -2230,6 +2234,7 @@ static void fetch_numeric_target(void)
uistat.value = setting.frequency_IF;
plot_printf(uistat.text, sizeof uistat.text, "%3.3fMHz", uistat.value / 1000000.0);
break;
+#ifdef TINYSA4
case KM_IF2:
uistat.value = config.frequency_IF2;
plot_printf(uistat.text, sizeof uistat.text, "%3.3fMHz", uistat.value / 1000000.0);
@@ -2242,6 +2247,7 @@ static void fetch_numeric_target(void)
uistat.value = ADF4350_modulo;
plot_printf(uistat.text, sizeof uistat.text, "%4d", uistat.value);
break;
+#endif
case KM_SAMPLETIME:
uistat.value = setting.step_delay;
plot_printf(uistat.text, sizeof uistat.text, "%3dus", ((int32_t)uistat.value));
@@ -2257,10 +2263,10 @@ static void fetch_numeric_target(void)
case KM_LOWOUTLEVEL:
uistat.value = get_level(); // compensation for dB offset during low output mode
int end_level = ((int32_t)uistat.value)+setting.level_sweep;
- if (end_level < SL_GENLOW_LEVEL_MIN + config.low_level_output_offset)
- end_level = SL_GENLOW_LEVEL_MIN + config.low_level_output_offset;
- if (end_level > SL_GENLOW_LEVEL_MIN + SL_GENLOW_LEVEL_RANGE + config.low_level_output_offset)
- end_level = SL_GENLOW_LEVEL_MIN + SL_GENLOW_LEVEL_RANGE + config.low_level_output_offset;
+ if (end_level < level_min())
+ end_level = level_min();
+ if (end_level > level_max())
+ end_level = level_max();
uistat.value += setting.offset;
end_level += setting.offset;
if (setting.level_sweep != 0)
@@ -2283,18 +2289,27 @@ static void fetch_numeric_target(void)
plot_printf(uistat.text, sizeof uistat.text, "%5d", ((int32_t)uistat.value));
break;
#endif
+#ifdef TINYSA4
case KM_LPF:
uistat.value = config.ultra_threshold;
plot_printf(uistat.text, sizeof uistat.text, "%3.6fMHz", uistat.value / 1000000.0);
break;
+#endif
case KM_NOISE:
uistat.value = setting.noise;
plot_printf(uistat.text, sizeof uistat.text, "%3d", ((int32_t)uistat.value));
break;
+#ifdef TINYSA4
case KM_30MHZ:
uistat.value = config.setting_frequency_30mhz;
plot_printf(uistat.text, sizeof uistat.text, "%3.6fMHz", uistat.value / 1000000.0);
break;
+#else
+ case KM_10MHZ:
+ uistat.value = config.setting_frequency_10mhz;
+ plot_printf(uistat.text, sizeof uistat.text, "%3.6fMHz", uistat.value / 1000000.0);
+ break;
+#endif
case KM_OFFSET:
uistat.value = setting.offset;
plot_printf(uistat.text, sizeof uistat.text, "%.1fdB", uistat.value);
@@ -2378,6 +2393,7 @@ set_numeric_value(void)
set_IF(uistat.value);
// config_save();
break;
+#ifdef TINYSA4
case KM_IF2:
set_IF2(uistat.value);
// config_save();
@@ -2393,6 +2409,7 @@ set_numeric_value(void)
ADF4351_CP((int)uistat.value);
// config_save();
break;
+#endif
case KM_SAMPLETIME:
set_step_delay(uistat.value);
break;
@@ -2422,16 +2439,24 @@ set_numeric_value(void)
set_attack(uistat.value);
break;
#endif
+#ifdef TINYSA4
case KM_LPF:
config.ultra_threshold = uistat.value;
config_save();
break;
+#endif
case KM_NOISE:
set_noise(uistat.value);
break;
+#ifdef TINYSA4
case KM_30MHZ:
set_30mhz(uistat.value);
break;
+#else
+ case KM_10MHZ:
+ set_10mhz(uistat.value);
+ break;
+#endif
case KM_OFFSET:
set_offset(uistat.value);
break;
@@ -2459,7 +2484,7 @@ set_numeric_value(void)
case KM_MODULATION:
set_modulation_frequency((int)uistat.value);
break;
-#if 1
+#ifdef TINYSA4
case KM_COR_AM:
config.cor_am = -(int)uistat.value;
config_save();
@@ -2778,13 +2803,13 @@ redraw_cal_status:
ili9341_drawstring(buf, x, y);
y += YSTEP + YSTEP/2 ;
#endif
-
+#ifdef TINYSA
if (setting.extra_lna){
ili9341_set_foreground(LCD_BRIGHT_COLOR_GREEN);
y = add_quick_menu("LNA:ON", x, y, (menuitem_t *)menu_level);
y += YSTEP;
}
-
+#endif
// Cal output
if (setting.refer >= 0) {
ili9341_set_foreground(LCD_BRIGHT_COLOR_GREEN);
@@ -2873,7 +2898,11 @@ redraw_cal_status:
// Version
y += YSTEP + YSTEP/2 ;
+#ifdef TINYSA4
strncpy(buf,&VERSION[11], BLEN-1);
+#else
+ strncpy(buf,&VERSION[8], BLEN-1);
+#endif
ili9341_drawstring(buf, x, y);