Skip to content

Commit

Permalink
TV F7 Migration + PCB bring up (#85)
Browse files Browse the repository at this point in the history
* TV working

* GPS fully updated, Magnetometer removed (no longer needed)

* Fixed CircleCI Error

* small change

---------

Co-authored-by: AdityaAsGithub <[email protected]>
  • Loading branch information
AdityaAsGithub and AdityaAsGithub authored Jan 30, 2024
1 parent cb9e4cd commit d4790b5
Show file tree
Hide file tree
Showing 15 changed files with 326 additions and 422 deletions.
6 changes: 3 additions & 3 deletions .vscode/launch.json
Original file line number Diff line number Diff line change
Expand Up @@ -67,11 +67,11 @@
"request": "launch",
"type": "cortex-debug",
"servertype": "openocd",
"device:": "STM32L471RE",
"svdFile": "${workspaceRoot}/common/svd/STM32L4x2.svd",
"device:": "STM32F732RE",
"svdFile": "${workspaceRoot}/common/svd/STM32F7x.svd",
"configFiles": [
"interface/stlink.cfg",
"target/stm32l4x.cfg"
"target/stm32f7x.cfg"
],
"debuggerArgs": [
"-d",
Expand Down
17 changes: 17 additions & 0 deletions common/phal_F4_F7/gpio/gpio.h
Original file line number Diff line number Diff line change
Expand Up @@ -177,6 +177,7 @@ typedef struct
If you find yourself adding the same pin mappings to multiple devices, add a macro below
to cut down on duplication.
*/
#ifdef STM32F407xx
//CAN
#define GPIO_INIT_CANRX_PD0 GPIO_INIT_AF(GPIOD, 0, 9, GPIO_OUTPUT_ULTRA_SPEED, GPIO_OUTPUT_OPEN_DRAIN, GPIO_INPUT_OPEN_DRAIN)
#define GPIO_INIT_CANTX_PD1 GPIO_INIT_AF(GPIOD, 1, 9, GPIO_OUTPUT_ULTRA_SPEED, GPIO_OUTPUT_PUSH_PULL, GPIO_INPUT_OPEN_DRAIN)
Expand All @@ -196,6 +197,22 @@ typedef struct

#define GPIO_INIT_USART2TX_PA2 GPIO_INIT_AF(GPIOA, 2, 7, GPIO_OUTPUT_ULTRA_SPEED, GPIO_OUTPUT_PUSH_PULL, GPIO_INPUT_OPEN_DRAIN)
#define GPIO_INIT_USART2RX_PA3 GPIO_INIT_AF(GPIOA, 3, 7, GPIO_OUTPUT_ULTRA_SPEED, GPIO_OUTPUT_OPEN_DRAIN, GPIO_INPUT_OPEN_DRAIN)
#endif

#ifdef STM32F732xx
//CAN
#define GPIO_INIT_CANRX_PA11 GPIO_INIT_AF(GPIOA, 11, 9, GPIO_OUTPUT_ULTRA_SPEED, GPIO_OUTPUT_OPEN_DRAIN, GPIO_INPUT_OPEN_DRAIN)
#define GPIO_INIT_CANTX_PA12 GPIO_INIT_AF(GPIOA, 12, 9, GPIO_OUTPUT_ULTRA_SPEED, GPIO_OUTPUT_PUSH_PULL, GPIO_INPUT_OPEN_DRAIN)


//SPI



//UART/USART
#define GPIO_INIT_UART4TX_PA0 GPIO_INIT_AF(GPIOA, 0, 8, GPIO_OUTPUT_ULTRA_SPEED, GPIO_OUTPUT_PUSH_PULL, GPIO_INPUT_OPEN_DRAIN)
#define GPIO_INIT_UART4RX_PA1 GPIO_INIT_AF(GPIOA, 1, 8, GPIO_OUTPUT_ULTRA_SPEED, GPIO_OUTPUT_OPEN_DRAIN, GPIO_INPUT_OPEN_DRAIN)
#endif

#define GPIO_INIT_USART1TX_PA9 GPIO_INIT_AF(GPIOA, 9, 7, GPIO_OUTPUT_ULTRA_SPEED, GPIO_OUTPUT_PUSH_PULL, GPIO_INPUT_OPEN_DRAIN)
#define GPIO_INIT_USART1RX_PA10 GPIO_INIT_AF(GPIOA, 10, 7, GPIO_OUTPUT_ULTRA_SPEED, GPIO_OUTPUT_OPEN_DRAIN, GPIO_INPUT_OPEN_DRAIN)
Expand Down
175 changes: 175 additions & 0 deletions common/phal_F4_F7/usart/usart.c
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,7 @@ bool PHAL_initUSART(usart_init_t* handle, const uint32_t fck)

// Enable peripheral clock in RCC
// ADD: When adding a new peripheral, be sure to enable the clock here
#ifdef STM32F407xx
switch ((ptr_int) handle->periph) {
case USART1_BASE:
RCC->APB2ENR |= RCC_APB2ENR_USART1EN;
Expand All @@ -59,6 +60,16 @@ bool PHAL_initUSART(usart_init_t* handle, const uint32_t fck)
default:
return false;
}
#endif
#ifdef STM32F732xx
switch ((ptr_int) handle->periph) {
case UART4_BASE:
RCC->APB1ENR |= RCC_APB1ENR_UART4EN;
break;
default:
return false;
}
#endif

// The following FBRG configuration is based off RM0090 p. 978 - 980
over8 = 8 << !handle->ovsample;
Expand Down Expand Up @@ -131,15 +142,31 @@ bool PHAL_usartTxDma(usart_init_t* handle, uint16_t* data, uint32_t len) {
while ((active_uarts[handle->usart_active_num].active_handle->periph->SR & USART_SR_RXNE))
;
#endif
#ifdef STM32F732xx
// Ensure any RX data is not overwritten before continuing with transfer
while ((active_uarts[handle->usart_active_num].active_handle->periph->ISR & USART_ISR_RXNE))
;
#endif
// Enable All Interrupts needed to complete Tx transaction
// ADD: Ensure you enable the TX DMA interrupt for a new UART peripheral
#ifdef STM32F407xx
switch ((ptr_int) handle->periph) {
case USART2_BASE:
NVIC_EnableIRQ(DMA1_Stream6_IRQn);
break;
default:
return false;
}
#endif
#ifdef STM32F732xx
switch ((ptr_int) handle->periph) {
case UART4_BASE:
NVIC_EnableIRQ(DMA1_Stream4_IRQn);
break;
default:
return false;
}
#endif
PHAL_DMA_setTxferLength(handle->tx_dma_cfg, len);
PHAL_DMA_setMemAddress(handle->tx_dma_cfg, (uint32_t) data);

Expand Down Expand Up @@ -167,6 +194,7 @@ bool PHAL_usartRxDma(usart_init_t* handle, uint16_t* data, uint32_t len, bool co
handle->periph->CR1 |= USART_CR1_RE;
// Enable All Interrupts needed to complete Tx transaction
// ADD: Add cases to this switch statement to enable DMA and USART interrupts for RX USART peripherals
#ifdef STM32F407xx
switch ((ptr_int) handle->periph) {
case USART2_BASE:
NVIC_EnableIRQ(DMA1_Stream5_IRQn);
Expand All @@ -175,6 +203,17 @@ bool PHAL_usartRxDma(usart_init_t* handle, uint16_t* data, uint32_t len, bool co
default:
return false;
}
#endif
#ifdef STM32F732xx
switch ((ptr_int) handle->periph) {
case UART4_BASE:
NVIC_EnableIRQ(DMA1_Stream2_IRQn);
NVIC_EnableIRQ(UART4_IRQn);
break;
default:
return false;
}
#endif
// Configure parts of DMA that will not change each transaction, and enable DMA on USART
PHAL_DMA_setMemAddress(handle->rx_dma_cfg, (uint32_t) data);
handle->periph->CR3 |= USART_CR3_DMAR;
Expand All @@ -191,6 +230,7 @@ bool PHAL_disableContinousRxDMA(usart_init_t *handle)
handle->periph->CR3 &= ~USART_CR3_DMAR;
// Enable All Interrupts needed to complete Tx transaction
// ADD: Add cases to this switch statement to disable interrupts for new USART peripherals
#ifdef STM32F407xx
switch ((ptr_int) handle->periph) {
case USART2_BASE:
NVIC_DisableIRQ(DMA1_Stream5_IRQn);
Expand All @@ -199,6 +239,17 @@ bool PHAL_disableContinousRxDMA(usart_init_t *handle)
default:
return false;
}
#endif
#ifdef STM32F732xx
switch ((ptr_int) handle->periph) {
case USART2_BASE:
NVIC_DisableIRQ(DMA1_Stream2_IRQn);
NVIC_DisableIRQ(UART4_IRQn);
break;
default:
return false;
}
#endif
// RX will no longer be busy
active_uarts[handle->usart_active_num]._rx_busy = 0;
}
Expand Down Expand Up @@ -289,6 +340,93 @@ static void handleUsartIRQ(USART_TypeDef *handle, uint8_t idx)
}
//NOTE: According to RM0090, it is not safe to clear the TC bit unless Multibuffer mode is enabled.
#endif

#ifdef STM32F732xx
uint32_t sr = handle->ISR;
static uint32_t trash;
// USART RX Not Empty interrupt flag
if ( sr & USART_ISR_RXNE)
{
// Rx transaction is beginning, so set rx to busy and enable DMA to recieve this message
active_uarts[idx]._rx_busy = 1;
PHAL_DMA_setTxferLength(active_uarts[idx].active_handle->rx_dma_cfg, active_uarts[idx].rxfer_size);
PHAL_reEnable(active_uarts[idx].active_handle->rx_dma_cfg);
// QUESTION:
// active_uarts[idx].active_handle->periph->ICR |= USART_ICR_RXNECF; // Clear RXNE interrupt flag
// trash = active_uarts[idx].active_handle->periph->; // Clear RXNE interrupt flag
// We only need to enable DMA immediately after the reception of the first bit
// We also do not want this interrupt activating for every single bit recieved on the rx buffer
active_uarts[idx].active_handle->periph->CR1 &= ~USART_CR1_RXNEIE;
// Clear any errors that may have been set in the previous Rx
active_uarts[idx].active_handle->rx_errors.framing_error = 0;
active_uarts[idx].active_handle->rx_errors.noise_detected = 0;
active_uarts[idx].active_handle->rx_errors.overrun = 0;
active_uarts[idx].active_handle->rx_errors.parity_error = 0;
}
// Clear to send flag
if (sr & USART_ISR_CTS)
{
active_uarts[idx].active_handle->periph->ICR |= USART_ICR_CMCF; // We currently do not plan on using CTS or LIN mode in the near future, so this is placeholder code for the future
}
// Lin Break Detection flag
if (sr & USART_ISR_LBDF)
{
active_uarts[idx].active_handle->periph->ICR |= USART_ICR_LBDCF; // We currently do not plan on using CTS or LIN mode in the near future, so this is placeholder code for the future
}
// Overrun Error Flag
if (sr & USART_ISR_ORE)
{
// Communicate these errors to the user, so we can clear this bit but leave USART clear for future transactions
active_uarts[idx].active_handle->rx_errors.overrun = 1;
active_uarts[idx].active_handle->periph->ICR |= USART_ICR_ORECF;
}
// Noise Error Flag
if (sr & USART_ISR_NE)
{
// Communicate these errors to the user, so we can clear this bit for future transactions
active_uarts[idx].active_handle->rx_errors.noise_detected = 1;
active_uarts[idx].active_handle->periph->ICR |= USART_ICR_NCF;
}
// Framing Error Flag
if (sr & USART_ISR_FE)
{
// Communicate these errors to the user, so we can clear this bit for future transactions
active_uarts[idx].active_handle->rx_errors.framing_error = 1;
active_uarts[idx].active_handle->periph->ICR |= USART_ICR_FECF;
}
// Parity Error Flag
if (sr & USART_ISR_PE)
{
// Communicate these errors to the user, so we can clear this bit for future transactions
active_uarts[idx].active_handle->rx_errors.parity_error = 1;
active_uarts[idx].active_handle->periph->ICR |= USART_ICR_PECF;
}

// Idle line is detected upon the completion of a USART reception
// This is the last flag handled, so that important info can be updated before callback function
if (sr & USART_ISR_IDLE)
{
// Stop DMA Transaction
PHAL_stopTxfer(active_uarts[idx].active_handle->rx_dma_cfg);
if (active_uarts[idx].cont_rx)
{
// Re-enable the RX not empty interrupt to accept the next message
active_uarts[idx].active_handle->periph->CR1 |= USART_CR1_RXNEIE;
}
else
{
// No more messages should be recieved, so disable RX mode for the peripheral
active_uarts[idx].active_handle->periph->CR1 &= ~USART_CR1_RE;
}
active_uarts[idx]._rx_busy = 0;
// Clear idle flag
// trash = active_uarts[idx].active_handle->periph->ISR;
// trash = active_uarts[idx].active_handle->periph->DR;
active_uarts[idx].active_handle->periph->ICR |= USART_ICR_IDLECF;
usart_recieve_complete_callback(active_uarts[idx].active_handle);
}
//NOTE: According to 0431, there is no point to clearing the TC bit (we do not handle transmissions here anyway)
#endif
}

/**
Expand Down Expand Up @@ -439,6 +577,11 @@ static void handleDMAxComplete(uint8_t idx, uint32_t irq, uint8_t dma_type)
while (!(active_uarts[idx].active_handle->periph->SR & USART_SR_TC))
;
#endif
#ifdef STM32F732xx
// Wait for the transfer complete bit to be set, indicating the completion of USART transaction
while (!(active_uarts[idx].active_handle->periph->ISR & USART_ISR_TC))
;
#endif
// TX is no longer busy, so communicate this and disable TX part of USART
active_uarts[idx]._tx_busy = 0;
active_uarts[idx].active_handle->periph->CR1 &= ~USART_CR1_TE;
Expand Down Expand Up @@ -520,6 +663,7 @@ USART TX and RX interrupts - need to modify when adding a usart peripheral

//ADD:

#ifdef STM32F407xx
// USART1:

// USART2:
Expand Down Expand Up @@ -547,4 +691,35 @@ void USART2_IRQHandler()

// USART3:

#endif

#ifdef STM32F732xx
// USART1:

// USART2:

// Add new DMA interrupt handlers here, passing in new active struct index, along with
// the correct DMA IRQ, and corresponding transfer mode (TX or Rx)
void DMA1_Stream4_IRQHandler() //TX
{
handleDMAxComplete(USART4_ACTIVE_IDX, DMA1_Stream4_IRQn, USART_DMA_TX);
}

// Add new DMA interrupt handlers here, passing in new active struct index, along with
// the correct DMA IRQ, and corresponding transfer mode (TX or Rx)
void DMA1_Stream2_IRQHandler() //RX
{
handleDMAxComplete(USART4_ACTIVE_IDX, DMA1_Stream2_IRQn, USART_DMA_RX);
}

// Add new USART Interrupts as new peripherals are needed,
// feeding in the new USART peripheral, along with active array index
void UART4_IRQHandler()
{
handleUsartIRQ(UART4, USART4_ACTIVE_IDX);
}

// USART3:

#endif
//...etc
16 changes: 8 additions & 8 deletions common/phal_F4_F7/usart/usart.h
Original file line number Diff line number Diff line change
Expand Up @@ -228,24 +228,24 @@ extern void usart_recieve_complete_callback(usart_init_t *handle);
.periph=DMA1, .stream=DMA1_Stream6 \
}
#else
#define USART2_RXDMA_CONT_CONFIG(rx_addr_, priority_) \
#define USART4_RXDMA_CONT_CONFIG(rx_addr_, priority_) \
{ \
.periph_addr = (uint32_t) & (USART2->TDR), .mem_addr = (uint32_t)(rx_addr_), \
.periph_addr = (uint32_t) & (UART4->RDR), .mem_addr = (uint32_t)(rx_addr_), \
.tx_size = 1, .increment = false, .circular = false, \
.dir = 0b0, .mem_inc = true, .periph_inc = false, .mem_to_mem = false, \
.priority = (priority_), .mem_size = 0b00, .periph_size = 0b00, \
.tx_isr_en = false, .dma_chan_request=0b0100, .stream_idx=5, \
.periph=DMA1, .stream=DMA1_Stream5 \
.tx_isr_en = true, .dma_chan_request=0b0100, .stream_idx=2, \
.periph=DMA1, .stream=DMA1_Stream2 \
}

#define USART2_TXDMA_CONT_CONFIG(tx_addr_, priority_) \
#define USART4_TXDMA_CONT_CONFIG(tx_addr_, priority_) \
{ \
.periph_addr = (uint32_t) & (USART2->RDR), .mem_addr = (uint32_t)(tx_addr_), \
.periph_addr = (uint32_t) & (UART4->TDR), .mem_addr = (uint32_t)(tx_addr_), \
.tx_size = 1, .increment = false, .circular = false, \
.dir = 0b1, .mem_inc = true, .periph_inc = false, .mem_to_mem = false, \
.priority = (priority_), .mem_size = 0b00, .periph_size = 0b00, \
.tx_isr_en = true, .dma_chan_request=0b0100, .stream_idx=6, \
.periph=DMA1, .stream=DMA1_Stream6 \
.tx_isr_en = true, .dma_chan_request=0b0100, .stream_idx=4, \
.periph=DMA1, .stream=DMA1_Stream4 \
}
#endif
#endif
4 changes: 2 additions & 2 deletions source/torque_vector/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ target_link_libraries(${TARGET_NAME} ${CMAKE_CURRENT_LIST_DIR}/bsxlite/libalgobs
set_target_properties(${TARGET_NAME} PROPERTIES
COMPONENT_NAME ${COMPONENT_NAME}
COMPONENT_DIR ${CMAKE_CURRENT_LIST_DIR}
LINKER_SCRIPT "STM32L496VGTx_FLASH"
COMMON_LIBS "CMSIS_L471;PSCHED_L471;QUEUE;PHAL_L471;libm.a;"
LINKER_SCRIPT "STM32F732RETX_FLASH"
COMMON_LIBS "CMSIS_F732;PSCHED_F732;QUEUE;PHAL_F732;libm.a;"
)
COMMON_FIRMWARE_COMPONENT(${TARGET_NAME})
2 changes: 1 addition & 1 deletion source/torque_vector/bmi/bmi088.c
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@

#include "bmi088.h"
#include "bsxlite_interface.h"
#include "common/phal_L4/spi/spi.h"
#include "common/phal_F4_F7/spi/spi.h"
#include "common_defs.h"
#include "main.h"

Expand Down
5 changes: 2 additions & 3 deletions source/torque_vector/bmi/bmi088.h
Original file line number Diff line number Diff line change
Expand Up @@ -12,13 +12,12 @@
#ifndef _BMI_H_
#define _BMI_H_

#include "stm32l4xx.h"
#include <stdint.h>
#include <inttypes.h>
#include <stdbool.h>
#include "bsxlite_interface.h"
#include "common/phal_L4/gpio/gpio.h"
#include "common/phal_L4/spi/spi.h"
#include "common/phal_F4_F7/gpio/gpio.h"
#include "common/phal_F4_F7/spi/spi.h"

#define BMI088_GYRO_CHIP_ID (0x0FU)
#define BMI088_ACC_CHIP_ID (0x1EU)
Expand Down
Loading

0 comments on commit d4790b5

Please sign in to comment.