diff --git a/tracker/software/cfg/pp10a/portab.c b/tracker/software/cfg/pp10a/portab.c index 2d84f721..b6918159 100644 --- a/tracker/software/cfg/pp10a/portab.c +++ b/tracker/software/cfg/pp10a/portab.c @@ -41,20 +41,20 @@ const si446x_mcucfg_t radio1_cfg = { .nirq = LINE_RADIO_NIRQ, .sdn = LINE_RADIO_SDN, .cs = LINE_RADIO_CS, - .spi = PKT_RADIO_SPI, + .spi = PKT_RADIO1_SPI, .icu = RADIO1_ICU_DRIVER, .alt = (PAL_MODE_INPUT | PAL_MODE_ALTERNATE(2)), .cfg = { ICU_INPUT_ACTIVE_HIGH, - ICU_COUNT_FREQUENCY, /* ICU clock frequency. */ + ICU_COUNT_FREQUENCY, /**< ICU clock frequency. */ #if LINE_PWM_MIRROR != PAL_NOLINE - pktRadioICUWidth, /* ICU width callback. */ + pktRadioICUWidth, /**< ICU width callback. */ #else - NULL, /* ICU width callback. */ + NULL, /**< ICU width callback. */ #endif - pktRadioICUPeriod, /* ICU period callback. */ - pktRadioICUOverflow, /* ICU overflow callback. */ - ICU_CHANNEL_1, /* Timer channel 0. */ + pktRadioICUPeriod, /**< ICU period callback. */ + pktRadioICUOverflow, /**< ICU overflow callback. */ + ICU_CHANNEL_1, /**< Timer channel. */ 0 } }; @@ -67,17 +67,20 @@ si446x_data_t radio1_dat = { */ }; +/* List of bands in this radio. */ +const radio_band_t *const radio_bands[] = { + (radio_band_t *const)&band_2m, + NULL +}; + /* Radios on this board. */ const radio_config_t radio_list[] = { { /* Radio #1 */ .unit = PKT_RADIO_1, .type = SI446X, - .cfg = (si446x_mcucfg_t * const)&radio1_cfg, + .cfg = (si446x_mcucfg_t *const)&radio1_cfg, .dat = (si446x_data_t *)&radio1_dat, - .bands = { - (radio_band_t * const)&band_2m, - NULL - } + .bands = (radio_band_t **const)radio_bands }, /* End radio1 */ { .unit = PKT_RADIO_NONE diff --git a/tracker/software/cfg/pp10a/portab.h b/tracker/software/cfg/pp10a/portab.h index da74b0b9..a006e090 100644 --- a/tracker/software/cfg/pp10a/portab.h +++ b/tracker/software/cfg/pp10a/portab.h @@ -18,17 +18,15 @@ */ #define SERIAL_CFG_DEBUG_DRIVER &SD3 -//#define USE_SPI_ATTACHED_RADIO TRUE - /* - * TODO: Need to use radio unit ID to set assigned GPIO & SPI. - * Only if there is a multi radio board... + * SPI definitions */ +#define SPI_BUS1_DRIVER &SPID3 /* * Radio SPI definitions. */ -#define PKT_RADIO_SPI &SPID3 +#define PKT_RADIO1_SPI SPI_BUS1_DRIVER // Camera pins #define LINE_CAM_XCLK PAL_LINE(GPIOC, 9U) @@ -109,6 +107,7 @@ #define LINE_SPI_MISO PAL_LINE(GPIOB, 4U) #define LINE_SPI_MOSI PAL_LINE(GPIOB, 5U) +/* TODO: Move into pktradio.h */ #define BAND_MIN_2M_FREQ 144000000 /* Minimum allowed frequency in Hz */ #define BAND_MAX_2M_FREQ 148000000 /* Maximum allowed frequency in Hz */ #define BAND_STEP_2M_HZ 12500 @@ -119,13 +118,16 @@ #define BAND_DEF_70CM_APRS 439100000 /* Default frequency in Hz. */ #define DEFAULT_OPERATING_FREQ 144800000 +#if DEFAULT_OPERATING_FREQ < BAND_MIN_2M_FREQ +#error "Default operating frequency must be an absolute in Hz" +#endif /* Si446x clock setup. */ #define Si446x_CLK STM32_HSECLK /* Oscillator frequency in Hz */ #define Si446x_CLK_OFFSET 22 /* Oscillator frequency drift in ppm */ #define Si446x_CLK_TCXO_EN true /* Set this true, if a TCXO is used, false for XTAL */ -#define NUM_BANDS_PER_RADIO 2 +//#define NUM_BANDS_PER_RADIO 2 /* LED status indicators (set to PAL_NOLINE if not available). */ #define LINE_OVERFLOW_LED PAL_NOLINE @@ -246,14 +248,6 @@ /* Module data structures and types. */ /*===========================================================================*/ -typedef struct radioConfig { - radio_unit_t unit; - radio_type_t type; - void *cfg; - void *dat; - radio_band_t *bands[NUM_BANDS_PER_RADIO]; -} radio_config_t; - /*===========================================================================*/ /* Module macros. */ /*===========================================================================*/ diff --git a/tracker/software/cfg/pp10b/portab.c b/tracker/software/cfg/pp10b/portab.c index 8a28c4ec..8eca4679 100644 --- a/tracker/software/cfg/pp10b/portab.c +++ b/tracker/software/cfg/pp10b/portab.c @@ -41,7 +41,7 @@ const si446x_mcucfg_t radio1_cfg = { .nirq = LINE_RADIO_NIRQ, .sdn = LINE_RADIO_SDN, .cs = LINE_RADIO_CS, - .spi = PKT_RADIO_SPI, + .spi = PKT_RADIO1_SPI, .icu = RADIO1_ICU_DRIVER, .alt = (PAL_MODE_INPUT | PAL_MODE_ALTERNATE(2)), .cfg = { @@ -64,21 +64,25 @@ si446x_data_t radio1_dat = { // TODO: Move part and func structs into here and add functions to get }; -/* Array of radios on this board. */ + +/* List of bands in this radio. */ +const radio_band_t *const radio_bands[] = { + (radio_band_t *const)&band_2m, + NULL +}; + +/* Radios on this board. */ const radio_config_t radio_list[] = { { /* Radio #1 */ .unit = PKT_RADIO_1, .type = SI446X, - .cfg = (si446x_mcucfg_t * const)&radio1_cfg, - .dat = (si446x_data_t *)&radio1_dat, - .bands = { - (radio_band_t * const)&band_2m, - NULL - } + .cfg = (si446x_mcucfg_t *const)&radio1_cfg, + .dat = (si446x_data_t *)&radio1_dat, + .bands = (radio_band_t **const)radio_bands }, /* End radio1 */ { .unit = PKT_RADIO_NONE - } /* End radios. */ + } }; /** diff --git a/tracker/software/cfg/pp10b/portab.h b/tracker/software/cfg/pp10b/portab.h index c8d67d44..81ebfd18 100644 --- a/tracker/software/cfg/pp10b/portab.h +++ b/tracker/software/cfg/pp10b/portab.h @@ -23,10 +23,15 @@ * Only if there is a multi radio board... */ +/* + * SPI definitions + */ +#define SPI_BUS1_DRIVER &SPID3 + /* * Radio SPI definitions. */ -#define PKT_RADIO_SPI &SPID3 +#define PKT_RADIO1_SPI SPI_BUS1_DRIVER // Camera pins #define LINE_CAM_XCLK PAL_LINE(GPIOC, 9U) @@ -108,6 +113,7 @@ #define LINE_SPI_MISO PAL_LINE(GPIOB, 4U) #define LINE_SPI_MOSI PAL_LINE(GPIOB, 5U) +/* TODO: Move into pktradio.h */ #define BAND_MIN_2M_FREQ 144000000 /* Minimum allowed frequency in Hz */ #define BAND_MAX_2M_FREQ 148000000 /* Maximum allowed frequency in Hz */ #define BAND_STEP_2M_HZ 12500 @@ -118,13 +124,16 @@ #define BAND_DEF_70CM_APRS 439100000 /* Default frequency in Hz. */ #define DEFAULT_OPERATING_FREQ 144800000 +#if DEFAULT_OPERATING_FREQ < BAND_MIN_2M_FREQ +#error "Default operating frequency must be an absolute in Hz" +#endif /* Si446x clock setup. */ #define Si446x_CLK STM32_HSECLK /* Oscillator frequency in Hz */ #define Si446x_CLK_OFFSET 22 /* Oscillator frequency drift in ppm */ #define Si446x_CLK_TCXO_EN true /* Set this true, if a TCXO is used, false for XTAL */ -#define NUM_BANDS_PER_RADIO 2 +//#define NUM_BANDS_PER_RADIO 2 /* LED status indicators (set to PAL_NOLINE if not available). */ #define LINE_OVERFLOW_LED PAL_NOLINE @@ -243,14 +252,6 @@ /* Module data structures and types. */ /*===========================================================================*/ -typedef struct radioConfig { - radio_unit_t unit; - radio_type_t type; - void *cfg; - void *dat; - radio_band_t *bands[NUM_BANDS_PER_RADIO]; -} radio_config_t; - /*===========================================================================*/ /* Module macros. */ /*===========================================================================*/ diff --git a/tracker/software/make/pp10a.make b/tracker/software/make/pp10a.make index a311e623..81582381 100644 --- a/tracker/software/make/pp10a.make +++ b/tracker/software/make/pp10a.make @@ -216,8 +216,8 @@ CPPWARN = -Wall -Wextra -Wundef # List all user C define here, like -D_DEBUG=1 UDEFS = -D_GNU_SOURCE -DARM_MATH_CM4 -DSHELL_CMD_TEST_ENABLED=0 \ -DSHELL_CMD_EXIT_ENABLED=1 -DUSB_TRACE_LEVEL=5 \ - -DSHELL_CMD_MEM_ENABLED=0 - # -DDISABLE_HW_WATCHDOG=1 + -DSHELL_CMD_MEM_ENABLED=0 + #-DDISABLE_HW_WATCHDOG=1 # Define ASM defines here UADEFS = diff --git a/tracker/software/source/config/config.c b/tracker/software/source/config/config.c index 5ef24eab..4cf8b93a 100644 --- a/tracker/software/source/config/config.c +++ b/tracker/software/source/config/config.c @@ -55,15 +55,15 @@ const conf_t conf_flash_default = { // Primary image app .img_pri = { .svc_conf = { - .active = false, - .cycle = TIME_S2I(60 * 30), + .active = true, + .cycle = TIME_S2I(60 * 5), .init_delay = TIME_S2I(90), - .send_spacing = TIME_S2I(30) + .send_spacing = TIME_S2I(5) }, .radio_conf = { .pwr = 0x7F, - .freq = APRS_FREQ_AUSTRALIA, - .mod = MOD_AFSK, + .freq = 144800000, + .mod = MOD_2FSK, .cca = 0x4F }, @@ -81,7 +81,7 @@ const conf_t conf_flash_default = { // Secondary image app .img_sec = { .svc_conf = { - .active = false, + .active = true, .cycle = TIME_S2I(60 * 15), .init_delay = TIME_S2I(60 * 1), .send_spacing = TIME_S2I(30) diff --git a/tracker/software/source/drivers/ov5640.c b/tracker/software/source/drivers/ov5640.c index 3e61ddbd..143364a0 100644 --- a/tracker/software/source/drivers/ov5640.c +++ b/tracker/software/source/drivers/ov5640.c @@ -983,13 +983,14 @@ void vsync_cb(void *arg) { * Other drivers using resources that can cause DMA competition are locked. */ msg_t OV5640_LockResourcesForCapture(void) { - + /* TODO: have to make this a loop which would handle multiple receivers. */ + /* Acquire radio after any TX completes. */ msg_t msg = pktAcquireRadio(PKT_RADIO_1, TIME_INFINITE); if(msg != MSG_OK) { return msg; } I2C_Lock(); - /* TODO: have to make this a loop which would handle multiple receivers. */ + pktLLDradioPauseDecoding(PKT_RADIO_1); //pktPauseDecoding(PKT_RADIO_1); /* Hold TRACE output on USB. */ @@ -1009,9 +1010,13 @@ void OV5640_UnlockResourcesForCapture(void) { /* TODO: have to make this a loop which would handle multiple receivers. */ pktLLDradioResumeDecoding(PKT_RADIO_1); //pktResumeDecoding(PKT_RADIO_1); + /* Enable TX tasks to run. */ pktReleaseRadio(PKT_RADIO_1); } +/** + * + */ uint32_t OV5640_Capture(uint8_t* buffer, uint32_t size) { /* @@ -1030,8 +1035,8 @@ uint32_t OV5640_Capture(uint8_t* buffer, uint32_t size) { dma_capture_t dma_control = {0}; /* Setup DMA for transfer on timer CC tigger. - * For TIM8 this DMA2 stream 2, channel 7. - * Use PL 3 as PCLCK rate is high. + * For TIM8 this is DMA2 stream 2, channel 7. + * Use PL 3 as camera PCLK rate is high and we need priority service. */ dma_control.dmastp = STM32_DMA_STREAM(STM32_DMA_STREAM_ID(2, 2)); uint32_t dmamode = STM32_DMA_CR_CHSEL(7) | diff --git a/tracker/software/source/drivers/sd.c b/tracker/software/source/drivers/sd.c index e8e35893..53e77e8c 100644 --- a/tracker/software/source/drivers/sd.c +++ b/tracker/software/source/drivers/sd.c @@ -39,10 +39,10 @@ bool initSD(void) }; // MMC/SD over SPI driver configuration - static MMCConfig mmccfg = {&SPID3, &ls_spicfg, &hs_spicfg}; + static MMCConfig mmccfg = {SPI_BUS1_DRIVER, &ls_spicfg, &hs_spicfg}; // Check SD card presence - spiAcquireBus(&SPID3); + spiAcquireBus(SPI_BUS1_DRIVER); // Init MMC mmcObjectInit(&MMCD1); @@ -55,7 +55,7 @@ bool initSD(void) TRACE_INFO("SD > SD card connection OK"); sdInitialized = true; } - spiReleaseBus(&SPID3); + spiReleaseBus(SPI_BUS1_DRIVER); return sdInitialized; } @@ -65,7 +65,7 @@ bool writeBufferToFile(const char *filename, const uint8_t *buffer, uint32_t len if(!sdInitialized) return false; - spiAcquireBus(&SPID3); + spiAcquireBus(SPI_BUS1_DRIVER); static FATFS fs; static FIL fdst; @@ -125,7 +125,7 @@ bool writeBufferToFile(const char *filename, const uint8_t *buffer, uint32_t len } } - spiReleaseBus(&SPID3); + spiReleaseBus(SPI_BUS1_DRIVER); return gres; } diff --git a/tracker/software/source/drivers/si446x_patch.h b/tracker/software/source/drivers/si4463_patch.h similarity index 94% rename from tracker/software/source/drivers/si446x_patch.h rename to tracker/software/source/drivers/si4463_patch.h index 97734e8c..603d5a56 100644 --- a/tracker/software/source/drivers/si446x_patch.h +++ b/tracker/software/source/drivers/si4463_patch.h @@ -10,10 +10,10 @@ // SIZE=512 // CRCT=0x714b -#define SI446X_PATCH_ROMID 00 -#define SI446X_PATCH_ID 00 +#define SI4463_PATCH_ROMID 0x06 +#define SI4463_PATCH_ID 0xCA90 -#define SI446X_PATCH_CMDS \ +#define SI4463_PATCH_CMDS \ 0x08,0x04,0x21,0x71,0x4B,0x00,0x00,0xDC,0x95, \ 0x08,0x05,0xA6,0x22,0x21,0xF0,0x41,0x5B,0x26, \ 0x08,0xE2,0x2F,0x1C,0xBB,0x0A,0xA8,0x94,0x28, \ diff --git a/tracker/software/source/drivers/si446x.c b/tracker/software/source/drivers/si446x.c index 32e60640..3d4af120 100644 --- a/tracker/software/source/drivers/si446x.c +++ b/tracker/software/source/drivers/si446x.c @@ -5,30 +5,20 @@ */ #include "pktconf.h" -#ifndef PKT_IS_TEST_PROJECT #include "debug.h" -#endif - -#ifndef PKT_IS_TEST_PROJECT #include "radio.h" -#endif - #include "geofence.h" -#include "si446x_patch.h" +#include "si4463_patch.h" /*===========================================================================*/ /* Module local variables. */ /*===========================================================================*/ -/* TODO: Has to move into radio data struct. */ -//static int16_t lastTemp = 0x7FFF; - /*===========================================================================*/ /* Module constants. */ /*===========================================================================*/ - /*===========================================================================*/ /* Module exported variables. */ /*===========================================================================*/ @@ -37,8 +27,8 @@ /* Module local definitions. */ /*===========================================================================*/ -static const uint8_t Radio_Patch_Data_Array[] = { - SI446X_PATCH_CMDS, +static const uint8_t Si4463_Patch_Data_Array[] = { + SI4463_PATCH_CMDS, 0x00 }; @@ -81,7 +71,7 @@ static SPIDriver *Si446x_spiSetupBus(const radio_unit_t radio, /** * SPI write which uses CTS presented on radio GPIO1. * Used when starting the radio up from shutdown state. - * @pre The MCU GPIO pin connected to 446x GPIO1 must be pre-configured. + * @pre The MCU GPIO pin connected to 446x GPIO1 must be configured as input. */ static bool Si446x_writeBoot(const radio_unit_t radio, const uint8_t* txData, uint32_t len) { @@ -91,7 +81,7 @@ static bool Si446x_writeBoot(const radio_unit_t radio, SPIDriver *spip = Si446x_spiSetupBus(radio, &ls_spicfg); spiStart(spip, &ls_spicfg); - /* Poll for CTS. */ + /* Poll for CTS with timeout of 100mS. */ ioline_t cts = Si446x_getConfig(radio)->gpio1; uint8_t timeout = 100; do { @@ -107,7 +97,7 @@ static bool Si446x_writeBoot(const radio_unit_t radio, return false; } - /* Transfer data. No need to check CTS.*/ + /* Transfer data now there is CTS.*/ spiSelect(spip); spiSend(spip, len, txData); spiUnselect(spip); @@ -131,7 +121,7 @@ static bool Si446x_write(const radio_unit_t radio, SPIDriver *spip = Si446x_spiSetupBus(radio, &ls_spicfg); spiStart(spip, &ls_spicfg); - /* Poll for CTS. */ + /* Poll for CTS with timeout of 100mS. */ uint8_t timeout = 100; uint8_t rx_ready[] = {Si446x_READ_CMD_BUFF, 0x00}; do { @@ -174,7 +164,7 @@ static bool Si446x_readBoot(const radio_unit_t radio, /* Acquire bus and get SPI Driver object. */ SPIDriver *spip = Si446x_spiSetupBus(radio, &ls_spicfg); - /* Poll for CTS on GPIO1 from radio. */ + /* Poll for CTS with timeout of 100mS. */ ioline_t cts = Si446x_getConfig(radio)->gpio1; uint8_t timeout = 100; while(palReadLine(cts) != PAL_HIGH && timeout--) { @@ -238,6 +228,7 @@ static bool Si446x_read(const radio_unit_t radio, * Poll command buffer waiting for CTS from the READ_CMD_BUFF command. * This command does not itself cause CTS to report busy. * Allocate a buffer to use for CTS check. + * Timeout after 100mS waiting for CTS. */ uint8_t timeout = 100; uint8_t rx_ready[] = {Si446x_READ_CMD_BUFF, 0x00}; @@ -268,6 +259,7 @@ static bool Si446x_read(const radio_unit_t radio, * Poll waiting for CTS again using the READ_CMD_BUFF command. * Once CTS is received the response data is ready in the rx data buffer. * The buffer contains the command, CTS and 0 - 16 bytes of response. + * Timeout after 100mS waiting for CTS. */ timeout = 100; do { @@ -399,10 +391,10 @@ static bool Si446x_init(const radio_unit_t radio) { chThdSleep(TIME_MS2I(10)); Si446x_radioStartup(radio); uint16_t i = 0; - while(Radio_Patch_Data_Array[i] != 0) { - Si446x_writeBoot(radio, &Radio_Patch_Data_Array[i + 1], - Radio_Patch_Data_Array[i]); - i += Radio_Patch_Data_Array[i] + 1; + while(Si4463_Patch_Data_Array[i] != 0) { + Si446x_writeBoot(radio, &Si4463_Patch_Data_Array[i + 1], + Si4463_Patch_Data_Array[i]); + i += Si4463_Patch_Data_Array[i] + 1; } const uint8_t init_command[] = {Si446x_POWER_UP, 0x81, (Si446x_CLK_TCXO_EN & 0x1), @@ -573,12 +565,17 @@ bool Si446x_conditional_init(const radio_unit_t radio) { /* * Set radio NCO registers for frequency. - * This function also collects the chip temperature data. + * This function also collects the chip temperature data at the moment. + * TODO: Move temperature reading to??? */ bool Si446x_setBandParameters(const radio_unit_t radio, radio_freq_t freq, channel_hz_t step) { + /* + * TODO: The driver should not check for DYNAMIC. + * All frequencies passed to radio should be absolute. + */ if(freq == FREQ_APRS_DYNAMIC) { /* Get transmission frequency by geofencing. */ freq = getAPRSRegionFrequency(); @@ -949,6 +946,7 @@ static bool Si446x_transmit(const radio_unit_t radio, radio_squelch_t rssi, sysinterval_t cca_timeout) { + /* Get an absolute operating frequency in Hz. */ radio_freq_t op_freq = pktComputeOperatingFrequency(radio, freq, step, chan, RADIO_TX); @@ -1087,11 +1085,12 @@ bool Si4464_resumeReceive(const radio_unit_t radio, mod_t rx_mod) { bool ret = true; + /* Get an absolute operating frequency in Hz. */ radio_freq_t op_freq = pktComputeOperatingFrequency(radio, rx_frequency, - rx_step, - rx_chan, - RADIO_RX); + rx_step, + rx_chan, + RADIO_RX); TRACE_INFO( "SI > Enable reception %d.%03d MHz (ch %d)," @@ -1168,7 +1167,9 @@ static uint8_t Si446x_getUpsampledNRZIbits(up_sampler_t *upsampler, */ static void Si446x_transmitTimeoutI(thread_t *tp) { /* Tell the thread to terminate. */ - chEvtSignal(tp, SI446X_EVT_TX_TIMEOUT); + chSysLockFromISR(); + chEvtSignalI(tp, SI446X_EVT_TX_TIMEOUT); + chSysUnlockFromISR(); } /* @@ -1201,6 +1202,7 @@ THD_FUNCTION(bloc_si_fifo_feeder_afsk, arg) { /* Initialize radio. */ Si446x_conditional_init(radio); + /* Base frequency is an absolute frequency in Hz. */ Si446x_setBandParameters(radio, rto->base_frequency, rto->step_hz); @@ -1459,6 +1461,7 @@ THD_FUNCTION(bloc_si_fifo_feeder_fsk, arg) { /* Set 446x back to READY from RX (if active). */ Si446x_pauseReceive(radio); + /* Base frequency is an absolute frequency in Hz. */ Si446x_setBandParameters(radio, rto->base_frequency, rto->step_hz); /* Set parameters for 2FSK transmission. */ diff --git a/tracker/software/source/math/geofence.c b/tracker/software/source/math/geofence.c index 7b6a1065..9fb6988e 100644 --- a/tracker/software/source/math/geofence.c +++ b/tracker/software/source/math/geofence.c @@ -658,7 +658,9 @@ uint32_t getAPRSRegionFrequency() { // Position unknown if(point == NULL || (point->gps_lat == 0 && point->gps_lon == 0)) - return conf_sram.freq; + //return conf_sram.freq; + // Return code and let pktradio figure out what to do. + return FREQ_APRS_DEFAULT; // America 144.390 MHz if(isPointInAmerica(point->gps_lat, point->gps_lon)) diff --git a/tracker/software/source/pkt/channels/rxpwm.c b/tracker/software/source/pkt/channels/rxpwm.c index ca95b662..49cb29a0 100644 --- a/tracker/software/source/pkt/channels/rxpwm.c +++ b/tracker/software/source/pkt/channels/rxpwm.c @@ -207,7 +207,7 @@ void pktDisableRadioPWM(const radio_unit_t radio) { /* * Reschedule is required to avoid a "priority order violation". * TODO: Investigate the iclass time used. Might be systick related? */ - chSchRescheduleS(); + //chSchRescheduleS(); chSysUnlock(); } @@ -449,7 +449,10 @@ void pktOpenPWMChannelI(ICUDriver *myICU, eventflags_t evt) { * @api */ void pktSleepICUI(ICUDriver *myICU) { - /* All we do is stop capture. */ + /** + * Each ICU instance is attached to only one radio. + * All we do is stop the capture for that ICU instance. + */ icuStopCaptureI(myICU); } @@ -464,9 +467,10 @@ void pktSleepICUI(ICUDriver *myICU) { */ void pktICUInactivityTimeout(ICUDriver *myICU) { - /* This will stop ICU to save power. + /* * The ICU notifications are enabled and disabled during normal operation. - * This timer will shutdown the ICU timer after an idle period. + * This timer shuts down the ICU timer after an idle period. + * This saves a (probably insignificant) amount of MCU power. */ chSysLockFromISR(); AFSKDemodDriver *myDemod = myICU->link; @@ -527,7 +531,7 @@ void pktRadioCCALeadTimer(ICUDriver *myICU) { switch(cca) { case PAL_LOW: { /* - * CAA has dropped so it is a spike. + * CAA has dropped so it is a spike which is ignored. */ pktAddEventFlagsI(myHandler, EVT_RADIO_CCA_SPIKE); break; @@ -635,6 +639,7 @@ void pktRadioCCAInput(ICUDriver *myICU) { return; } +#if LINE_PWM_MIRROR != PAL_NOLINE /** * @brief Width callback from ICU driver. * @notes Called at ISR level. @@ -647,6 +652,7 @@ void pktRadioICUWidth(ICUDriver *myICU) { (void)myICU; pktWriteGPIOline(LINE_PWM_MIRROR, PAL_LOW); } +#endif /** * @brief Period callback from ICU driver. diff --git a/tracker/software/source/pkt/managers/pktradio.c b/tracker/software/source/pkt/managers/pktradio.c index 9528abf4..456a6acc 100644 --- a/tracker/software/source/pkt/managers/pktradio.c +++ b/tracker/software/source/pkt/managers/pktradio.c @@ -15,9 +15,8 @@ */ #include "pktconf.h" -#ifndef PKT_IS_TEST_PROJECT #include "radio.h" -#endif + #include "si446x.h" #include "debug.h" #include "geofence.h" @@ -30,14 +29,14 @@ const radio_band_t band_2m = { .start = BAND_MIN_2M_FREQ, .end = BAND_MAX_2M_FREQ, .step = BAND_STEP_2M_HZ, - .def_aprs = BAND_DEF_2M_APRS + //.def_aprs = BAND_DEF_2M_APRS }; const radio_band_t band_70cm = { .start = BAND_MIN_70CM_FREQ, .end = BAND_MAX_70CM_FREQ, .step = BAND_STEP_70CM_HZ, - .def_aprs = BAND_DEF_70CM_APRS + //.def_aprs = BAND_DEF_70CM_APRS }; /** @@ -54,7 +53,7 @@ const radio_band_t band_70cm = { * @notapi */ THD_FUNCTION(pktRadioManager, arg) { - /* When waiting for TX tasks to complete. */ + /* When waiting for TX tasks to complete if manager is terminating. */ #define PKT_RADIO_TX_TASK_RECHECK_WAIT_MS 100 packet_svc_t *handler = arg; @@ -708,7 +707,10 @@ int pktDisplayFrequencyCode(const radio_freq_t code, char *buf, size_t size) { } /** - * @brief Get default operating frequency. + * @brief Get a default operating frequency. + * @notes If a valid default is set in configuration use it + * @notes Else if a valid frequency is in the radio configuration use it + * @notes Else fall back to #defined DEFAULT_OPERATING_FREQUENCY * * @param[in] radio Radio unit ID. * @@ -719,13 +721,15 @@ int pktDisplayFrequencyCode(const radio_freq_t code, char *buf, size_t size) { * @api */ radio_freq_t pktGetDefaultOperatingFrequency(const radio_unit_t radio) { - /* FIXME: Default frequency in config to be per radio. */ - (void)radio; - /* FIXME: INVALID relies on 0 in conf if no default set. */ - if(conf_sram.freq != FREQ_RADIO_INVALID) + radio_band_t *band = pktCheckAllowedFrequency(radio, conf_sram.freq); + if(band != NULL) return conf_sram.freq; - else - return DEFAULT_OPERATING_FREQ; + radio_config_t *radio_data = pktGetRadioData(radio); + if(pktCheckAllowedFrequency(radio, radio_data->def_aprs)) + /* Use default APRS frequency in radio configuration. */ + return radio_data->def_aprs; + /* Fall back to defined default as last resort. */ + return DEFAULT_OPERATING_FREQ; } /** @@ -733,9 +737,9 @@ radio_freq_t pktGetDefaultOperatingFrequency(const radio_unit_t radio) { * * @param[in] radio Radio unit ID. * - * @return Actual operating frequency or special code - * @retval Operating receive frequency or code if receive is active - * @retval Default frequency otherwise. + * @return Actual operating frequency or special code. + * @retval Absolute receive frequency or code if receive is active. + * @retval Default operating frequency if receive not active. * * @notapi */ @@ -768,20 +772,16 @@ radio_freq_t pktGetReceiveOperatingFrequency(const radio_unit_t radio) { * @retval FREQ_RADIO_INVALID if frequency or radio ID is invalid * * @api - * - * TODO: Return pointer to band or NULL if invalid. */ radio_band_t *pktCheckAllowedFrequency(const radio_unit_t radio, - radio_freq_t freq) { + const radio_freq_t freq) { /* Check validity. */ uint8_t radios = pktGetNumRadios(); const radio_config_t *list = pktGetRadioList(); for(uint8_t i = 0; i < radios; i++) { - if(list->unit == radio) { - for(uint8_t x = 0; x < NUM_BANDS_PER_RADIO; x++) { - if(list->bands[x] == NULL) - /* Vacant band slot in this radio. */ - continue; + if(list->unit == radio && list->bands != NULL) { + uint8_t x = 0; + while(list->bands[x] != NULL) { if(list->bands[x]->start <= freq && freq < list->bands[x]->end) return list->bands[x]; @@ -866,7 +866,7 @@ radio_freq_t pktComputeOperatingFrequency(const radio_unit_t radio, } /** - * + * HAL functions */ bool pktLLDradioInit(const radio_unit_t radio) { /* TODO: Implement hardware mapping. */ @@ -933,9 +933,9 @@ bool pktLLDradioSendPacket(radio_task_object_t *rto) { /** * @brief Enable reception. - * @notes This is the API interface to the radio LLD. + * @notes This is the HAL API to the radio LLD. * @notes Currently just map directly to 446x driver. - * @notes In future would implement a lookup and VMT to access radio methods. + * @notes In future a VMT lookup would access the relevant radio methods. * * @param[in] radio radio unit ID. * @param[in] rto pointer to radio task object @@ -950,8 +950,6 @@ bool pktLLDradioEnableReceive(const radio_unit_t radio, radio_task_object_t *rto) { packet_svc_t *handler = pktGetServiceObject(radio); - //chDbgAssert(handler != NULL, "invalid radio ID"); - if(handler == NULL) return false; @@ -1131,4 +1129,5 @@ uint8_t pktLLDradioReadCCA(const radio_unit_t radio) { */ return Si446x_readCCA(radio); } + /** @} */ diff --git a/tracker/software/source/pkt/managers/pktradio.h b/tracker/software/source/pkt/managers/pktradio.h index 2dd70d39..b76174a5 100644 --- a/tracker/software/source/pkt/managers/pktradio.h +++ b/tracker/software/source/pkt/managers/pktradio.h @@ -139,12 +139,12 @@ extern "C" { void pktScheduleThreadRelease(const radio_unit_t radio, thread_t *thread); msg_t pktAcquireRadio(const radio_unit_t radio, - sysinterval_t timeout); + const sysinterval_t timeout); void pktReleaseRadio(const radio_unit_t radio); const radio_config_t *pktGetRadioList(void); uint8_t pktGetNumRadios(void); radio_band_t *pktCheckAllowedFrequency(const radio_unit_t radio, - radio_freq_t freq); + const radio_freq_t freq); radio_freq_t pktComputeOperatingFrequency(const radio_unit_t radio, radio_freq_t base_freq, channel_hz_t step, diff --git a/tracker/software/source/pkt/pktconf.h b/tracker/software/source/pkt/pktconf.h index f0f3fccd..249d5fa5 100644 --- a/tracker/software/source/pkt/pktconf.h +++ b/tracker/software/source/pkt/pktconf.h @@ -174,10 +174,8 @@ typedef uint32_t statusmask_t; /**< Mask of status identifiers. */ #include "ax25_dump.h" #include "si446x.h" #include "pktevt.h" - -#ifndef PKT_IS_TEST_PROJECT #include "debug.h" -#endif + extern packet_svc_t RPKTD1; /*===========================================================================*/ diff --git a/tracker/software/source/pkt/pkttypes.h b/tracker/software/source/pkt/pkttypes.h index 3cc3970d..d14face9 100644 --- a/tracker/software/source/pkt/pkttypes.h +++ b/tracker/software/source/pkt/pkttypes.h @@ -97,9 +97,18 @@ typedef struct radioBand { radio_freq_t start; radio_freq_t end; channel_hz_t step; - radio_freq_t def_aprs; + //radio_freq_t def_aprs; } radio_band_t; +typedef struct radioConfig { + radio_unit_t unit; + radio_type_t type; + void *cfg; + void *dat; + radio_freq_t def_aprs; /**< A frequency in one of the bands. */ + radio_band_t **bands; +} radio_config_t; + typedef uint8_t ax25char_t; typedef int32_t gps_coord_t;