Updated GPIO to new format

This commit is contained in:
Ea-r-th
2025-11-03 23:17:55 -08:00
parent 0b4a6ef584
commit aa7a041946
15 changed files with 264 additions and 244 deletions

View File

@@ -5,6 +5,9 @@ BUILD_DIR := build
BUILD_TYPE ?= Debug
TOOLCHAIN := gcc-arm-none-eabi.cmake
CFLAGS_DEBUG ?= -g3 -O0
CXXFLAGS_DEBUG ?= -g3 -O0
# MCU target (override on command line: make build MCU_MODEL=STM32F051x8)
MCU_MODEL ?= STM32L432xx
MCU_FAMILY ?= STM32L4xx
@@ -20,6 +23,8 @@ ${BUILD_DIR}/build.ninja:
-DCMAKE_BUILD_TYPE=${BUILD_TYPE} \
-DCMAKE_TOOLCHAIN_FILE=${TOOLCHAIN} \
-DCMAKE_EXPORT_COMPILE_COMMANDS=ON \
-DCMAKE_C_FLAGS_DEBUG="${CFLAGS_DEBUG}" \
-DCMAKE_CXX_FLAGS_DEBUG="${CXXFLAGS_DEBUG}" \
-DMCU_MODEL=$(MCU_MODEL) \
-DMCU_FAMILY=$(MCU_FAMILY)

View File

@@ -10,6 +10,7 @@
#define SHMINGO_HAL_SHAL_CORE_H
#include <cstdint>
#include <cstddef>
//Overall init function for SHAL --------------------------
@@ -70,45 +71,57 @@ bool SHAL_wait_for_condition_ms(Condition cond, uint32_t timeout_ms) {
return false; // timeout
}
//Sets bits starting from offset as the LSB
static inline void SHAL_set_bits(volatile uint32_t* reg, uint32_t size, uint32_t bits, uint32_t offset){
if(reg == nullptr){
return;
}
uint32_t mask = (1 << (size)) - 1;
*reg &= ~(mask << offset);
*reg |= bits << offset;
}
#define SHAL_set_bits(reg, size, bits, offset) \
do { \
if ((reg) != NULL) { \
uint32_t _mask = ((1U << (size)) - 1U); \
*(reg) &= ~((uint32_t)(_mask) << (offset)); \
*(reg) |= ((uint32_t)(bits) << (offset)); \
} \
} while (0)
//Sets bits starting from offset as the LSB (for uint16_t)
static inline void SHAL_set_bits_16(volatile uint16_t* reg, uint32_t size, uint32_t bits, uint32_t offset){
uint16_t mask = (1 << (size)) - 1;
*reg &= ~(mask << offset);
*reg |= bits << offset;
}
#define SHAL_flip_bits(reg, size, offset) \
do { \
if ((reg) != NULL) { \
uint32_t _mask = ((1U << (size)) - 1U); \
*(reg) ^= (_mask << (offset)); \
} \
} while (0)
static inline void SHAL_clear_bitmask(volatile uint32_t* reg, uint32_t mask){
*reg &= ~(mask);
}
#define SHAL_set_bits_16(reg, size, bits, offset) \
do { \
if ((reg) != NULL) { \
uint16_t _mask = (uint16_t)((1U << (size)) - 1U); \
*(reg) &= (uint16_t)~((uint16_t)(_mask) << (offset)); \
*(reg) |= (uint16_t)((uint16_t)(bits) << (offset)); \
} \
} while (0)
static inline void SHAL_apply_bitmask(volatile uint32_t* reg, uint32_t mask){
SHAL_clear_bitmask(reg,mask);
*reg |= mask;
}
#define SHAL_clear_bitmask(reg, mask) \
do { \
*(reg) &= ~(mask); \
} while (0)
static inline void SHAL_set_register_value(volatile uint32_t* reg, uint32_t value){
if(reg == nullptr){
return;
}
*reg = value;
}
#define SHAL_apply_bitmask(reg, mask) \
do { \
SHAL_clear_bitmask((reg), (mask)); \
*(reg) |= (mask); \
} while (0)
#define SHAL_set_register_value(reg, value) \
do { \
if ((reg) != NULL) { \
*(reg) = (uint32_t)(value); \
} \
} while (0)
#define SHAL_set_register_value_16(reg, value) \
do { \
if ((reg) != NULL) { \
*(reg) = (uint16_t)(value); \
} \
} while (0)
static inline void SHAL_set_register_value_16(volatile uint16_t* reg, uint16_t value){
if(reg == nullptr){
return;
}
*reg = value;
}
void SHAL_print_register(const volatile uint32_t* reg);

View File

@@ -11,18 +11,18 @@
#define EXTI_PENDING_REG(line) ((line) < 32 ? EXTI->PR1 : EXTI->PR2)
static inline SHAL_EXTI_Interrupt_Mask_Register getEXTIInterruptMaskRegister(uint32_t line){
uint32_t imr = line < 32 ? EXTI->IMR1 : EXTI->IMR2;
return {&imr};
volatile uint32_t* reg = line < 32 ? &EXTI->IMR1 : &EXTI->IMR2;
return {reg};;
}
static inline SHAL_EXTI_Rising_Trigger_Selection_Register getEXTIRisingTriggerSelectionRegister(uint32_t line){
auto reg = line < 32 ? EXTI->RTSR1 : EXTI->RTSR2;
return {&reg};
volatile uint32_t* reg = line < 32 ? &EXTI->RTSR1 : &EXTI->RTSR2;
return {reg};
}
static inline SHAL_EXTI_Falling_Trigger_Selection_Register getEXTIFallingTriggerSelectionRegister(uint32_t line){
auto reg = line < 32 ? EXTI->FTSR1 : EXTI->FTSR2;
return {&reg};
volatile uint32_t* reg = line < 32 ? &EXTI->FTSR1 : &EXTI->FTSR2;
return {reg};
}
#endif //SHMINGO_HAL_SHAL_EXTI_REG_L432KC_H

View File

@@ -14,51 +14,43 @@
#define PINS_PER_PORT 16
#define NUM_EXTI_LINES 16
#define AVAILABLE_GPIO \
X(A0) X(A1) X(A2) X(A3) X(A4) X(A5) X(A6) X(A7) X(A8) X(A9) X(A10) X(A11) X(A12) X(A13) X(A14) X(A15) \
X(B0) X(B1) X(B3) X(B4) X(B5) X(B6) X(B7)
//Build enum map of available SHAL_GPIO pins
enum class GPIO_Key : uint8_t {
#define X(key) key,
AVAILABLE_GPIO
#undef X
A0,
A1,
A2,
A3,
A4,
A5,
A6,
A7,
A8,
A9,
A10,
A11,
A12,
A13,
A14,
A15,
B0,
B1,
B3 = 19, //Offset to compensate for lack of B2
B4,
B5,
B6,
B7,
NUM_GPIO,
INVALID
};
constexpr SHAL_GPIO_Peripheral getGPIORegister(const GPIO_Key g){
switch(g) {
case GPIO_Key::A0: return {GPIOA,0};
case GPIO_Key::A1: return {GPIOA,1};
case GPIO_Key::A2: return {GPIOA,2};
case GPIO_Key::A3: return {GPIOA,3};
case GPIO_Key::A4: return {GPIOA,4};
case GPIO_Key::A5: return {GPIOA,5};
case GPIO_Key::A6: return {GPIOA,6};
case GPIO_Key::A7: return {GPIOA,7};
case GPIO_Key::A8: return {GPIOA,8};
case GPIO_Key::A9: return {GPIOA,9};
case GPIO_Key::A10: return {GPIOA,10};
case GPIO_Key::A11: return {GPIOA,11};
case GPIO_Key::A12: return {GPIOA,12};
case GPIO_Key::A13: return {GPIOA,13};
case GPIO_Key::A14: return {GPIOA,14};
case GPIO_Key::A15: return {GPIOA,15};
case GPIO_Key::B0: return {GPIOB,0};
case GPIO_Key::B1: return {GPIOB,1};
case GPIO_Key::B3: return {GPIOB,3};
case GPIO_Key::B4: return {GPIOB,4};
case GPIO_Key::B5: return {GPIOB,5};
case GPIO_Key::B6: return {GPIOB,6};
case GPIO_Key::B7: return {GPIOB,7};
case GPIO_Key::INVALID:
case GPIO_Key::NUM_GPIO:
assert(false);
return SHAL_GPIO_Peripheral(nullptr,0); //Unreachable
}
__builtin_unreachable();
static volatile GPIO_TypeDef * GPIO_TABLE[2] = { //Lookup table for ADCs
GPIOA,
GPIOB
};
constexpr uint8_t getGPIOPinNumber(GPIO_Key key){
return static_cast<uint8_t>(key) % 16;
}
constexpr SHAL_GPIO_EXTI_Register getGPIOEXTICR(const GPIO_Key g){
@@ -96,74 +88,56 @@ constexpr SHAL_GPIO_EXTI_Register getGPIOEXTICR(const GPIO_Key g){
__builtin_unreachable();
}
constexpr SHAL_Peripheral_Register getGPIORCCEnable(const GPIO_Key g){
switch(g) {
case GPIO_Key::A0:
case GPIO_Key::A1:
case GPIO_Key::A2:
case GPIO_Key::A3:
case GPIO_Key::A4:
case GPIO_Key::A5:
case GPIO_Key::A6:
case GPIO_Key::A7:
case GPIO_Key::A8:
case GPIO_Key::A9:
case GPIO_Key::A10:
case GPIO_Key::A11:
case GPIO_Key::A12:
case GPIO_Key::A13:
case GPIO_Key::A14:
case GPIO_Key::A15:
return {&RCC->AHB2ENR, RCC_AHB2ENR_GPIOAEN_Pos};
case GPIO_Key::B0:
case GPIO_Key::B1:
case GPIO_Key::B3:
case GPIO_Key::B4:
case GPIO_Key::B5:
case GPIO_Key::B6:
case GPIO_Key::B7:
return {&RCC->AHB2ENR, RCC_AHB2ENR_GPIOBEN_Pos};
case GPIO_Key::INVALID:
case GPIO_Key::NUM_GPIO:
assert(false);
return SHAL_Peripheral_Register(nullptr,0); //Unreachable
}
__builtin_unreachable();
static inline SHAL_GPIO_RCC_Enable_Register getGPIORCCEnable(const GPIO_Key g){
volatile uint32_t* reg = &RCC->AHB2ENR; //register
uint32_t offset;
offset = (static_cast<uint8_t>(g) / 16) == 0 ? RCC_AHB2ENR_GPIOAEN_Pos : RCC_AHB2ENR_GPIOBEN_Pos;
return {reg,offset};
}
constexpr uint32_t getGPIOPortNumber(const GPIO_Key g){
switch(g) {
case GPIO_Key::A0:
case GPIO_Key::A1:
case GPIO_Key::A2:
case GPIO_Key::A3:
case GPIO_Key::A4:
case GPIO_Key::A5:
case GPIO_Key::A6:
case GPIO_Key::A7:
case GPIO_Key::A8:
case GPIO_Key::A9:
case GPIO_Key::A10:
case GPIO_Key::A11:
case GPIO_Key::A12:
case GPIO_Key::A13:
case GPIO_Key::A14:
case GPIO_Key::A15:
return 0;
case GPIO_Key::B0:
case GPIO_Key::B1:
case GPIO_Key::B3:
case GPIO_Key::B4:
case GPIO_Key::B5:
case GPIO_Key::B6:
case GPIO_Key::B7:
return 1;
case GPIO_Key::INVALID:
case GPIO_Key::NUM_GPIO:
assert(false);
return 0;
}
__builtin_unreachable();
return (static_cast<uint8_t>(g) / 16);
}
static inline SHAL_GPIO_Mode_Register getGPIOModeRegister(const GPIO_Key key){
volatile uint32_t* reg = &GPIO_TABLE[static_cast<uint8_t>(key) / 16]->MODER;
uint32_t offset = 2 * static_cast<uint8_t>(key) % 16;
return {reg,offset};
}
static inline SHAL_GPIO_Pullup_Pulldown_Register getGPIOPUPDRegister(const GPIO_Key key){
volatile uint32_t* reg = &GPIO_TABLE[static_cast<uint8_t>(key) / 16]->PUPDR;
uint32_t offset = 2 * static_cast<uint8_t>(key) % 16;
return {reg,offset};
}
static inline SHAL_GPIO_Alternate_Function_Register getGPIOAlternateFunctionRegister(const GPIO_Key key){
uint32_t pinNumber = static_cast<uint8_t>(key); //Number of pin (We need 0-7 to be AFR 1 and 8-15 to be AFR 2
uint32_t afrIndex = pinNumber < 8 ? 0 : 1;
volatile uint32_t* reg = &GPIO_TABLE[static_cast<uint8_t>(key) / 16]->AFR[afrIndex];
uint32_t offset = (pinNumber % 8) * 4; //Increment in groups of four
return {reg,offset};
}
static inline SHAL_GPIO_Output_Speed_Register getGPIOOutputSpeedRegister(const GPIO_Key key){
volatile uint32_t* reg = &GPIO_TABLE[static_cast<uint8_t>(key) / 16]->OSPEEDR;
uint32_t offset = 2 * static_cast<uint8_t>(key) % 16;
return {reg,offset};
}
static inline SHAL_GPIO_Output_Type_Register getGPIOOutputTypeRegister(const GPIO_Key key){
volatile uint32_t* reg = &GPIO_TABLE[static_cast<uint8_t>(key) / 16]->OTYPER;
uint32_t offset = static_cast<uint8_t>(key) % 16;
return {reg,offset};
}
static inline SHAL_GPIO_Output_Data_Register getGPIOOutputDataRegister(const GPIO_Key key){
volatile uint32_t* reg = &GPIO_TABLE[static_cast<uint8_t>(key) / 16]->ODR;
uint32_t offset = static_cast<uint8_t>(key) % 16;
return {reg,offset};
}
constexpr SHAL_GPIO_Port_Info getGPIOPortInfo(GPIO_Key key){

View File

@@ -32,7 +32,7 @@ public:
void setAlternateFunction(GPIO_Alternate_Function AF) volatile;
void setPinType(PinType type) volatile;
void setOutputType(PinType type) volatile;
void setOutputSpeed(OutputSpeed speed) volatile;

View File

@@ -15,14 +15,39 @@ struct SHAL_GPIO_EXTI_Register{
IRQn_Type IRQN; //IRQ number for enabling lines
};
struct SHAL_GPIO_Peripheral {
GPIO_TypeDef * reg;
unsigned long global_offset;
struct SHAL_GPIO_RCC_Enable_Register{
volatile uint32_t* reg;
uint32_t offset;
};
struct SHAL_Peripheral_Register {
struct SHAL_GPIO_Mode_Register {
volatile uint32_t* reg;
unsigned long offset;
uint32_t offset;
};
struct SHAL_GPIO_Pullup_Pulldown_Register {
volatile uint32_t* reg;
uint32_t offset;
};
struct SHAL_GPIO_Alternate_Function_Register {
volatile uint32_t* reg;
uint32_t offset;
};
struct SHAL_GPIO_Output_Speed_Register{
volatile uint32_t* reg;
uint32_t offset;
};
struct SHAL_GPIO_Output_Type_Register {
volatile uint32_t* reg;
uint32_t offset;
};
struct SHAL_GPIO_Output_Data_Register {
volatile uint32_t* reg;
uint32_t offset;
};
struct SHAL_GPIO_Port_Info{

View File

@@ -20,46 +20,38 @@ SHAL_GPIO::SHAL_GPIO(GPIO_Key key) : m_GPIO_KEY(key) {
}
void SHAL_GPIO::setLow() {
auto gpioPeripheral = getGPIORegister(m_GPIO_KEY);
gpioPeripheral.reg->ODR &= ~(1 << gpioPeripheral.global_offset);
auto outputDataReg = getGPIOOutputDataRegister(m_GPIO_KEY);
SHAL_set_bits(outputDataReg.reg,1,0,outputDataReg.offset);
}
void SHAL_GPIO::setHigh() {
auto gpioPeripheral = getGPIORegister(m_GPIO_KEY);
gpioPeripheral.reg->ODR |= (1 << gpioPeripheral.global_offset);
auto outputDataReg = getGPIOOutputDataRegister(m_GPIO_KEY);
SHAL_set_bits(outputDataReg.reg,1,1,outputDataReg.offset);
}
void SHAL_GPIO::toggle() volatile {
SHAL_GPIO_Peripheral gpioPeripheral = getGPIORegister(m_GPIO_KEY);
gpioPeripheral.reg->ODR ^= (1 << gpioPeripheral.global_offset);
auto outputDataReg = getGPIOOutputDataRegister(m_GPIO_KEY);
SHAL_flip_bits(outputDataReg.reg,1,outputDataReg.offset);
}
void SHAL_GPIO::setPinType(PinType type) volatile {
SHAL_GPIO_Peripheral gpioPeripheral = getGPIORegister(m_GPIO_KEY);
gpioPeripheral.reg->OTYPER &= ~(1 << gpioPeripheral.global_offset);
gpioPeripheral.reg->OTYPER |= (static_cast<uint8_t>(type) << gpioPeripheral.global_offset);
void SHAL_GPIO::setOutputType(PinType type) volatile {
auto outputTypeReg = getGPIOOutputTypeRegister(m_GPIO_KEY);
SHAL_set_bits(outputTypeReg.reg,2,static_cast<uint8_t>(type),outputTypeReg.offset);
}
void SHAL_GPIO::setOutputSpeed(OutputSpeed speed) volatile {
SHAL_GPIO_Peripheral gpioPeripheral = getGPIORegister(m_GPIO_KEY);
gpioPeripheral.reg->OSPEEDR |= (static_cast<uint8_t>(speed) << (2 * gpioPeripheral.global_offset));
auto outputSpeedReg = getGPIOOutputSpeedRegister(m_GPIO_KEY);
SHAL_set_bits(outputSpeedReg.reg,2,static_cast<uint8_t>(speed),outputSpeedReg.offset);
}
void SHAL_GPIO::setInternalResistor(InternalResistorType type) volatile {
SHAL_GPIO_Peripheral gpioPeripheral = getGPIORegister(m_GPIO_KEY);
gpioPeripheral.reg->PUPDR &= ~(0x03 << (2 * gpioPeripheral.global_offset));
gpioPeripheral.reg->PUPDR |= (static_cast<uint8_t>(type) << (2 * gpioPeripheral.global_offset));
auto pupdreg = getGPIOPUPDRegister(m_GPIO_KEY);
SHAL_set_bits(pupdreg.reg,2,static_cast<uint8_t>(type),pupdreg.offset);
}
void SHAL_GPIO::setAlternateFunction(GPIO_Alternate_Function AF) volatile {
SHAL_GPIO_Peripheral gpioPeripheral = getGPIORegister(m_GPIO_KEY);
int afrIndex = gpioPeripheral.global_offset < 8 ? 0 : 1; //Get index of AFR
gpioPeripheral.reg->AFR[afrIndex] &= ~(0xF << (gpioPeripheral.global_offset * 4));
gpioPeripheral.reg->AFR[afrIndex] |= (static_cast<int>(AF) << (gpioPeripheral.global_offset * 4));
auto alternateFunctionReg = getGPIOAlternateFunctionRegister(m_GPIO_KEY);
SHAL_set_bits(alternateFunctionReg.reg,4,static_cast<uint8_t>(AF),alternateFunctionReg.offset);
}
void SHAL_GPIO::setPinMode(PinMode mode) volatile {

View File

@@ -27,8 +27,8 @@ void SHAL_I2C::init(I2C_Pair pair) volatile {
GET_GPIO(SDA_Key).setAlternateFunction(I2CPair.SDA_Mask);
//These may be abstracted further to support multiple I2C configurations
GET_GPIO(SCL_Key).setPinType(PinType::OPEN_DRAIN);
GET_GPIO(SDA_Key).setPinType(PinType::OPEN_DRAIN);
GET_GPIO(SCL_Key).setOutputType(PinType::OPEN_DRAIN);
GET_GPIO(SDA_Key).setOutputType(PinType::OPEN_DRAIN);
GET_GPIO(SCL_Key).setOutputSpeed(OutputSpeed::HIGH_SPEED);
GET_GPIO(SDA_Key).setOutputSpeed(OutputSpeed::HIGH_SPEED);

View File

@@ -18,6 +18,7 @@ void SHAL_init(){
ADCManager::getByIndex(i).init(adc_key);
}
SET_ANALOGREAD_ADC(SHAL_ADC1); //Default ADC1 for analogread calls
}

View File

@@ -43,5 +43,5 @@ DEFINE_MULTI_EXTI_IRQ(10,15);
//Link function to EXTI line
void registerEXTICallback(GPIO_Key key, EXTICallback callback){
EXTI_callbacks[getGPIORegister(key).global_offset] = callback;
EXTI_callbacks[getGPIOPinNumber(key)] = callback;
}

View File

@@ -6,7 +6,7 @@
#include "SHAL_GPIO.h"
#include "SHAL_UART.h"
#include <cstdio>
//Can hard code registers on F0 because all F0 devices have only one ADC, and use only one clock
SHAL_Result SHAL_ADC::init(ADC_Key key) {
m_ADCKey = key;
@@ -16,11 +16,6 @@ SHAL_Result SHAL_ADC::init(ADC_Key key) {
return SHAL_Result::ERROR;
}
SHAL_UART2.sendString("Init called\r\n");
PIN(B4).toggle();
SHAL_delay_ms(100);
PIN(B4).toggle();
SHAL_ADC_RCC_Enable_Reg clock_reg = getADCRCCEnableRegister(m_ADCKey); //Clock enable
SHAL_apply_bitmask(clock_reg.reg,clock_reg.mask);
@@ -115,10 +110,6 @@ SHAL_Result SHAL_ADC::multiConvertSingle(SHAL_ADC_Channel* channels, const int n
SHAL_set_bits(sampleTimeReg.reg,3,static_cast<uint8_t>(time),sampleTimeReg.channel_offset); //Set sample time register TODO un-hardcode bit width?
addADCChannelToSequence(channel,i); //Use index 0 to convert channel
if(enable() != SHAL_Result::OKAY){
return SHAL_Result::ERROR;
}
}
startConversion(); //Start ADC conversion
@@ -293,9 +284,6 @@ SHAL_Result SHAL_ADC::addADCChannelToSequence(SHAL_ADC_Channel channel, uint32_t
return SHAL_Result::OKAY;
}
SHAL_ADC &ADCManager::get(ADC_Key key) {
return m_ADCs[static_cast<uint8_t>(key)];
}

View File

@@ -2,6 +2,7 @@
// Created by Luca on 8/30/2025.
//
#include <cstdio>
#include "SHAL_GPIO.h"
#include "SHAL_EXTI_CALLBACK.h"
@@ -20,65 +21,59 @@ SHAL_GPIO::SHAL_GPIO(GPIO_Key key) : m_GPIO_KEY(key) {
}
void SHAL_GPIO::setLow() {
auto gpioPeripheral = getGPIORegister(m_GPIO_KEY);
gpioPeripheral.reg->ODR &= ~(1 << gpioPeripheral.global_offset);
auto outputDataReg = getGPIOOutputDataRegister(m_GPIO_KEY);
SHAL_set_bits(outputDataReg.reg,1,0,outputDataReg.offset);
}
void SHAL_GPIO::setHigh() {
auto gpioPeripheral = getGPIORegister(m_GPIO_KEY);
gpioPeripheral.reg->ODR |= (1 << gpioPeripheral.global_offset);
auto outputDataReg = getGPIOOutputDataRegister(m_GPIO_KEY);
SHAL_set_bits(outputDataReg.reg,1,1,outputDataReg.offset);
}
void SHAL_GPIO::toggle() volatile {
SHAL_GPIO_Peripheral gpioPeripheral = getGPIORegister(m_GPIO_KEY);
gpioPeripheral.reg->ODR ^= (1 << gpioPeripheral.global_offset);
auto outputDataReg = getGPIOOutputDataRegister(m_GPIO_KEY);
SHAL_flip_bits(outputDataReg.reg,1,outputDataReg.offset);
}
void SHAL_GPIO::setOutputType(PinType type) volatile {
auto outputTypeReg = getGPIOOutputTypeRegister(m_GPIO_KEY);
SHAL_set_bits(outputTypeReg.reg,2,static_cast<uint8_t>(type),outputTypeReg.offset);
}
void SHAL_GPIO::setOutputSpeed(OutputSpeed speed) volatile {
auto outputSpeedReg = getGPIOOutputSpeedRegister(m_GPIO_KEY);
SHAL_set_bits(outputSpeedReg.reg,2,static_cast<uint8_t>(speed),outputSpeedReg.offset);
}
void SHAL_GPIO::setInternalResistor(InternalResistorType type) volatile {
auto pupdreg = getGPIOPUPDRegister(m_GPIO_KEY);
SHAL_set_bits(pupdreg.reg,2,static_cast<uint8_t>(type),pupdreg.offset);
}
void SHAL_GPIO::setAlternateFunction(GPIO_Alternate_Function AF) volatile {
auto alternateFunctionReg = getGPIOAlternateFunctionRegister(m_GPIO_KEY);
SHAL_set_bits(alternateFunctionReg.reg,4,static_cast<uint8_t>(AF),alternateFunctionReg.offset);
}
SHAL_Result SHAL_GPIO::setPinMode(PinMode mode) volatile {
SHAL_GPIO_Peripheral gpioPeripheral = getGPIORegister(m_GPIO_KEY);
auto pinModeReg = getGPIOModeRegister(m_GPIO_KEY);
gpioPeripheral.reg->MODER &= ~(0x03 << (2 * gpioPeripheral.global_offset));
gpioPeripheral.reg->MODER |= (static_cast<uint8_t>(mode) << (2 * gpioPeripheral.global_offset));
if(mode == PinMode::ANALOG_MODE && getGPIOPortInfo(m_GPIO_KEY).ADCChannel != SHAL_ADC_Channel::NO_ADC_MAPPING){
SHAL_UART2.sendString("Error: GPIO pin has no valid ADC mapping\r\n");
if(mode == PinMode::ANALOG_MODE && getGPIOPortInfo(m_GPIO_KEY).ADCChannel == SHAL_ADC_Channel::NO_ADC_MAPPING){
char buff[100];
sprintf(buff, "Error: GPIO pin %d has no valid ADC mapping\r\n", static_cast<uint8_t>(m_GPIO_KEY));
SHAL_UART2.sendString(buff);
return SHAL_Result::ERROR;
}
SHAL_print_register(pinModeReg.reg);
SHAL_set_bits(pinModeReg.reg,2,static_cast<uint8_t>(mode),pinModeReg.offset); //Set mode
return SHAL_Result::OKAY;
}
void SHAL_GPIO::setPinType(PinType type) volatile {
SHAL_GPIO_Peripheral gpioPeripheral = getGPIORegister(m_GPIO_KEY);
gpioPeripheral.reg->OTYPER &= ~(1 << gpioPeripheral.global_offset);
gpioPeripheral.reg->OTYPER |= (static_cast<uint8_t>(type) << gpioPeripheral.global_offset);
}
void SHAL_GPIO::setOutputSpeed(OutputSpeed speed) volatile {
SHAL_GPIO_Peripheral gpioPeripheral = getGPIORegister(m_GPIO_KEY);
gpioPeripheral.reg->OSPEEDR |= (static_cast<uint8_t>(speed) << (2 * gpioPeripheral.global_offset));
}
void SHAL_GPIO::setInternalResistor(InternalResistorType type) volatile {
SHAL_GPIO_Peripheral gpioPeripheral = getGPIORegister(m_GPIO_KEY);
gpioPeripheral.reg->PUPDR &= ~(0x03 << (2 * gpioPeripheral.global_offset));
gpioPeripheral.reg->PUPDR |= (static_cast<uint8_t>(type) << (2 * gpioPeripheral.global_offset));
}
void SHAL_GPIO::setAlternateFunction(GPIO_Alternate_Function AF) volatile {
SHAL_GPIO_Peripheral gpioPeripheral = getGPIORegister(m_GPIO_KEY);
int afrIndex = gpioPeripheral.global_offset < 8 ? 0 : 1; //Get index of AFR
gpioPeripheral.reg->AFR[afrIndex] &= ~(0xF << (gpioPeripheral.global_offset * 4));
gpioPeripheral.reg->AFR[afrIndex] |= (static_cast<int>(AF) << (gpioPeripheral.global_offset * 4));
}
void SHAL_GPIO::useAsExternalInterrupt(TriggerMode mode, EXTICallback callback) {
uint32_t gpioPin = getGPIORegister(m_GPIO_KEY).global_offset; //Use existing structs to get offset
uint32_t gpioPin = getGPIOPinNumber(m_GPIO_KEY);
setPinMode(PinMode::INPUT_MODE); //Explicitly set mode to input
@@ -118,7 +113,7 @@ uint16_t SHAL_GPIO::analogRead(SHAL_ADC_SampleTime sampleTime) {
SHAL_GPIO& GPIOManager::get(GPIO_Key key) {
unsigned int gpioPort = getGPIOPortNumber(key);
unsigned long gpioPin = getGPIORegister(key).global_offset; //Use existing structs to get offset
uint8_t gpioPin = getGPIOPinNumber(key);
if (m_gpios[gpioPort][gpioPin].m_GPIO_KEY == GPIO_Key::INVALID){
m_gpios[gpioPort][gpioPin] = SHAL_GPIO(key);

View File

@@ -27,8 +27,8 @@ void SHAL_I2C::init(I2C_Pair pair) volatile {
GET_GPIO(SDA_Key).setAlternateFunction(I2CPair.SDA_Mask);
//These may be abstracted further to support multiple I2C configurations
GET_GPIO(SCL_Key).setPinType(PinType::OPEN_DRAIN);
GET_GPIO(SDA_Key).setPinType(PinType::OPEN_DRAIN);
GET_GPIO(SCL_Key).setOutputType(PinType::OPEN_DRAIN);
GET_GPIO(SDA_Key).setOutputType(PinType::OPEN_DRAIN);
GET_GPIO(SCL_Key).setOutputSpeed(OutputSpeed::HIGH_SPEED);
GET_GPIO(SDA_Key).setOutputSpeed(OutputSpeed::HIGH_SPEED);

View File

@@ -66,7 +66,7 @@ void SHAL_UART::sendChar(char c) volatile {
auto ISR_non_fifo = getUARTISRFifoDisabled(m_key);
if(!SHAL_WAIT_FOR_CONDITION_MS((*ISR_non_fifo.reg & ISR_non_fifo.transmit_data_register_empty_mask) != 0, 500)){
PIN(B3).toggle();
PIN(B3).setHigh();
return;
}

View File

@@ -1,30 +1,57 @@
#include <cstdio>
#include "SHAL.h"
void timer2callback(){
uint16_t val = PIN(A5).analogRead(SHAL_ADC_SampleTime::C4);
GPIO_Key gpios[6] = {
GPIO_Key::A0,
GPIO_Key::A1,
GPIO_Key::A4,
GPIO_Key::A5,
GPIO_Key::A6,
GPIO_Key::A7,
};
if(val <= 600){
PIN(B3).setHigh();
}
else{
PIN(B3).setLow();
void timer2callback(){
uint16_t val[6];
for(int i = 0; i < 6; i++){
val[i] = GPIOManager::get(gpios[i]).analogRead(SHAL_ADC_SampleTime::C8);
SHAL_delay_ms(30);
}
char buff[64];
sprintf(buff, "%d, %d, %d, %d, %d, %d\r\n", val[0],val[1],val[2],val[3],val[4],val[5]);
SHAL_UART2.sendString(buff);
}
int main() {
SHAL_init();
PIN(B3).setPinMode(PinMode::OUTPUT_MODE);
PIN(A5).setPinMode(PinMode::ANALOG_MODE);
SHAL_UART2.init(UART_Pair_Key::Tx2A2_Rx2A3);
SHAL_UART2.begin(115200);
SHAL_TIM2.init(4000000,50);
SHAL_UART2.sendString("Begin\r\n");
PIN(A0).setPinMode(PinMode::ANALOG_MODE);
PIN(A1).setPinMode(PinMode::ANALOG_MODE);
PIN(A4).setPinMode(PinMode::ANALOG_MODE);
PIN(A5).setPinMode(PinMode::ANALOG_MODE);
PIN(A6).setPinMode(PinMode::ANALOG_MODE);
PIN(A7).setPinMode(PinMode::ANALOG_MODE);
SHAL_UART2.sendString("Hello\r\n");
SHAL_TIM2.init(4000000,400);
SHAL_TIM2.setCallbackFunc(timer2callback);
SHAL_TIM2.enableInterrupt();
SHAL_TIM2.start();
while (true) {
SHAL_UART2.sendString("Hello\r\n");
while (true) {
}
}