Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions Q24ECU/.vscode/c_cpp_properties.json
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
"${workspaceFolder}/core/include",
"${workspaceFolder}/core/include",
"${workspaceFolder}/vendor/cmsis_f4/Include",
"${workspaceFolder}/core/include",
"${workspaceFolder}/core/include"
],
"defines": [
Expand Down
4 changes: 3 additions & 1 deletion Q24ECU/.vscode/settings.json
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,8 @@
"interface_uart.h": "c",
"task.h": "c",
"freertosconfig.h": "c",
"hal_can.h": "c"
"hal_can.h": "c",
"uart.h": "c",
"tasker.h": "c"
},
}
3 changes: 2 additions & 1 deletion Q24ECU/core/config/FreeRTOSConfig.h
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@
#define configCPU_CLOCK_HZ ( 180000000 )
#define configTICK_RATE_HZ ((TickType_t)1000)
#define configMAX_PRIORITIES ( 32 )
#define configMINIMAL_STACK_SIZE ((uint16_t)256)
#define configMINIMAL_STACK_SIZE ((uint16_t)128)
#define configTOTAL_HEAP_SIZE ((size_t)15360)
#define configMAX_TASK_NAME_LEN ( 16 )
#define configUSE_16_BIT_TICKS 0
Expand Down Expand Up @@ -94,6 +94,7 @@ to exclude the API function. */
#define INCLUDE_eTaskGetState 1

#define INCLUDE_xTaskDelayUntil 1
#define INCLUDE_xSemaphoreGetMutexHolder 1

/* Cortex-M specific definitions. */
#ifdef __NVIC_PRIO_BITS
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
* @file interface_adc.h
* @author Jacob Chisholm (https://jchisholm204.github.io/)
* @brief FreeRTOS ADC Interface for QFSAE VCU
* @version 0.1
* @version 1.1
* @date 2024-02-24
*
* @copyright Copyright (c) 2024
Expand All @@ -14,7 +14,10 @@
#include "stm32f4xx.h"
#include "stdbool.h"
#include "float.h"
#include "inttypes.h"
#include "hal/hal_adc.h"
#include "hal/hal_dma.h"
#include "hal/hal_gpio.h"
#include "FreeRTOS.h"
#include "pins.h"

Expand All @@ -40,21 +43,18 @@ enum ADC_CHANNEL {
};

/**
* @brief OS ADC Setup Handler
* @brief ADC Initialization Handler
*
* This function should be called to init the ADC bus and handler interfaces
* This function will initialize the ADC and DMA interfaces.
* This function should not be called more than once
* ALL CAN bus initialization should happen within this function
*
* Called in main
*
*/
extern void os_adc_setup(void);
extern void adc_init(void);

/**
* @brief Fetch the last recorded voltage of an ADC channel
* @brief Read the last recorded voltage of an ADC channel
*
* @param channel the channel to draw from
* @param channel the channel to read
* @returns the voltage of the channel
*/
extern double adc_fetch(enum ADC_CHANNEL channel);
extern double adc_read(enum ADC_CHANNEL channel);
58 changes: 58 additions & 0 deletions Q24ECU/core/include/drivers/can.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,58 @@
/**
* @file can.h
* @author Jacob Chisholm (https://jchisholm204.github.io/)
* @brief FreeRTOS CAN bus Interface for QFSAE VCU
* @version 1.1
* @date 2024-03-04
*
* Version 1.0
* - Created CAN Interface code
* Version 1.1
* - Refactored as a driver
*
* @copyright Copyright (c) 2024
*
*/

#pragma once
#include "stm32f4xx.h"
#include "stdbool.h"
#include "hal/hal_can.h"
#include "FreeRTOS.h"


/**
* @brief CAN Initialization Handler
*
* This function will initialize the CAN bus and handler interfaces
* This function should not be called more than once
*
* @note This Driver initializes a FreeRTOS Task in order to function
*/
extern void can_init(void);


/**
* @brief Get most current copy of a CAN message based on its ID
*
* @param CAN The Physical CAN Bus the message was received on
* @param id The CAN ID of the message
* @return can_msg_t
*/
extern can_msg_t can_read(CAN_TypeDef *CAN, uint32_t id);


/**
* @brief Send a message on the CAN Bus
*
* @param CAN The Physical CAN bus to use
* @param tx_msg The CAN Message to send
* @param timeout The Timeout to wait to claim a CAN mailbox
* @returns SYS_OK or the associated error
*/
extern uint8_t can_write(CAN_TypeDef *CAN, can_msg_t *tx_msg, TickType_t timeout);

/* All IRQ Handlers must be globally accessible for linking purposes */

// CAN1 Receive IRQ Handler
extern void CAN1_RX0_IRQHandler(void);
120 changes: 120 additions & 0 deletions Q24ECU/core/include/drivers/uart.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,120 @@
/**
* @file uart.h
* @author Jacob Chisholm (Jchisholm204.github.io)
* @brief UART Driver (For FreeRTOS based system)
* @version 1.2
* @date 2024-03-04
*
* Version 1.0
* - Created UART Interface code
* Version 1.1
* - Added RX Interrupt + Handler
* Version 1.2
* - Refactored as a driver (No task + buffer handling done outside of driver)
*
* @copyright Copyright (c) 2024
*
*/

#pragma once

#include "hal/hal_uart.h"
#include "FreeRTOS.h"
#include "semphr.h"
#include "stream_buffer.h"
#include "errors.h"


typedef struct UART_StreamBuffer {
char buffer[64];
StaticStreamBuffer_t staticBuffer;
StreamBufferHandle_t handle;
} UART_StreamBuffer_t;


/**
* @brief UART port typedef
* @param port The UART port (CMSIS UART typedef)
* @param writeHandler The semaphore controlling write access to the UART port
* @param readHandler The semaphore controlling read access to the UART receive buffer
* @param pbuffer Pointer to the receive buffer loaded by the UART IRQ Handler
*
*/
typedef struct UART_Handle {
USART_TypeDef *pUART;
StaticSemaphore_t writeSemaphore;
xSemaphoreHandle writeHandler;
StaticSemaphore_t readSemaphore;
xSemaphoreHandle readHandler;
StreamBufferHandle_t *pBuffer;
} UART_Handle_t;

extern UART_Handle_t Serial2, Serial4;


/**
* @brief UART Initialization Handler
*
* This function will initialize all onboard UART interfaces.
* This function should not be called more than once.
*
*/
extern void uart_init(unsigned long baud);

/**
* @brief Open a UART RX Buffer (enables RX Interrupts)
* @note Buffer Handling must be done inside the calling function
* @param pHandle Pointer to the UART Handle to open
* @param stream A pointer to preallocated memory for the stream buffer
* @param timeout The amount of ticks to wait for the interface to become available
* @return SYS_OK if successful
*/
extern enum SYS_ERROR uart_open_buffer(UART_Handle_t *pHandle, UART_StreamBuffer_t *stream, TickType_t timeout);

/**
* @brief Close a UART RX Buffer (disables RX Interrupts)
*
* @param pHandle Pointer to the Handle to close
* @return SYS_OK if successful
*/
extern enum SYS_ERROR uart_close_buffer(UART_Handle_t *pHandle);

/**
* @brief Write a byte to a UART port
*
* @param pHandle Pointer to the Handle for the port to write to
* @param byte byte to write
* @param timeout The amount of ticks to wait for the interface to become available
* @return SYS_OK if successful
*/
extern enum SYS_ERROR uart_write_byte(UART_Handle_t *pHandle, char byte, TickType_t timeout);

/**
* @brief Write a buffer to a UART port
*
* @param pHandle Pointer to the Handle for the port to write to
* @param buf A pointer to the buffer to write
* @param timeout The amount of ticks to wait for the interface to become available
* @return SYS_OK if successful
*/
extern enum SYS_ERROR uart_write(UART_Handle_t *pHandle, char* buf, size_t len, TickType_t timeout);

/**
* @brief Write a String to a uart port
*
* @param pHandle Pointer to the Handle for the port to write to
* @param str The String to write
* @param timeout The amount of ticks to wait for the interface to become available
* @return SYS_OK if successful
*/
extern enum SYS_ERROR uart_write_str(UART_Handle_t *pHandle, char* str, TickType_t timeout);


/* All IRQ Handlers must be globally accessible for linking purposes */

// USART2 IQR Handler
extern void USART2_IRQHandler(void);

// USART2 IQR Handler
extern void UART4_IRQHandler(void);

4 changes: 4 additions & 0 deletions Q24ECU/core/include/hal/hal_clock.h
Original file line number Diff line number Diff line change
Expand Up @@ -57,3 +57,7 @@ static inline void clock_init(void){
while (!(RCC->CFGR & RCC_CFGR_SWS_PLL)) __asm__("nop"); // Wait until done
}

static inline void spin(volatile uint32_t count) {
while (count--) __asm__("nop");
}

4 changes: 4 additions & 0 deletions Q24ECU/core/include/hal/hal_dma.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,9 @@
#pragma once

#include "stm32f4xx.h"
#include <inttypes.h>
#include "errors.h"
#include <stddef.h>

enum DMA_CHANNEL {
DMA_CHANNEL_0 = 0,
Expand Down Expand Up @@ -54,6 +56,8 @@ enum DMA_MEM_SIZE {
* @param periph_addr Peripheral Address
* @param mem_addr Memory Address
*/


static inline enum SYS_ERROR hal_dma_init(DMA_TypeDef *dma, DMA_Stream_TypeDef *stream, enum DMA_CHANNEL ch, enum DMA_PRIORITY priority, enum DMA_MEM_SIZE mem_size, volatile void *periph_addr, void *mem_addr, size_t num_transfers) {
// Enable DMA Clock
if (dma == DMA1) {
Expand Down
24 changes: 12 additions & 12 deletions Q24ECU/core/include/hal/hal_gpio.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
#include <stdbool.h>
#include <sys/stat.h>

#include <stm32f446xx.h>
#include "stm32f4xx.h"
#include "hal_clock.h"
#include "pins.h"

Expand All @@ -27,9 +27,9 @@ enum GPIO_AF_MODE { GPIO_AF_SYS = 0, GPIO_AF_TIM1 = 1, GPIO_AF_TIM2 = 1, GPIO_AF
static inline void gpio_set_mode(uint16_t pin, enum GPIO_MODE_IO mode) {
GPIO_TypeDef *gpio = GPIO(PINBANK(pin));
int n = PINNO(pin);
RCC->AHB1ENR |= BIT(PINBANK(pin)); // Enable GPIO clock
gpio->MODER &= ~(3U << (n*2));
gpio->MODER |= (mode & 3U) << (n * 2); // Set new mode
SET_BIT(RCC->AHB1ENR, (uint32_t)(1UL << PINBANK(pin))); // Enable GPIO clock
gpio->MODER &= (uint32_t)~(3U << (n*2));
gpio->MODER |= (uint32_t)((mode & 3U) << (n * 2)); // Set new mode

}

Expand All @@ -42,8 +42,8 @@ static inline void gpio_set_mode(uint16_t pin, enum GPIO_MODE_IO mode) {
static inline void gpio_set_af(uint16_t pin, enum GPIO_AF_MODE af) {
GPIO_TypeDef *gpio = GPIO(PINBANK(pin));
int n = PINNO(pin);
gpio->AFR[n >> 3] &= ~(15UL << ((n & 7) * 4));
gpio->AFR[n >> 3] |= ((uint32_t) af) << ((n & 7) * 4);
gpio->AFR[n >> 3] &= (uint32_t)~(15UL << ((n & 7) * 4));
gpio->AFR[n >> 3] |= (uint32_t)((uint32_t) af) << ((n & 7) * 4);
}

/**
Expand All @@ -54,28 +54,28 @@ static inline void gpio_set_af(uint16_t pin, enum GPIO_AF_MODE af) {
*/
static inline void gpio_write(uint16_t pin, bool value) {
GPIO_TypeDef *gpio = GPIO(PINBANK(pin));
gpio->BSRR = (1U << PINNO(pin)) << (value ? 0 : 16);
gpio->BSRR = (uint32_t)((1UL << PINNO(pin)) << (value ? 0 : 16));
}

static inline void gpio_toggle_pin(uint16_t pin){
GPIO_TypeDef *gpio = GPIO(PINBANK(pin));
gpio->BSRR = (1UL << PINNO(pin)) << (gpio->ODR & (1UL << PINNO(pin)) ? 16 : 0);
gpio->BSRR = (uint32_t)((1UL << PINNO(pin)) << (gpio->ODR & (1UL << PINNO(pin)) ? 16 : 0));
}

static inline bool gpio_read_idr(uint16_t pin) {
const GPIO_TypeDef *gpio = GPIO(PINBANK(pin));
return (gpio->IDR & (1U << PINNO(pin)));
return (bool)((gpio->IDR >> PINNO(pin)) & 0x1UL);
}

static inline bool gpio_read_odr(uint16_t pin){
const GPIO_TypeDef *gpio = GPIO(PINBANK(pin));
return (gpio->ODR & (1U << PINNO(pin)));
return (bool)((gpio->ODR >> PINNO(pin)) & 0x1UL);
}

static inline void gpio_pull(uint16_t pin, enum GPIO_PULL_MODE mode){
GPIO_TypeDef *gpio = GPIO(PINBANK(pin));
gpio->PUPDR &= ~(3U << (PINNO(pin)*2));
if(mode!=GPIO_RESET) gpio->PUPDR |= mode << (2*(PINNO(pin)));
gpio->PUPDR &= (uint32_t)~(3U << (PINNO(pin)*2));
if(mode!=GPIO_RESET) gpio->PUPDR |= (uint32_t)(mode << (2*(PINNO(pin))));
}

// t: expiration time, prd: period, now: current time. Return true if expired
Expand Down
4 changes: 2 additions & 2 deletions Q24ECU/core/include/hal/hal_tim_basic.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,8 +30,8 @@ static inline void TIM_basic_Init(TIM_TypeDef *timer, uint16_t prescaler, uint16
timer->DIER &= ~(BIT(8U) | BIT(0U)); // reset interrupt enable reg
timer->DIER |= BIT(0); // enable timer interrupt
// TIM6->EGR |= BIT(0);
timer->ARR = (reload_register-1);//(65536);
timer->PSC = (prescaler-1);//(APB1_FREQUENCY);
timer->ARR = (uint32_t)(reload_register-1UL);//(65536);
timer->PSC = (uint32_t)(prescaler-1UL);//(APB1_FREQUENCY);
timer->CR1 &= ~(TIM_CR1_ARPE | TIM_CR1_OPM | TIM_CR1_URS | TIM_CR1_CEN); // reset timer control register 1
timer->CR1 |= (TIM_CR1_CEN); // set interrupt source to only overflow | enable timer
}
Expand Down
3 changes: 0 additions & 3 deletions Q24ECU/core/include/hal/hal_uart.h
Original file line number Diff line number Diff line change
Expand Up @@ -64,9 +64,6 @@ static inline uint8_t hal_uart_read_byte(const USART_TypeDef *uart) {
return ((uint8_t) (uart->DR & 255));
}

static inline void spin(volatile uint32_t count) {
while (count--) __asm__("nop");
}

static inline void hal_uart_write_byte(USART_TypeDef * uart, uint8_t byte) {
uart->DR = byte;
Expand Down
3 changes: 3 additions & 0 deletions Q24ECU/core/include/interfaces/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
# Interfaces

Interfaces act as abstraction between device drivers (CAN, UART, I2C) and devices on the car. For example, an interface may be used to abstract CAN bus communication between a task and the BMS.
Loading