1
0
mirror of https://github.com/peterantypas/maiana.git synced 2025-05-21 01:40:09 -07:00

Board 9.3

This commit is contained in:
Peter Antypas 2020-11-21 10:49:04 -08:00
parent e655e48841
commit 6a79e3601d
11 changed files with 183 additions and 125 deletions

View File

@ -27,7 +27,7 @@
// Either modify this header or define a different symbol in the preprocessor to build for a different board
#ifndef BOARD_REV
#define BOARD_REV 61
#define BOARD_REV 93
#endif
/**
@ -47,9 +47,9 @@ void bsp_enter_dfu();
void bsp_gnss_on();
void bsp_gnss_off();
bool bsp_is_tx_disabled();
uint8_t bsp_noise_floor();
void bsp_signal_high();
void bsp_signal_low();
void bsp_signal_rx_event();
void bsp_signal_tx_event();
void bsp_signal_gps_status(bool tracking);
// Callback for processing UART input (interrupt)
typedef void(*char_input_cb)(char c);
@ -83,14 +83,12 @@ bool bsp_read_station_data(StationData &data);
// Board-specific headers go here
#if BOARD_REV == 50
#include "bsp_5_0.hpp"
#elif BOARD_REV == 52
#if BOARD_REV == 52
#include "bsp_5_2.hpp"
#elif BOARD_REV == 53
#include "bsp_5_3.hpp"
#elif BOARD_REV == 61
#include <bsp_6_1.hpp>
#elif BOARD_REV == 93
#include <bsp_9_3.hpp>
#endif

View File

@ -17,20 +17,23 @@
along with this program. If not, see <https://www.gnu.org/licenses/>
*/
#ifndef INC_BSP_5_3_HPP_
#define INC_BSP_5_3_HPP_
#ifndef INC_BSP_9_3_HPP_
#define INC_BSP_9_3_HPP_
// GPIO Pin definitions
#define GNSS_EN_PORT GPIOC
#define GNSS_EN_PIN GPIO_PIN_14
#define EEPROM_WREN_PORT GPIOC
#define EEPROM_WREN_PIN GPIO_PIN_15
#define TRX_IC_CLK_PORT GPIOC
#define TRX_IC_CLK_PIN GPIO_PIN_15
#define CS2_PORT GPIOA
#define CS2_PIN GPIO_PIN_0
#define TRX_IC_CLK_PORT GPIOA
#define TRX_IC_CLK_PIN GPIO_PIN_1
#define RX_EVT_PORT GPIOA
#define RX_EVT_PIN GPIO_PIN_1
#define GNSS_1PPS_PORT GPIOA
#define GNSS_1PPS_PIN GPIO_PIN_2
@ -56,8 +59,8 @@
#define TRX_IC_DATA_PORT GPIOB
#define TRX_IC_DATA_PIN GPIO_PIN_1
#define DFU_EN_PORT GPIOA
#define DFU_EN_PIN GPIO_PIN_8
#define TX_EVT_PORT GPIOA
#define TX_EVT_PIN GPIO_PIN_8
#define UART_TX_PORT GPIOA
#define UART_TX_PIN GPIO_PIN_9
@ -65,6 +68,12 @@
#define UART_RX_PORT GPIOA
#define UART_RX_PIN GPIO_PIN_10
#define GNSS_STATE_PORT GPIOA
#define GNSS_STATE_PIN GPIO_PIN_11
#define TX_DISABLE_PORT GPIOA
#define TX_DISABLE_PIN GPIO_PIN_12
#define SDN2_PORT GPIOA
#define SDN2_PIN GPIO_PIN_15
@ -84,4 +93,5 @@
#define I2C_SDA_PIN GPIO_PIN_7
#endif /* INC_BSP_5_2_HPP_ */
#endif /* INC_BSP_5_0_HPP_ */

View File

@ -70,7 +70,8 @@
//#define RF_GLOBAL_XO_TUNE_1 0x11, 0x00, 0x01, 0x00, 0x30
#define RF_GLOBAL_XO_TUNE_1 0x11, 0x00, 0x01, 0x00, 0x2D
//#define RF_GLOBAL_XO_TUNE_1 0x11, 0x00, 0x01, 0x00, 0x2C
//#define RF_GLOBAL_XO_TUNE_1 0x11, 0x00, 0x01, 0x00, 0x2A
/*
// Set properties: RF_GLOBAL_CONFIG_1
// Number of properties: 1

View File

@ -96,6 +96,7 @@ void GPS::enable()
void GPS::disable()
{
bsp_gnss_off();
bsp_signal_gps_status(false);
}
void GPS::onRX(char c)
@ -123,9 +124,6 @@ void GPS::onRX(char c)
}
}
/*
* What happens if PPS stops and resumes? Isn't our timestamp wrong?
*/
void GPS::onPPS()
{
// If we don't have time yet, we can't use this
@ -234,7 +232,7 @@ void GPS::parseSentence(const char *buff)
if (fields[1].length () < 6 || fields[9].length () < 6)
{
// TODO: A loss of fix while the SOTDMA timer is active, MUST stop the timer
bsp_signal_gps_status(false);
return;
}
@ -253,6 +251,7 @@ void GPS::parseSentence(const char *buff)
// Do we have a fix?
if (mUTC && sentence.fields()[3].length() > 0 && sentence.fields()[5].length() > 0)
{
bsp_signal_gps_status(true);
mLat = Utils::latitudeFromNMEA (sentence.fields()[3], sentence.fields()[4]);
mLng = Utils::longitudeFromNMEA (sentence.fields()[5], sentence.fields()[6]);
mSpeed = atof(sentence.fields()[7].c_str());

View File

@ -15,7 +15,7 @@
You should have received a copy of the GNU General Public License
along with this program. If not, see <https://www.gnu.org/licenses/>
*/
*/
#include "NMEAEncoder.hpp"
@ -48,33 +48,37 @@ void NMEAEncoder::encode(RXPacket &packet, vector<string> &sentences)
uint16_t numBits = packet.size();
uint16_t fillBits = 0;
if ( numBits % 6 ) {
if ( numBits % 6 )
{
fillBits = 6 - (numBits%6);
packet.addFillBits(fillBits);
numBits = packet.size();
}
}
uint16_t numSentences = 1;
while ( numBits > MAX_SENTENCE_BITS ) {
while ( numBits > MAX_SENTENCE_BITS )
{
++numSentences;
numBits -= MAX_SENTENCE_BITS;
}
}
numBits = packet.size();
if ( numSentences > 1 ) {
if ( numSentences > 1 )
{
++mSequence;
if ( mSequence > 9 )
mSequence = 0;
}
}
// Now we know how many sentences we need
char sentence[85];
uint16_t pos = 0;
for ( uint16_t i = 1; i <= numSentences; ++i ) {
for ( uint16_t i = 1; i <= numSentences; ++i )
{
uint8_t k = 0;
if ( numSentences > 1 )
sprintf(sentence, "!AIVDM,%d,%d,%d,%c,", numSentences, i, mSequence, AIS_CHANNELS[packet.channel()].designation);
@ -84,26 +88,30 @@ void NMEAEncoder::encode(RXPacket &packet, vector<string> &sentences)
k = strlen(sentence);
uint16_t sentenceBits = 0;
for ( ; pos < numBits && sentenceBits < MAX_SENTENCE_BITS; pos += 6, sentenceBits += 6 ) {
for ( ; pos < numBits && sentenceBits < MAX_SENTENCE_BITS; pos += 6, sentenceBits += 6 )
{
uint8_t nmeaByte = (uint8_t)packet.bits(pos, 6);
nmeaByte += (nmeaByte < 40) ? 48 : 56;
sentence[k++] = nmeaByte;
}
}
sentence[k++] = ',';
if ( numSentences > 1 ) {
if ( numSentences > 1 )
{
if ( i == numSentences )
sentence[k++] = '0' + fillBits;
else
sentence[k++] = '0';
}
}
else
sentence[k++] = '0';
{
sentence[k++] = '0';
}
sentence[k++] = '*';
sprintf(sentence+k, "%.2X", nmeaCRC(sentence));
sentences.push_back(string(sentence));
}
}
}

View File

@ -29,6 +29,7 @@
#include "Utils.hpp"
#include "AISChannels.h"
#include "printf_serial.h"
#include "bsp.hpp"
#if MULTIPLEXED_OUTPUT
@ -57,6 +58,8 @@ void RXPacketProcessor::processEvent(const Event &e)
if (e.rxPacket->isBad() || !e.rxPacket->checkCRC ())
return;
bsp_signal_rx_event();
if ( e.rxPacket->messageType() == 15 )
{
AISMessage15 msg;

View File

@ -223,18 +223,12 @@ Receiver::Action Receiver::processNRZIBit(uint8_t bit)
}
case BIT_STATE_IN_PACKET:
{
if ( mRXPacket->size() >= MAX_AIS_RX_PACKET_SIZE )
if ( mOneBitCount >= 7 || mRXPacket->size() >= MAX_AIS_RX_PACKET_SIZE )
{
// Start over
return RESTART_RX;
}
// We can never have 7 consecutive "1" bits in a proper NRZI encoded packet
if ( mOneBitCount >= 7 )
{
return RESTART_RX;
}
mLastNRZIBit = bit;
mBitWindow <<= 1;
mBitWindow |= decodedBit;

View File

@ -143,11 +143,11 @@ void Transceiver::configureGPIOsForTX(tx_power_level powerLevel)
bsp_set_tx_mode();
GPIO_PIN_CFG_PARAMS gpiocfg;
gpiocfg.GPIO0 = 0x20; // TX_STATE; low during RX and high during TX
gpiocfg.GPIO1 = 0x04; // Input
gpiocfg.GPIO2 = 0x1F; // RX/TX data clock
gpiocfg.GPIO0 = 0x00; // No change
gpiocfg.GPIO1 = 0x04; // RX/TX bit data
gpiocfg.GPIO2 = 0x1F; // RX/TX bit clock
gpiocfg.GPIO3 = 0x21; // RX_STATE; high in RX, low in TX
gpiocfg.NIRQ = 0x1A; // Sync word detect
gpiocfg.NIRQ = 0x00; // No change
gpiocfg.SDO = 0x00; // No change
gpiocfg.GENCFG = 0x00; // No change
sendCmd(GPIO_PIN_CFG, &gpiocfg, sizeof gpiocfg, NULL, 0);
@ -316,11 +316,11 @@ void Transceiver::configureGPIOsForRX()
bsp_set_rx_mode();
GPIO_PIN_CFG_PARAMS gpiocfg;
gpiocfg.GPIO0 = 0x20; // TX_STATE; low during RX and high during TX
gpiocfg.GPIO0 = 0x00; // No change
gpiocfg.GPIO1 = 0x14; // RX data bits
gpiocfg.GPIO2 = 0x1F; // RX/TX data clock
gpiocfg.GPIO3 = 0x21; // RX_STATE; high during RX and low during TX
gpiocfg.NIRQ = 0x00; // Nothing
gpiocfg.NIRQ = 0x00; // No change
gpiocfg.SDO = 0x00; // No change
gpiocfg.GENCFG = 0x00; // No change
sendCmd(GPIO_PIN_CFG, &gpiocfg, sizeof gpiocfg, NULL, 0);
@ -335,4 +335,5 @@ void Transceiver::reportTXEvent()
snprintf(e->nmeaBuffer.sentence, sizeof e->nmeaBuffer.sentence, "$PAITX,%c,%s*", AIS_CHANNELS[mTXPacket->channel()].designation, mTXPacket->messageType());
Utils::completeNMEA(e->nmeaBuffer.sentence);
EventQueue::instance().push(e);
bsp_signal_tx_event();
}

View File

@ -553,6 +553,21 @@ void bsp_enter_dfu()
bsp_reboot();
}
void bsp_signal_rx_event()
{
}
void bsp_signal_tx_event()
{
}
void bsp_signal_gps_status(bool tracking)
{
}
extern "C"
{

View File

@ -555,24 +555,22 @@ void bsp_enter_dfu()
bsp_reboot();
}
uint8_t bsp_noise_floor()
void bsp_signal_rx_event()
{
/**
* This is the result of extensive characterization with this hardware
*/
return 0x22;
}
void bsp_signal_high()
void bsp_signal_tx_event()
{
HAL_GPIO_WritePin(SPARE_PORT, SPARE_PIN, GPIO_PIN_SET);
}
void bsp_signal_low()
void bsp_signal_gps_status(bool tracking)
{
HAL_GPIO_WritePin(SPARE_PORT, SPARE_PIN, GPIO_PIN_RESET);
}
extern "C"
{

View File

@ -25,7 +25,7 @@
#include <string.h>
#if BOARD_REV==53
#if BOARD_REV==93
I2C_HandleTypeDef hi2c1;
SPI_HandleTypeDef hspi1;
@ -53,9 +53,11 @@ typedef struct
} GPIO;
static const GPIO __gpios[] = {
{EEPROM_WREN_PORT, {EEPROM_WREN_PIN, GPIO_MODE_OUTPUT_OD, GPIO_NOPULL, GPIO_SPEED_LOW, 0}, GPIO_PIN_SET},
{CS2_PORT, {CS2_PIN, GPIO_MODE_OUTPUT_PP, GPIO_NOPULL, GPIO_SPEED_HIGH, 0}, GPIO_PIN_SET},
{GNSS_EN_PORT, {GNSS_EN_PIN, GPIO_MODE_OUTPUT_PP, GPIO_NOPULL, GPIO_SPEED_LOW, 0}, GPIO_PIN_RESET},
{TRX_IC_CLK_PORT, {TRX_IC_CLK_PIN, GPIO_MODE_IT_RISING, GPIO_NOPULL, GPIO_SPEED_LOW, 0}, GPIO_PIN_RESET},
{TX_DISABLE_PORT, {TX_DISABLE_PIN, GPIO_MODE_INPUT, GPIO_PULLUP, GPIO_SPEED_LOW, 0}, GPIO_PIN_SET},
{CS2_PORT, {CS2_PIN, GPIO_MODE_OUTPUT_PP, GPIO_NOPULL, GPIO_SPEED_HIGH, 0}, GPIO_PIN_SET},
{RX_EVT_PORT, {RX_EVT_PIN, GPIO_MODE_OUTPUT_PP, GPIO_NOPULL, GPIO_SPEED_LOW, 0}, GPIO_PIN_RESET},
{GNSS_1PPS_PORT, {GNSS_1PPS_PIN, GPIO_MODE_IT_FALLING, GPIO_PULLUP, GPIO_SPEED_LOW, 0}, GPIO_PIN_RESET},
{GNSS_NMEA_RX_PORT, {GNSS_NMEA_RX_PIN, GPIO_MODE_AF_PP, GPIO_PULLUP, GPIO_SPEED_LOW, GPIO_AF7_USART2}, GPIO_PIN_RESET},
{CS1_PORT, {CS1_PIN, GPIO_MODE_OUTPUT_PP, GPIO_NOPULL, GPIO_SPEED_HIGH, 0}, GPIO_PIN_SET},
@ -64,9 +66,10 @@ static const GPIO __gpios[] = {
{MOSI_PORT, {MOSI_PIN, GPIO_MODE_AF_PP, GPIO_NOPULL, GPIO_SPEED_HIGH, GPIO_AF5_SPI1}, GPIO_PIN_SET},
{SDN1_PORT, {SDN1_PIN, GPIO_MODE_OUTPUT_PP, GPIO_NOPULL, GPIO_SPEED_LOW, 0}, GPIO_PIN_SET},
{TRX_IC_DATA_PORT, {TRX_IC_DATA_PIN, GPIO_MODE_INPUT, GPIO_NOPULL, GPIO_SPEED_LOW, 0}, GPIO_PIN_RESET},
{DFU_EN_PORT, {DFU_EN_PIN, GPIO_MODE_OUTPUT_PP, GPIO_NOPULL, GPIO_SPEED_LOW, 0}, GPIO_PIN_RESET},
{TX_EVT_PORT, {TX_EVT_PIN, GPIO_MODE_OUTPUT_PP, GPIO_NOPULL, GPIO_SPEED_LOW, 0}, GPIO_PIN_RESET},
{UART_TX_PORT, {UART_TX_PIN, GPIO_MODE_AF_PP, GPIO_PULLUP, GPIO_SPEED_LOW, GPIO_AF7_USART1}, GPIO_PIN_RESET},
{UART_RX_PORT, {UART_RX_PIN, GPIO_MODE_AF_PP, GPIO_PULLUP, GPIO_SPEED_LOW, GPIO_AF7_USART1}, GPIO_PIN_RESET},
{GNSS_STATE_PORT, {GNSS_STATE_PIN, GPIO_MODE_OUTPUT_PP, GPIO_NOPULL, GPIO_SPEED_LOW, 0}, GPIO_PIN_RESET},
{SDN2_PORT, {SDN2_PIN, GPIO_MODE_OUTPUT_PP, GPIO_NOPULL, GPIO_SPEED_LOW, 0}, GPIO_PIN_SET},
{RX_IC_CLK_PORT, {RX_IC_CLK_PIN, GPIO_MODE_IT_RISING, GPIO_NOPULL, GPIO_SPEED_LOW, 0}, GPIO_PIN_RESET},
{RX_IC_DATA_PORT, {RX_IC_DATA_PIN, GPIO_MODE_INPUT, GPIO_NOPULL, GPIO_SPEED_LOW, 0}, GPIO_PIN_RESET},
@ -77,11 +80,12 @@ static const GPIO __gpios[] = {
extern "C"
{
void Error_Handler(void)
void Error_Handler(uint8_t i)
{
printf_serial_now("[ERROR]\r\n");
printf_serial_now("[ERROR] ***** System error handler resetting *****\r\n");
NVIC_SystemReset();
asm("BKPT 0");
printf_serial_now("[ERROR %d]\r\n", i);
//printf_serial_now("[ERROR] ***** System error handler resetting *****\r\n");
//NVIC_SystemReset();
}
}
@ -105,18 +109,6 @@ void bsp_hw_init()
gpio_pin_init();
// 1PPS signal
HAL_NVIC_SetPriority(EXTI2_IRQn, 5, 0);
HAL_NVIC_EnableIRQ(EXTI2_IRQn);
// RF IC clock interrupts
HAL_NVIC_SetPriority(EXTI1_IRQn, 5, 0);
HAL_NVIC_EnableIRQ(EXTI1_IRQn);
HAL_NVIC_SetPriority(EXTI3_IRQn, 5, 0);
HAL_NVIC_EnableIRQ(EXTI3_IRQn);
// USART1 (main UART)
@ -132,7 +124,7 @@ void bsp_hw_init()
huart1.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT;
HAL_UART_Init(&huart1);
HAL_NVIC_SetPriority(USART1_IRQn, 6, 0);
HAL_NVIC_SetPriority(USART1_IRQn, 7, 0);
HAL_NVIC_EnableIRQ(USART1_IRQn);
__HAL_UART_ENABLE_IT(&huart1, UART_IT_RXNE);
@ -156,7 +148,7 @@ void bsp_hw_init()
if (HAL_SPI_Init(&hspi1) != HAL_OK)
{
Error_Handler();
Error_Handler(0);
}
__HAL_SPI_ENABLE(&hspi1);
@ -175,7 +167,7 @@ void bsp_hw_init()
huart2.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT;
HAL_UART_Init(&huart2);
HAL_NVIC_SetPriority(USART2_IRQn, 5, 0);
HAL_NVIC_SetPriority(USART2_IRQn, 7, 0);
HAL_NVIC_EnableIRQ(USART2_IRQn);
__HAL_UART_ENABLE_IT(&huart2, UART_IT_RXNE);
@ -192,9 +184,6 @@ void bsp_hw_init()
HAL_TIM_Base_Init(&htim2);
HAL_NVIC_SetPriority(TIM2_IRQn, 5, 0);
HAL_NVIC_EnableIRQ(TIM2_IRQn);
// I2C
hi2c1.Instance = I2C1;
hi2c1.Init.Timing = 0x00702991;
@ -207,26 +196,41 @@ void bsp_hw_init()
hi2c1.Init.NoStretchMode = I2C_NOSTRETCH_DISABLE;
if (HAL_I2C_Init(&hi2c1) != HAL_OK)
{
Error_Handler();
Error_Handler(0);
}
/** Configure Analogue filter
*/
if (HAL_I2CEx_ConfigAnalogFilter(&hi2c1, I2C_ANALOGFILTER_ENABLE) != HAL_OK)
{
Error_Handler();
Error_Handler(0);
}
/** Configure Digital filter
*/
if (HAL_I2CEx_ConfigDigitalFilter(&hi2c1, 0) != HAL_OK)
{
Error_Handler();
Error_Handler(0);
}
// 1PPS signal
HAL_NVIC_SetPriority(EXTI2_IRQn, 6, 0);
HAL_NVIC_EnableIRQ(EXTI2_IRQn);
// SOTDMA
HAL_NVIC_SetPriority(TIM2_IRQn, 1, 0);
HAL_NVIC_EnableIRQ(TIM2_IRQn);
// RF IC clock interrupts
HAL_NVIC_SetPriority(EXTI15_10_IRQn, 1, 0);
HAL_NVIC_EnableIRQ(EXTI15_10_IRQn);
HAL_NVIC_SetPriority(EXTI3_IRQn, 1, 0);
HAL_NVIC_EnableIRQ(EXTI3_IRQn);
// This is our HAL tick timer now
HAL_NVIC_SetPriority(TIM6_DAC_IRQn, 0, 0);
}
bool bsp_is_tx_disabled()
{
return false;
}
void SystemClock_Config()
{
@ -238,14 +242,13 @@ void SystemClock_Config()
*/
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI;
RCC_OscInitStruct.HSIState = RCC_HSI_ON;
RCC_OscInitStruct.HSICalibrationValue = 16;
RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI;
RCC_OscInitStruct.PLL.PLLM = 1;
RCC_OscInitStruct.PLL.PLLN = 10; // 80 MHz
//RCC_OscInitStruct.PLL.PLLN = 8; // 64 MHz
//RCC_OscInitStruct.PLL.PLLN = 6; // 48 MHz
#ifdef STM32L432xx
RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV7;
#endif
@ -253,7 +256,7 @@ void SystemClock_Config()
RCC_OscInitStruct.PLL.PLLR = RCC_PLLR_DIV2;
if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
{
Error_Handler();
Error_Handler(0);
}
/**Initializes the CPU, AHB and APB bus clocks
@ -267,21 +270,21 @@ void SystemClock_Config()
if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_4) != HAL_OK)
{
Error_Handler();
Error_Handler(0);
}
PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USART1;
PeriphClkInit.Usart1ClockSelection = RCC_USART1CLKSOURCE_HSI;
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK)
{
Error_Handler();
Error_Handler(0);
}
/**Configure the main internal regulator output voltage
*/
if (HAL_PWREx_ControlVoltageScaling(PWR_REGULATOR_VOLTAGE_SCALE1) != HAL_OK)
{
Error_Handler();
Error_Handler(0);
}
/**Configure the Systick interrupt time
@ -321,6 +324,10 @@ void HAL_MspInit(void)
HAL_NVIC_SetPriorityGrouping(NVIC_PRIORITYGROUP_4);
/**
* Some of these interrupts will be managed and configured in FreeRTOS
*/
/* System interrupt init*/
/* MemoryManagement_IRQn interrupt configuration */
HAL_NVIC_SetPriority(MemoryManagement_IRQn, 0, 0);
@ -329,13 +336,16 @@ void HAL_MspInit(void)
/* UsageFault_IRQn interrupt configuration */
HAL_NVIC_SetPriority(UsageFault_IRQn, 0, 0);
/* SVCall_IRQn interrupt configuration */
HAL_NVIC_SetPriority(SVCall_IRQn, 0, 0);
HAL_NVIC_SetPriority(SVCall_IRQn, 10, 0);
/* DebugMonitor_IRQn interrupt configuration */
HAL_NVIC_SetPriority(DebugMonitor_IRQn, 0, 0);
/* PendSV_IRQn interrupt configuration */
HAL_NVIC_SetPriority(PendSV_IRQn, 0, 0);
HAL_NVIC_SetPriority(PendSV_IRQn, 10, 0);
/* SysTick_IRQn interrupt configuration */
#ifndef RTOS
HAL_NVIC_SetPriority(SysTick_IRQn, 0, 0);
#endif
/* USER CODE BEGIN MspInit 1 */
@ -344,7 +354,7 @@ void HAL_MspInit(void)
void bsp_set_rx_mode()
{
HAL_GPIO_WritePin(TX_CTRL_PORT, TX_CTRL_PIN, GPIO_PIN_RESET);
HAL_GPIO_WritePin(TX_CTRL_PORT, TX_CTRL_PIN, GPIO_PIN_RESET); // Kill the RF MOSFET bias voltage
GPIO_InitTypeDef gpio;
gpio.Pin = TRX_IC_DATA_PIN;
@ -363,19 +373,21 @@ void bsp_set_tx_mode()
gpio.Pull = GPIO_NOPULL;
HAL_GPIO_Init(TRX_IC_DATA_PORT, &gpio);
HAL_GPIO_WritePin(TX_CTRL_PORT, TX_CTRL_PIN, GPIO_PIN_SET);
HAL_GPIO_WritePin(TX_CTRL_PORT, TX_CTRL_PIN, GPIO_PIN_SET); // RF MOSFET bias voltage
}
void bsp_gnss_on()
{
// Do nothing
HAL_GPIO_WritePin(GNSS_EN_PORT, GNSS_EN_PIN, GPIO_PIN_SET);
}
void bsp_gnss_off()
{
// Do nothing
HAL_GPIO_WritePin(GNSS_EN_PORT, GNSS_EN_PIN, GPIO_PIN_RESET);
HAL_Delay(10);
}
void USART_putc(USART_TypeDef* USARTx, char c)
{
while ( !(USARTx->ISR & USART_ISR_TXE) )
@ -471,14 +483,13 @@ uint32_t bsp_get_system_clock()
uint8_t bsp_tx_spi_byte(uint8_t data)
{
uint8_t result = 0;
HAL_SPI_TransmitReceive(&hspi1, &data, &result, 1, 10);
HAL_SPI_TransmitReceive(&hspi1, &data, &result, 1, 2);
return result;
}
bool bsp_erase_station_data()
{
uint8_t b = 0xff;
HAL_GPIO_WritePin(EEPROM_WREN_PORT, EEPROM_WREN_PIN, GPIO_PIN_RESET);
HAL_Delay(1);
for ( unsigned i = 0; i < sizeof(StationData); ++i )
@ -486,14 +497,12 @@ bool bsp_erase_station_data()
HAL_I2C_Mem_Write(&hi2c1, EEPROM_ADDRESS, i, 1, &b, 1, 100);
HAL_Delay(6);
}
HAL_GPIO_WritePin(EEPROM_WREN_PORT, EEPROM_WREN_PIN, GPIO_PIN_SET);
return true;
}
bool bsp_save_station_data(const StationData &data)
{
HAL_GPIO_WritePin(EEPROM_WREN_PORT, EEPROM_WREN_PIN, GPIO_PIN_RESET);
HAL_Delay(1);
uint8_t *b = (uint8_t*)&data;
@ -503,8 +512,6 @@ bool bsp_save_station_data(const StationData &data)
HAL_Delay(6);
}
HAL_GPIO_WritePin(EEPROM_WREN_PORT, EEPROM_WREN_PIN, GPIO_PIN_SET);
return true;
}
@ -524,24 +531,37 @@ bool bsp_read_station_data(StationData &data)
return true;
}
bool bsp_is_tx_disabled()
{
return HAL_GPIO_ReadPin(TX_DISABLE_PORT, TX_DISABLE_PIN) == GPIO_PIN_RESET;
}
void bsp_enter_dfu()
{
/**
* The RC delay circuit feeding BOOT0 from this GPIO will latch the voltage high
* long enough for the next reset to invoke the ROM bootloader. This is the cleanest
* way to go about it. The alternative requires that we shut down all peripherals and
* disable every interrupt including Systick.
*/
// Cut off the GPS signals immediately to prevent its UART from transmitting and hijacking the bootloader upon reset
bsp_gnss_off();
// This flag simply tells main() to jump to the ROM bootloader immediately upon reset, before initializing anything
*(uint32_t*)DFU_FLAG_ADDRESS = DFU_FLAG_MAGIC;
/**
* BUG: This can never work with this board, because the GNSS UART is constantly sending data, so the bootloader
* will enable DFU protocol on that USART instead of the main one :(
*/
HAL_GPIO_WritePin(DFU_EN_PORT, DFU_EN_PIN, GPIO_PIN_SET);
HAL_Delay(5);
bsp_reboot();
}
void bsp_signal_rx_event()
{
HAL_GPIO_WritePin(RX_EVT_PORT, RX_EVT_PIN, GPIO_PIN_SET);
}
void bsp_signal_tx_event()
{
HAL_GPIO_WritePin(TX_EVT_PORT, TX_EVT_PIN, GPIO_PIN_SET);
}
void bsp_signal_gps_status(bool tracking)
{
HAL_GPIO_WritePin(GNSS_STATE_PORT, GNSS_STATE_PIN, tracking ? GPIO_PIN_SET: GPIO_PIN_RESET);
}
extern "C"
{
@ -601,16 +621,27 @@ extern "C"
}
}
void EXTI1_IRQHandler(void)
void EXTI15_10_IRQHandler(void)
{
if ( __HAL_GPIO_EXTI_GET_IT(GPIO_PIN_1) != RESET )
if ( __HAL_GPIO_EXTI_GET_IT(GPIO_PIN_15) != RESET )
{
__HAL_GPIO_EXTI_CLEAR_IT(GPIO_PIN_1);
__HAL_GPIO_EXTI_CLEAR_IT(GPIO_PIN_15);
if ( trxClockCallback )
trxClockCallback();
}
}
void HAL_SYSTICK_Callback()
{
static int count = 1;
if ( count++ % 20 == 0 )
{
count = 1;
HAL_GPIO_WritePin(RX_EVT_PORT, RX_EVT_PIN, GPIO_PIN_RESET);
HAL_GPIO_WritePin(TX_EVT_PORT, TX_EVT_PIN, GPIO_PIN_RESET);
}
}
}
#endif