Skip to content
Snippets Groups Projects

Compare revisions

Changes are shown as if the source revision was being merged into the target revision. Learn more about comparing revisions.

Source

Select target project
No results found

Target

Select target project
  • e-24/public/ahoi/firmware
1 result
Show changes
Showing
with 595 additions and 26 deletions
......@@ -138,4 +138,22 @@ i2c_receiveAddr(uint16_t slaveAddr, uint16_t memAddr, uint16_t memAddSize, uint8
// i2c_isRxCompleted(void);
/**
* @brief Disable the I2C module and set the pins floating
*
* @retval None
*/
void
i2c_sleep(void);
/**
* @brief Restores the I2C module configuration after calling of i2c_sleep
*
* @retval None
*/
void
i2c_wakeup(void);
#endif
......@@ -106,4 +106,21 @@ void spi_transmit(void * txPtr);
void spi_receive(void * rxPtr);
/**
* @brief Disables the SPI module for lower consumption. Sets pins floating
*
* @retval None
*/
void spi_sleep(void);
/**
* @brief Restores the SPI module configuration after calling spi_sleep.
*
* @retval None
*/
void spi_wakeup(void);
#endif
......@@ -76,6 +76,13 @@ void uart_write_line(const char * str);
*/
bool uart_sendPacket(const uint8_t * pkt, uint8_t len);
/**
* @brief determine if UART is busy sending a message
*
* @retval true if a TX operation is ongoing; false otherwise
*/
bool uart_isBusySending(void);
/**
* @brief set uart receive callback
*
......
......@@ -228,6 +228,21 @@ adda_hasSample(void)
// disable both RX and TX
void
adda_powerDown(void)
{
// make sure everything is off
txEnabled = false;
txamp_disable();
rxamp_disable();
// simply make sure we don't fill any queues
switchToTimerISR();
}
// activates reception by activating the ADC channel and using ISR_ADC
void
adda_activateSampling(void)
......
/**
* Copyright 2024
*
* Bernd-Christian Renner and
* Hamburg University of Technology (TUHH).
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
*
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
* A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
* HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
* DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
* THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifdef SLEEP_ENABLE
#include <hal_sleep.h>
#include <hal_board.h>
#include <hal_adda.h>
#include <hal_gpio.h>
#include <hal_host.h>
#include <mcu_irq.h>
#include <agc.h> // TODO no upper layer inclusion
/******************************************************************************
* Defines *
******************************************************************************/
/******************************************************************************
* Variables & Declarations *
******************************************************************************/
static volatile bool sleep = false;
/******************************************************************************
* Private Functions *
******************************************************************************/
/******************************************************************************
* Public Functions *
******************************************************************************/
void
hal_checkSleep(void)
{
if (! sleep) {
return;
}
// FIXME a very short shut down (LOW -> HIGH) causes the system
// to hang, might have to do with dependencies of ADDA/AGC
// observations:
// - AGC light does not switch on (we we hang before agc_enable())
// - current consumption is lower (ca. 21 vs. 24.5mA)
// - only happens, if RX connected
// power-down ad/da interface
adda_powerDown();
// FIXME it would be much nicer/clearer, if we could
// somehow deactivate the LEDs alltogether
bool agcEn = agc_isEnabled();
agc_disable();
// wait for ongoing UART TX to complete
while (uart_isBusySending()) { ; }
//led_off(LED_MODEM_TX); // only active during TX anyway
led_off(LED_MODEM_RX);
led_off(LED_SERIAL_RX);
led_off(LED_ALIVE); // TODO not fail-proof, if IRQ pending
led_off(LED_POWER);
// go to sleep
board_enterPowerDownMode();
led_on(LED_POWER);
// NOTE if there is trouble with waking up in production, we
// *could* reset the device as a hot fix
// NVIC_SystemReset();
irq_disable_global();
// go to receive mode and restore AGC
// FIXME adda_activateSampling has sporadically caused freezes;
// potential I2C or SPI hang due to some functionality not
// being properly restored after shut down
adda_activateSampling();
//adda_init();
if (agcEn) {
agc_enable();
}
//agc_init(agcEn);
sleep = false;
irq_enable_global();
}
bool
hal_requestSleep(void)
{
sleep = true;
return true;
}
/******************************************************************************
* Callbacks *
******************************************************************************/
/******************************************************************************
* IRQ Handler *
******************************************************************************/
/******************************************************************************
* Initialization *
******************************************************************************/
#endif
/**
* Copyright 2016-2023
* Copyright 2016-2024
*
* Timo Kortbrae,
* Jan Heitmann,
......@@ -132,6 +132,7 @@
* @{
*/
#define EXT_PKT_PIN GPIO_NA
#define WAKEUP_PIN GPIO_NA
/** @} */
......@@ -139,11 +140,12 @@
* \defgroup leds STM32F4 Led to GPIO mapping
* @{
*/
#define LED_1 (gpio_t){GPIOA, GPIO_PIN_3}
#define LED_2 (gpio_t){GPIOA, GPIO_PIN_11}
#define LED_3 (gpio_t){GPIOA, GPIO_PIN_6}
#define LED_4 (gpio_t){GPIOA, GPIO_PIN_7}
#define LED_5 (gpio_t){GPIOA, GPIO_PIN_12}
#define LED_1 (gpio_t){GPIOA, GPIO_PIN_3}
#define LED_2 (gpio_t){GPIOA, GPIO_PIN_11}
#define LED_3 (gpio_t){GPIOA, GPIO_PIN_6}
#define LED_4 (gpio_t){GPIOA, GPIO_PIN_7}
#define LED_5 (gpio_t){GPIOA, GPIO_PIN_12}
#define LED_POWER GPIO_NA
/** @} */
......
/**
* Copyright 2016-2023
* Copyright 2016-2024
*
* Timo Kortbrae,
* Jan Heitmann,
......@@ -132,6 +132,10 @@
* @{
*/
#define EXT_PKT_PIN (gpio_t){GPIOC, GPIO_PIN_11}
#define WAKEUP_PIN (gpio_t){GPIOA, GPIO_PIN_8}
#define WAKEUP_EXTI_IRQn EXTI9_5_IRQn
#define WAKEUP_EXTI_IRQHandler EXTI9_5_IRQHandler
#define WAKEUP_EXTI_IRQn_PRIO 0, 0 // was 2, 0
/** @} */
......@@ -144,6 +148,7 @@
#define LED_3 (gpio_t){GPIOA, GPIO_PIN_6}
#define LED_4 (gpio_t){GPIOA, GPIO_PIN_7}
#define LED_5 (gpio_t){GPIOA, GPIO_PIN_12}
#define LED_POWER (gpio_t){GPIOA, GPIO_PIN_4}
/** @} */
......
......@@ -44,7 +44,6 @@
#include <stdbool.h>
#define GPIO_NA ((gpio_t){0}) /* (pin0 = 1, pin1 = 2, ..., @see stm32f4xx_hal_gpio.h) */
typedef struct {
GPIO_TypeDef * port;
......
......@@ -75,6 +75,7 @@ hal/mcu/mcu_init.c \
hal/mcu/mcu_adda.c \
hal/mcu/mcu_debug.c \
hal/mcu/mcu_modem_config.c \
hal/mcu/mcu_sleep.c \
hal/boards/${TXAMP}/txamp.c \
hal/boards/${RXAMP}/filterraw.c \
hal/boards/${RXAMP}/filter.c \
......
......@@ -70,3 +70,92 @@ board_init(void)
}
/**
* @brief Enable the sleep mode to reduce power consumption. The program will stay in sleep mode until the next interrupt is fired.
*
* @retval None
*/
void
board_enterPowerDownMode(void)
{
// enable deep sleep (aka stop mode)
// cf. Sect. 5.3.5 in STM32 user manual
// RM0390, Reference manual, page 103pp
// NOTE device will only wake-up via WAKEUP_PIN
// TODO more aggressive power saving via PWR
// control register (PWR_CR) is possible
// enable EXINT pin
// GPIO_InitTypeDef GPIO_InitStruct;
// HAL_GPIO_Read(WAKEUP_PIN.port, &GPIO_InitStruct);
// GPIO_InitStruct.Mode = GPIO_MODE_IT_RISING;
// HAL_GPIO_Init(WAKEUP_PIN.port, &GPIO_InitStruct);
HAL_NVIC_EnableIRQ(WAKEUP_EXTI_IRQn);
// deactivate buses
i2c_sleep();
spi_sleep();
// Disable SysTick Timerr, to keep MCU in Stop (especially when debugger is connected)
HAL_SuspendTick();
// disable flash
HAL_PWREx_EnableFlashPowerDown();
// stop ... (until EXTI)
//HAL_PWR_EnterSTOPMode(PWR_MAINREGULATOR_ON, PWR_STOPENTRY_WFI);
HAL_PWR_EnterSTOPMode(PWR_LOWPOWERREGULATOR_ON, PWR_STOPENTRY_WFI);
//SET_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPDEEP_Msk));
//__WFI(); // Sleep and wait for EXTI
// re-enable flash after wake-up
HAL_PWREx_DisableFlashPowerDown();
// enable SysTick Timer
HAL_ResumeTick();
/*
* bring up the clock (HSE)
*/
/* Enable Power Control clock */
__PWR_CLK_ENABLE();
/* Get the Oscillators configuration according to the internal RCC registers */
RCC_OscInitTypeDef RCC_OscInitStruct;
HAL_RCC_GetOscConfig(&RCC_OscInitStruct);
/* After wake-up from STOP reconfigure the system clock: Enable HSE and PLL */
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
RCC_OscInitStruct.HSEState = RCC_HSE_ON;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
HAL_RCC_OscConfig(&RCC_OscInitStruct);
//if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) { ... }
/* Get the Clocks configuration according to the internal RCC registers */
RCC_ClkInitTypeDef RCC_ClkInitStruct;
uint32_t pFLatency = 0;
HAL_RCC_GetClockConfig(&RCC_ClkInitStruct, &pFLatency);
/* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2
clocks dividers */
RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_SYSCLK;
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
HAL_RCC_ClockConfig(&RCC_ClkInitStruct, pFLatency);
// if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, pFLatency) != HAL_OK)
// disable interrupt source
//GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
//HAL_GPIO_Init(WAKEUP_PIN.port, &GPIO_InitStruct);
HAL_NVIC_DisableIRQ(WAKEUP_EXTI_IRQn);
// re-enable GPIOs
// re-init of i2c driver is necessary, otherwise an error on first use occurs
i2c_wakeup();
i2c_init();
spi_wakeup();
}
/**
* Copyright 2016-2021
* Copyright 2016-2024
*
* Timo Kortbrae,
* Jan Heitmann,
......@@ -47,6 +47,24 @@
#include <stm32f4xx_hal.h>
#include <mcu_gpio.h>
#include <board_debug.h>
#include <board_config.h>
/******************************************************************************
* globals
******************************************************************************/
// volatile bool sleep__ = false;
// volatile uint16_t sleepICount = 0;
/******************************************************************************
* prototypes
******************************************************************************/
void
WAKEUP_EXTI_IRQHandler(void);
......@@ -128,8 +146,82 @@ gpio_init(void)
GPIO_InitStruct.Pin = LED_5.pin;
HAL_GPIO_Init(LED_5.port, &GPIO_InitStruct);
led_off(LED_5);
#ifdef SLEEP_ENABLE
GPIO_InitStruct.Pin = LED_POWER.pin;
HAL_GPIO_Init(LED_POWER.port, &GPIO_InitStruct);
led_on(LED_POWER);
#endif
//
// TODO sleep/wake-up pin
//
// TODO any better way to check this?
#ifdef SLEEP_ENABLE
GPIO_InitStruct.Pin = WAKEUP_PIN.pin;
//GPIO_InitStruct.Mode = GPIO_MODE_INPUT; // will be activated before sleep (@board_enterPowerDownMode())
GPIO_InitStruct.Mode = GPIO_MODE_IT_RISING; // GPIO_MODE_EVT_RISING_FALLING
//GPIO_InitStruct.Mode = GPIO_MODE_IT_FALLING; // GPIO_MODE_EVT_RISING_FALLING
GPIO_InitStruct.Pull = GPIO_NOPULL; // TODO for compatibility? GPIO_PULLDOWN
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
HAL_GPIO_Init(WAKEUP_PIN.port, &GPIO_InitStruct);
HAL_NVIC_SetPriority(WAKEUP_EXTI_IRQn, WAKEUP_EXTI_IRQn_PRIO);
//HAL_NVIC_EnableIRQ(WAKEUP_EXTI_IRQn); // NOTE will be activated before sleep (@board_enterPowerDownMode())
#endif
}
// ISR and Handler for WAKE-UP IR
#ifdef SLEEP_ENABLE
__attribute__((used))
void
WAKEUP_EXTI_IRQHandler(void)
{
HAL_GPIO_EXTI_IRQHandler(WAKEUP_PIN.pin);
}
void
HAL_GPIO_EXTI_Callback(uint16_t pin)
{
// sleepICount++;
// if (WAKEUP_PIN.pin == pin) {
// sleep__ = false; // NOTE simply disable sleep
//
// // NOTE control sleep mode with pin (needs some extra work)
// // sleep__ = ! gpio_read(WAKEUP_PIN);
// }
}
#endif
//
// TODO alternative to avoid messy and bloated STM SPL/HAL handling?
//
// __attribute__((used))
// void
// WAKEUP_EXTI_IRQHandler(void)
// {
// /* Make sure that interrupt flag is set and clear before action */
// //if (HAL_NVIC_GetPendingIRQ(WAKEUP_EXTI_IRQn)) {
// if (__HAL_GPIO_EXTI_GET_IT(WAKEUP_PIN.pin) != RESET) {
// __HAL_GPIO_EXTI_CLEAR_IT(WAKEUP_PIN.pin);
// /* TODO */
// if (gpio_read(WAKEUP_PIN)) {
// gpio_set(EXT_PKT_PIN); // TODO DEBUG
// } else {
// gpio_clear(EXT_PKT_PIN); // TODO DEBUG
// }
// }
// }
#ifdef PIN_DEBUG
/**
......
......@@ -399,3 +399,58 @@ i2c_isReady(void)
{
return HAL_I2C_GetState(&i2cHandle) == HAL_I2C_STATE_READY;
}
void
i2c_sleep(void)
{
GPIO_InitTypeDef GPIO_InitStruct;
// I2C SCL
GPIO_InitStruct.Pin = I2C1_SCL_PIN;
GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = I2C1_SCL_AF;
HAL_GPIO_Init(I2C1_SCL_GPIO_PORT, &GPIO_InitStruct);
// I2C SDA
GPIO_InitStruct.Pin = I2C1_SDA_PIN;
GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = I2C1_SDA_AF;
HAL_GPIO_Init(I2C1_SDA_GPIO_PORT, &GPIO_InitStruct);
__HAL_RCC_I2C1_CLK_DISABLE();
}
void
i2c_wakeup(void)
{
// TODO this a duplicate of the init, so clean this mess up
GPIO_InitTypeDef GPIO_InitStruct;
// I2C SCL
GPIO_InitStruct.Pin = I2C1_SCL_PIN;
GPIO_InitStruct.Mode = GPIO_MODE_AF_OD;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; //<- medium should be fast enough GPIO_SPEED_FAST;
GPIO_InitStruct.Alternate = I2C1_SCL_AF;
HAL_GPIO_Init(I2C1_SCL_GPIO_PORT, &GPIO_InitStruct);
// I2C SDA
GPIO_InitStruct.Pin = I2C1_SDA_PIN;
GPIO_InitStruct.Mode = GPIO_MODE_AF_OD;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_MEDIUM; //<- medium should be fast enough GPIO_SPEED_FAST;
GPIO_InitStruct.Alternate = I2C1_SDA_AF;
HAL_GPIO_Init(I2C1_SDA_GPIO_PORT, &GPIO_InitStruct);
__HAL_RCC_I2C1_CLK_ENABLE();
}
......@@ -77,6 +77,8 @@ void CFG_SPI_IRQHandler(void);
static inline void spi_TxRx(uint8_t * rxPtr, uint8_t * txPtr);
static inline void spi_chipDeSelect(void);
// timeout for SPI Functions in HAL Ticks (default Ticks: 1ms)
const uint16_t SPI_Timeout = 50;
/******************************************************************************
......@@ -100,10 +102,14 @@ __attribute__((__always_inline__))
#endif
static inline void
spi_TxRx(uint8_t * rxPtr, uint8_t * txPtr)
{
{
uint32_t tickstart = HAL_GetTick();
spiHandle.pTxBuffPtr = (uint8_t *)txPtr;
spiHandle.pRxBuffPtr = (uint8_t *)rxPtr;
WAIT_TIMED((spiHandle.Instance->SR & SPI_FLAG_TXE) == RESET);
spiHandle.Instance->DR = *((uint16_t *)spiHandle.pTxBuffPtr);
__HAL_SPI_CLEAR_OVRFLAG(&spiHandle);
__HAL_SPI_ENABLE_IT(&spiHandle, (SPI_IT_RXNE));
......@@ -263,3 +269,91 @@ HAL_SPI_MspInit(SPI_HandleTypeDef *hspi)
HAL_NVIC_SetPriority(CFG_SPI_IRQn, CFG_SPI_IRQn_PRIO);
HAL_NVIC_EnableIRQ(CFG_SPI_IRQn);
}
void spi_sleep(void)
{
GPIO_InitTypeDef GPIO_InitStruct;
// generic for all
GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
// SPI CS0
GPIO_InitStruct.Pin = CFG_SPI_CS0_PIN;
HAL_GPIO_Init(CFG_SPI_CS0_GPIO_PORT, &GPIO_InitStruct);
// SPI CS1
GPIO_InitStruct.Pin = CFG_SPI_CS1_PIN;
HAL_GPIO_Init(CFG_SPI_CS1_GPIO_PORT, &GPIO_InitStruct);
// SPI CS2
GPIO_InitStruct.Pin = CFG_SPI_CS2_PIN;
HAL_GPIO_Init(CFG_SPI_CS2_GPIO_PORT, &GPIO_InitStruct);
// SPI SCK
GPIO_InitStruct.Pin = CFG_SPI_SCK_PIN;
GPIO_InitStruct.Alternate = CFG_SPI_SCK_AF;
HAL_GPIO_Init(CFG_SPI_SCK_GPIO_PORT, &GPIO_InitStruct);
// SPI MOSI
GPIO_InitStruct.Pin = CFG_SPI_MOSI_PIN;
GPIO_InitStruct.Alternate = CFG_SPI_MOSI_AF;
HAL_GPIO_Init(CFG_SPI_MOSI_GPIO_PORT, &GPIO_InitStruct);
// SPI MISO
GPIO_InitStruct.Pin = CFG_SPI_MISO_PIN;
GPIO_InitStruct.Alternate = CFG_SPI_MISO_AF;
HAL_GPIO_Init(CFG_SPI_MISO_GPIO_PORT, &GPIO_InitStruct);
__HAL_RCC_SPI1_CLK_DISABLE();
}
void spi_wakeup(void)
{
// TODO redundant to init, merge!
__HAL_RCC_SPI1_CLK_ENABLE();
GPIO_InitTypeDef GPIO_InitStruct;
// CS: generic setup
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
// SPI CS0
GPIO_InitStruct.Pin = CFG_SPI_CS0_PIN;
HAL_GPIO_Init(CFG_SPI_CS0_GPIO_PORT, &GPIO_InitStruct);
gpio_set((gpio_t){ CFG_SPI_CS0_GPIO_PORT, CFG_SPI_CS0_PIN });
// SPI CS1
GPIO_InitStruct.Pin = CFG_SPI_CS1_PIN;
HAL_GPIO_Init(CFG_SPI_CS1_GPIO_PORT, &GPIO_InitStruct);
gpio_set((gpio_t){ CFG_SPI_CS1_GPIO_PORT, CFG_SPI_CS1_PIN });
// SPI CS2
GPIO_InitStruct.Pin = CFG_SPI_CS2_PIN;
HAL_GPIO_Init(CFG_SPI_CS2_GPIO_PORT, &GPIO_InitStruct);
gpio_set((gpio_t){ CFG_SPI_CS2_GPIO_PORT, CFG_SPI_CS2_PIN });
// non-CS: generic setup
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
// SPI SCK
GPIO_InitStruct.Pin = CFG_SPI_SCK_PIN;
GPIO_InitStruct.Alternate = CFG_SPI_SCK_AF;
HAL_GPIO_Init(CFG_SPI_SCK_GPIO_PORT, &GPIO_InitStruct);
// SPI MOSI
GPIO_InitStruct.Pin = CFG_SPI_MOSI_PIN;
GPIO_InitStruct.Alternate = CFG_SPI_MOSI_AF;
HAL_GPIO_Init(CFG_SPI_MOSI_GPIO_PORT, &GPIO_InitStruct);
// SPI MISO
GPIO_InitStruct.Pin = CFG_SPI_MISO_PIN;
GPIO_InitStruct.Alternate = CFG_SPI_MISO_AF;
HAL_GPIO_Init(CFG_SPI_MISO_GPIO_PORT, &GPIO_InitStruct);
}
......@@ -95,6 +95,15 @@ static UART_HandleTypeDef uartHandle;
* Public Functions *
******************************************************************************/
bool
uart_isBusySending(void)
{
return uartHandle.gState == HAL_UART_STATE_BUSY_TX;
}
bool
uart_sendPacket(const uint8_t * pkt, uint8_t len)
{
......
/**
* Copyright 2016-2018
* Copyright 2016-2024
*
* Timo Kortbrae,
* Bernd-Christian Renner, and
......@@ -45,6 +45,9 @@
#define LED_MODEM_RX 1 // toggle on event
#define LED_SERIAL_RX 2 // toggle on event
#define LED_AGC 3 // agc indicator
#define LED_POWER 4 // power LED (optional)
#define EXT_PKT_PIN 10
//#define SENDER_ENABLE_IO_PIN 0
......
/**
* Copyright 2016-2023
* Copyright 2016-2024
*
* Bernd-Christian Renner
* Jan Heitmann, and
......@@ -86,6 +86,7 @@
#include <stdbool.h>
#include <hal_init.h>
#include <hal_sleep.h>
#include <hal_adda.h>
#include <hal_filter.h>
#include <hal_debug.h>
......@@ -322,12 +323,13 @@ int main(void)
processRxPacket();
processTxPacket();
board_enterPowerSaveMode();
// check sleep
hal_checkSleep();
}
}
/******************************************************************************
* Callbacks *
* Callbacks *
******************************************************************************/
mm_packet_t *
......
/**
* Copyright 2016-2023
* Copyright 2016-2024
*
* Bernd-Christian Renner, and
* Hamburg University of Technology (TUHH).
......@@ -463,11 +463,13 @@ receive_decodePayload()
// STEP 4: calculate and check crc
crc = crc_CRC16(buf, PAYLOAD_TOTAL_LEN(rxPkt->header.len));
crc = (rxPkt->header.len <= CRC8_MAX_LEN) ?
crc_CRC8(buf, PAYLOAD_TOTAL_LEN(rxPkt->header.len)) :
crc_CRC16(buf, PAYLOAD_TOTAL_LEN(rxPkt->header.len));
if (crc) {
dbg("payload: CRC check failed\n");
aci_packetstat_incRxPayloadBadCrc();
return false; // TODO would be smarter to set a marker, so that we can do better debugging at the end
return false;
}
......
/**
* Copyright 2016-2023
* Copyright 2016-2024
*
* Bernd-Christian Renner, and
* Hamburg University of Technology (TUHH).
......@@ -143,7 +143,6 @@ send_encodePayload(const mm_packet_t * const pkt)
uint8_t rawBuf[MAX_PAYLOAD_TOTAL_LEN];
uint16_t encBlocks[PAYLOAD_MAX_BLOCKS];
uint16_t decBlocks[PAYLOAD_MAX_BLOCKS];
uint16_t crc16;
// nothing to do, if there is no payload
if (pkt->header.len == 0) {
......@@ -164,9 +163,14 @@ send_encodePayload(const mm_packet_t * const pkt)
// STEP 1: copy header into local buffer and append crc
memcpy(rawBuf, pkt->payload, pkt->header.len);
crc16 = crc_CRC16(rawBuf, pkt->header.len);
rawBuf[pkt->header.len] = (uint8_t)(crc16 >> 8);
rawBuf[pkt->header.len+1] = (uint8_t)(crc16 & 0x00FF);
if (pkt->header.len <= CRC8_MAX_LEN) {
uint8_t crc8 = crc_CRC8(rawBuf, pkt->header.len);
rawBuf[pkt->header.len] = crc8;
} else {
uint16_t crc16 = crc_CRC16(rawBuf, pkt->header.len);
rawBuf[pkt->header.len] = (uint8_t)(crc16 >> 8);
rawBuf[pkt->header.len+1] = (uint8_t)(crc16 & 0x00FF);
}
// STEP 2: deserialize bit/byte stream into coding blocks
memset(decBlocks, 0, sizeof(decBlocks));
......
/**
* Copyright 2016-2023
* Copyright 2016-2024
*
* Bernd-Christian Renner and
* Hamburg University of Technology (TUHH).
......@@ -42,6 +42,9 @@
#include <stdint.h>
#include <string.h>
#include "crc.h"
///////////////////////////////////////////////////////////////////////////
// PACKET / RX quality
......@@ -93,12 +96,12 @@ typedef uint8_t mm_length_t;
#define MM_HEADER_LEN (sizeof(mm_header_t))
#define MM_FOOTER_LEN (sizeof(mm_footer_t))
#define MM_PAYLOAD_CRC_LEN 2 /* bytes */
#define MM_HEADER_CRC_LEN 1 /* bytes */
#define MM_PAYLOAD_CRC_LEN(l) (((l) <= CRC8_MAX_LEN) ? 1 : 2) /* bytes */
#define MM_HEADER_CRC_LEN 1 /* bytes */
// maximum size of header and payload including CRCs
#define HEADER_TOTAL_LEN (MM_HEADER_LEN + MM_HEADER_CRC_LEN)
#define PAYLOAD_TOTAL_LEN(l) (((l) == 0) ? 0 : ((l) + MM_PAYLOAD_CRC_LEN))
#define PAYLOAD_TOTAL_LEN(l) (((l) == 0) ? 0 : ((l) + MM_PAYLOAD_CRC_LEN(l)))
#define MAX_PAYLOAD_TOTAL_LEN (PAYLOAD_TOTAL_LEN(MM_PAYLOAD_MAXLEN))
#define MAX_PACKET_LEN (HEADER_TOTAL_LEN + MAX_PAYLOAD_TOTAL_LEN)
......