Issue: cannot read core
This commit is contained in:
@@ -10,8 +10,8 @@ set(CPU_PARAMETERS
|
||||
-mcpu=cortex-m0
|
||||
-mthumb)
|
||||
|
||||
set(STARTUP_SCRIPT MX/L432KC/startup_stm32l432kcux.s)
|
||||
set(MCU_LINKER_SCRIPT MX/L432KC/STM32L432KCUX_FLASH.ld)
|
||||
set(STARTUP_SCRIPT ${CMAKE_CURRENT_SOURCE_DIR}/MX/L432KC/startup_stm32l432kcux.s)
|
||||
set(MCU_LINKER_SCRIPT ${CMAKE_CURRENT_SOURCE_DIR}/MX/L432KC/STM32L432KCUX_FLASH.ld)
|
||||
|
||||
set(EXECUTABLE ${CMAKE_PROJECT_NAME})
|
||||
enable_language(C CXX ASM)
|
||||
@@ -73,6 +73,8 @@ target_compile_options(${EXECUTABLE} PRIVATE
|
||||
-Wextra
|
||||
-Wpedantic
|
||||
-Wno-unused-parameter
|
||||
-Wno-switch
|
||||
-Wno-implicit-fallthrough
|
||||
$<$<COMPILE_LANGUAGE:CXX>:
|
||||
-Wno-volatile
|
||||
-Wsuggest-override>
|
||||
|
||||
@@ -71,24 +71,24 @@ bool SHAL_wait_for_condition_ms(Condition cond, uint32_t timeout_ms) {
|
||||
}
|
||||
|
||||
//Sets bits starting from offset as the LSB
|
||||
void SHAL_set_bits(volatile uint32_t* reg, uint32_t size, uint32_t bits, uint32_t offset){
|
||||
static inline void SHAL_set_bits(volatile uint32_t* reg, uint32_t size, uint32_t bits, uint32_t offset){
|
||||
uint32_t mask = (1 << (size)) - 1;
|
||||
*reg &= ~(mask << offset);
|
||||
*reg |= bits << offset;
|
||||
}
|
||||
|
||||
//Sets bits starting from offset as the LSB (for uint16_t)
|
||||
void SHAL_set_bits_16(volatile uint16_t* reg, uint32_t size, uint32_t bits, uint32_t offset){
|
||||
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;
|
||||
}
|
||||
|
||||
void SHAL_clear_bitmask(volatile uint32_t* reg, uint32_t mask){
|
||||
static inline void SHAL_clear_bitmask(volatile uint32_t* reg, uint32_t mask){
|
||||
*reg &= ~(mask);
|
||||
}
|
||||
|
||||
void SHAL_apply_bitmask(volatile uint32_t* reg, uint32_t mask){
|
||||
static inline void SHAL_apply_bitmask(volatile uint32_t* reg, uint32_t mask){
|
||||
SHAL_clear_bitmask(reg,mask);
|
||||
*reg |= mask;
|
||||
}
|
||||
|
||||
@@ -54,18 +54,18 @@ static volatile ADC_TypeDef* ADC_TABLE[1] = { //Lookup table for ADCs
|
||||
ADC1,
|
||||
};
|
||||
|
||||
SHAL_ADC_Common_Control_Reg getADCCommonControl() {
|
||||
static inline SHAL_ADC_Common_Control_Reg getADCCommonControl() {
|
||||
return {&ADC1_COMMON->CCR ,ADC_CCR_VREFEN,ADC_CCR_TSEN,ADC_CCR_VBATEN};
|
||||
}
|
||||
|
||||
SHAL_ADC_RCC_Enable_Reg getADCRCCEnableRegister(ADC_Key key){
|
||||
static inline SHAL_ADC_RCC_Enable_Reg getADCRCCEnableRegister(ADC_Key key){
|
||||
SHAL_ADC_RCC_Enable_Reg res = {nullptr, RCC_AHB2ENR_ADCEN};
|
||||
|
||||
res.reg = &(ADC_TABLE[static_cast<uint8_t>(key)]->ISR);
|
||||
return res;
|
||||
}
|
||||
|
||||
SHAL_ADC_Control_Reg getADCControlReg(ADC_Key key) {
|
||||
static inline SHAL_ADC_Control_Reg getADCControlReg(ADC_Key key) {
|
||||
|
||||
SHAL_ADC_Control_Reg res = {nullptr, ADC_CR_ADEN, ADC_CR_ADDIS, ADC_CR_ADCAL, ADC_CR_ADSTART};
|
||||
|
||||
@@ -73,7 +73,7 @@ SHAL_ADC_Control_Reg getADCControlReg(ADC_Key key) {
|
||||
return res;
|
||||
}
|
||||
|
||||
SHAL_ADC_Config_Reg getADCConfigReg(ADC_Key key) {
|
||||
static inline SHAL_ADC_Config_Reg getADCConfigReg(ADC_Key key) {
|
||||
|
||||
SHAL_ADC_Config_Reg res = {nullptr, ADC_CFGR_CONT, ADC_CFGR_RES_Pos, ADC_CFGR_ALIGN_Pos};
|
||||
|
||||
@@ -81,21 +81,21 @@ SHAL_ADC_Config_Reg getADCConfigReg(ADC_Key key) {
|
||||
return res;
|
||||
}
|
||||
|
||||
SHAL_ADC_ISR_Reg getADCISRReg(ADC_Key key){
|
||||
static inline SHAL_ADC_ISR_Reg getADCISRReg(ADC_Key key){
|
||||
SHAL_ADC_ISR_Reg res = {nullptr, ADC_ISR_EOC, ADC_ISR_EOS, ADC_ISR_ADRDY};
|
||||
|
||||
res.reg = &(ADC_TABLE[static_cast<uint8_t>(key)]->ISR);
|
||||
return res;
|
||||
}
|
||||
|
||||
SHAL_ADC_Data_Reg getADCDataReg(ADC_Key key){
|
||||
static inline SHAL_ADC_Data_Reg getADCDataReg(ADC_Key key){
|
||||
SHAL_ADC_Data_Reg res = {nullptr, 0xFFFF};
|
||||
|
||||
res.reg = &(ADC_TABLE[static_cast<uint8_t>(key)]->DR);
|
||||
return res;
|
||||
}
|
||||
|
||||
SHAL_ADC_Clock_Reg getADCClockSelectRegister(ADC_Clock_Source clockSource) {
|
||||
static inline SHAL_ADC_Clock_Reg getADCClockSelectRegister(ADC_Clock_Source clockSource) {
|
||||
SHAL_ADC_Clock_Reg res = {&RCC->CCIPR, RCC_CCIPR_ADCSEL_Msk, 1U << RCC_CCIPR_ADCSEL_Pos}; //Default to PLLSAI1
|
||||
|
||||
switch(clockSource){
|
||||
@@ -111,7 +111,7 @@ SHAL_ADC_Clock_Reg getADCClockSelectRegister(ADC_Clock_Source clockSource) {
|
||||
return res;
|
||||
}
|
||||
|
||||
SHAL_ADC_Channel_Sampling_Time_Reg getADCChannelSamplingTimeRegister(ADC_Key key, SHAL_ADC_Channel channel){
|
||||
static inline SHAL_ADC_Channel_Sampling_Time_Reg getADCChannelSamplingTimeRegister(ADC_Key key, SHAL_ADC_Channel channel){
|
||||
volatile ADC_TypeDef* ADCReg = ADC_TABLE[static_cast<uint8_t>(key)];
|
||||
|
||||
volatile uint32_t* SMPReg = nullptr;
|
||||
@@ -130,14 +130,14 @@ SHAL_ADC_Channel_Sampling_Time_Reg getADCChannelSamplingTimeRegister(ADC_Key key
|
||||
return {SMPReg, pos};
|
||||
}
|
||||
|
||||
SHAL_ADC_Sequence_Amount_Reg getADCSequenceAmountRegister(ADC_Key key){
|
||||
static inline SHAL_ADC_Sequence_Amount_Reg getADCSequenceAmountRegister(ADC_Key key){
|
||||
SHAL_ADC_Sequence_Amount_Reg res = {nullptr, ADC_SQR1_L_Pos};
|
||||
|
||||
res.reg = &(ADC_TABLE[static_cast<uint8_t>(key)]->SQR1);
|
||||
return res;
|
||||
}
|
||||
|
||||
SHAL_ADC_Sequence_Reg getADCSequenceRegisters(ADC_Key key){
|
||||
static inline SHAL_ADC_Sequence_Reg getADCSequenceRegisters(ADC_Key key){
|
||||
|
||||
volatile ADC_TypeDef* adc_reg = ADC_TABLE[static_cast<uint8_t>(key)];
|
||||
|
||||
|
||||
@@ -6,7 +6,23 @@
|
||||
#define SHMINGO_HAL_SHAL_EXTI_REG_L432KC_H
|
||||
|
||||
#include "SHAL_CORE.h"
|
||||
#include "SHAL_EXTI_TYPES.h"
|
||||
|
||||
#define EXTI_PENDING_REG(line) ((line) < 32 ? EXTI->PR1 : EXTI->PR2)
|
||||
|
||||
static inline SHAL_EXTI_Interrupt_Mask_Register getEXTIInterruptMaskRegister(uint32_t line){
|
||||
auto imr = line < 32 ? EXTI->IMR1 : EXTI->IMR2;
|
||||
return {&imr};
|
||||
}
|
||||
|
||||
static inline SHAL_EXTI_Rising_Trigger_Selection_Register getEXTIRisingTriggerSelectionRegister(uint32_t line){
|
||||
auto reg = line < 32 ? EXTI->RTSR1 : EXTI->RTSR2;
|
||||
return {®};
|
||||
}
|
||||
|
||||
static inline SHAL_EXTI_Falling_Trigger_Selection_Register getEXTIFallingTriggerSelectionRegister(uint32_t line){
|
||||
auto reg = line < 32 ? EXTI->FTSR1 : EXTI->FTSR2;
|
||||
return {®};
|
||||
}
|
||||
|
||||
#endif //SHMINGO_HAL_SHAL_EXTI_REG_L432KC_H
|
||||
|
||||
22
SHAL/Include/Peripheral/EXT/SHAL_EXTI_TYPES.h
Normal file
22
SHAL/Include/Peripheral/EXT/SHAL_EXTI_TYPES.h
Normal file
@@ -0,0 +1,22 @@
|
||||
//
|
||||
// Created by Luca on 10/17/2025.
|
||||
//
|
||||
|
||||
#ifndef SHMINGO_HAL_SHAL_EXTI_TYPES_H
|
||||
#define SHMINGO_HAL_SHAL_EXTI_TYPES_H
|
||||
|
||||
#include "SHAL_CORE.h"
|
||||
|
||||
struct SHAL_EXTI_Interrupt_Mask_Register {
|
||||
volatile uint32_t* reg;
|
||||
};
|
||||
|
||||
struct SHAL_EXTI_Rising_Trigger_Selection_Register {
|
||||
volatile uint32_t* reg;
|
||||
};
|
||||
|
||||
struct SHAL_EXTI_Falling_Trigger_Selection_Register {
|
||||
volatile uint32_t* reg;
|
||||
};
|
||||
|
||||
#endif //SHMINGO_HAL_SHAL_EXTI_TYPES_H
|
||||
@@ -8,6 +8,8 @@
|
||||
#include "SHAL_CORE.h"
|
||||
#include "SHAL_I2C_TYPES.h"
|
||||
|
||||
#define NUM_I2C_BUSES 3
|
||||
|
||||
enum class I2C_Pair : uint8_t{
|
||||
//I2C_1
|
||||
SCL1A9_SDA1A10, //AF4
|
||||
|
||||
@@ -13,11 +13,12 @@
|
||||
#include "SHAL_CORE.h"
|
||||
#include "SHAL_TIM_REG.h"
|
||||
|
||||
|
||||
#define DEFINE_TIMER_IRQ(key, irq_handler) \
|
||||
extern "C" void irq_handler(void) { \
|
||||
auto tim_status_reg = getTimerStatusRegister(key) \
|
||||
auto tim_status_reg = getTimerStatusRegister(key); \
|
||||
if (*tim_status_reg.reg & tim_status_reg.update_interrupt_flag_mask) { \
|
||||
SHAL_clear_mask(tim_status_reg.reg,tim_status_reg.update_interrupt_flag_mask) /* clear flag */ \
|
||||
SHAL_clear_bitmask(tim_status_reg.reg,tim_status_reg.update_interrupt_flag_mask); /* clear flag */ \
|
||||
auto cb = timer_callbacks[static_cast<int>(key)]; \
|
||||
if (cb) cb(); \
|
||||
}; \
|
||||
|
||||
@@ -11,7 +11,6 @@
|
||||
#include "SHAL_TIM.h"
|
||||
#include "SHAL_GPIO.h"
|
||||
#include "SHAL_UART.h"
|
||||
#include "SHAL_I2C.h"
|
||||
#include "SHAL_ADC.h"
|
||||
|
||||
|
||||
|
||||
@@ -9,7 +9,13 @@
|
||||
#elif defined(STM32L422xx)
|
||||
#elif defined(STM32L431xx)
|
||||
#elif defined(STM32L432xx)
|
||||
DEFINE_EXTI_IRQ()
|
||||
DEFINE_EXTI_IRQ(0);
|
||||
DEFINE_EXTI_IRQ(1);
|
||||
DEFINE_EXTI_IRQ(2);
|
||||
DEFINE_EXTI_IRQ(3);
|
||||
DEFINE_EXTI_IRQ(4);
|
||||
DEFINE_MULTI_EXTI_IRQ(5,9);
|
||||
DEFINE_MULTI_EXTI_IRQ(10,15);
|
||||
#elif defined(STM32L433xx)
|
||||
#elif defined(STM32L442xx)
|
||||
#elif defined(STM32L443xx)
|
||||
|
||||
@@ -74,32 +74,27 @@ void SHAL_GPIO::useAsExternalInterrupt(TriggerMode mode, EXTICallback callback)
|
||||
|
||||
setPinMode(PinMode::INPUT_MODE); //Explicitly set mode to input
|
||||
|
||||
RCC->APB2ENR |= RCC_APB2ENR_SYSCFGCOMPEN; //Enable EXT, TODO check if this is different across STM32 models
|
||||
RCC->APB2ENR |= RCC_APB2ENR_SYSCFGEN; //Enable EXT, TODO Add this to a global SHAL_GLOBAL_TYPES.h file
|
||||
NVIC_EnableIRQ(getGPIOEXTICR(m_GPIO_KEY).IRQN); //Enable IRQN for pin
|
||||
EXTI->IMR |= (1 << gpioPin); //Enable correct EXTI line
|
||||
|
||||
SHAL_EXTIO_Register EXTILineEnable = getGPIOEXTICR(m_GPIO_KEY);
|
||||
auto ext_imr = getEXTIInterruptMaskRegister(gpioPin);
|
||||
SHAL_set_bits(ext_imr.reg,1,1,gpioPin);
|
||||
|
||||
SHAL_GPIO_EXTI_Register EXTILineEnable = getGPIOEXTICR(m_GPIO_KEY);
|
||||
*EXTILineEnable.EXT_ICR |= EXTILineEnable.mask; //Set bits to enable correct port on correct line TODO Find way to clear bits before
|
||||
|
||||
uint32_t rising_mask = 0x00;
|
||||
uint32_t falling_mask = 0x00;
|
||||
|
||||
//Set rising and falling edge triggers based on pin offset (enabled EXTI line)
|
||||
switch(mode){
|
||||
case TriggerMode::RISING_EDGE:
|
||||
rising_mask = 1 << gpioPin;
|
||||
break;
|
||||
case TriggerMode::FALLING_EDGE:
|
||||
falling_mask = 1 << gpioPin;
|
||||
break;
|
||||
case TriggerMode::RISING_FALLING_EDGE:
|
||||
falling_mask = 1 << gpioPin;
|
||||
falling_mask = 1 << gpioPin;
|
||||
if(mode == TriggerMode::RISING_EDGE || mode == TriggerMode::RISING_FALLING_EDGE) {
|
||||
auto rising_trigger_selection_reg = getEXTIRisingTriggerSelectionRegister(gpioPin);
|
||||
SHAL_set_bits(rising_trigger_selection_reg.reg, 1, 1, gpioPin);
|
||||
}
|
||||
|
||||
//Set triggers
|
||||
EXTI->RTSR |= rising_mask;
|
||||
EXTI->FTSR |= falling_mask;
|
||||
if(mode == TriggerMode::FALLING_EDGE || mode == TriggerMode::RISING_FALLING_EDGE) {
|
||||
auto falling_trigger_selection_reg = getEXTIFallingTriggerSelectionRegister(gpioPin);
|
||||
SHAL_set_bits(falling_trigger_selection_reg.reg,1,1,gpioPin);
|
||||
}
|
||||
|
||||
//Set callback
|
||||
registerEXTICallback(m_GPIO_KEY,callback);
|
||||
|
||||
@@ -1,86 +1,9 @@
|
||||
#include "SHAL.h"
|
||||
#include "stm32f0xx.h"
|
||||
|
||||
#include <cstdlib>
|
||||
|
||||
void c3Interrupt(){
|
||||
SHAL_UART2.sendString("Begin\r\n");
|
||||
|
||||
uint8_t cmd[3] = {0xAC, 0x33, 0x00};
|
||||
SHAL_I2C1.masterWrite(0x38, cmd, 3);
|
||||
|
||||
SHAL_delay_ms(100);
|
||||
|
||||
uint8_t dht_buf[7] = {0};
|
||||
|
||||
//Read 7 bytes (status + 5 data + CRC)
|
||||
SHAL_I2C1.masterRead(0x38, dht_buf, 7);
|
||||
|
||||
//Parse humidity (20 bits)
|
||||
uint32_t rawHumidity = ((uint32_t)dht_buf[1] << 12) |
|
||||
((uint32_t)dht_buf[2] << 4) |
|
||||
((uint32_t)dht_buf[3] >> 4);
|
||||
|
||||
uint32_t rawTemp = (((uint32_t)dht_buf[3] & 0x0F) << 16) |
|
||||
((uint32_t)dht_buf[4] << 8) |
|
||||
((uint32_t)dht_buf[5]);
|
||||
|
||||
// Use 64-bit intermediate to avoid overflow
|
||||
uint32_t hum_hundredths = (uint32_t)(((uint64_t)rawHumidity * 10000ULL) >> 20);
|
||||
int32_t temp_hundredths = (int32_t)((((uint64_t)rawTemp * 20000ULL) >> 20) - 5000);
|
||||
|
||||
char out[80];
|
||||
sprintf(out, "rawH=0x%05lX rawT=0x%05lX\r\n",
|
||||
(unsigned long)rawHumidity, (unsigned long)rawTemp);
|
||||
SHAL_UART2.sendString(out);
|
||||
|
||||
// print as X.YY
|
||||
sprintf(out, "Temp: %ld.%02ld C, Hum: %ld.%02ld %%\r\n",
|
||||
(long)(temp_hundredths / 100), (long)(abs(temp_hundredths % 100)),
|
||||
(long)(hum_hundredths / 100), (long)(hum_hundredths % 100));
|
||||
SHAL_UART2.sendString(out);
|
||||
}
|
||||
|
||||
void tim2Handler(){
|
||||
PIN(A4).toggle();
|
||||
}
|
||||
|
||||
int main() {
|
||||
|
||||
SHAL_init();
|
||||
|
||||
//Setup UART2 (used by nucleo devices for USB comms)
|
||||
SHAL_UART2.init(UART_Pair_Key::Tx2A2_Rx2A3);
|
||||
SHAL_UART2.begin(115200);
|
||||
|
||||
SHAL_I2C1.init(I2C_Pair::SCL1B6_SDA1B7);
|
||||
SHAL_I2C1.setClockConfig(0x2000090E);
|
||||
|
||||
//Use pin C3 to trigger a function on external interrupt
|
||||
PIN(C3).useAsExternalInterrupt(TriggerMode::RISING_EDGE,c3Interrupt);
|
||||
|
||||
SHAL_TIM2.init(8000-1,1500-1);
|
||||
SHAL_TIM2.setCallbackFunc(tim2Handler);
|
||||
SHAL_TIM2.start();
|
||||
|
||||
PIN(A4).setPinMode(PinMode::OUTPUT_MODE);
|
||||
PIN(A5).setPinMode(PinMode::OUTPUT_MODE);
|
||||
|
||||
SHAL_delay_ms(3000); //Wait 100 ms from datasheet
|
||||
|
||||
uint8_t cmd = 0x71;
|
||||
uint8_t status = 0;
|
||||
|
||||
SHAL_I2C1.masterWriteRead(0x38, &cmd, 1, &status, 1);
|
||||
|
||||
char statusString[32];
|
||||
sprintf(statusString, "Status = 0x%02X\r\n", status);
|
||||
SHAL_UART2.sendString(statusString);
|
||||
|
||||
|
||||
SHAL_delay_ms(10);
|
||||
|
||||
c3Interrupt();
|
||||
//End setup
|
||||
|
||||
while (true) {
|
||||
|
||||
Reference in New Issue
Block a user