// Set up board clocks void SystemClock_Config(void) { // Set up external oscillator to 72 MHz RCC_OscInitTypeDef RCC_OscInitStruct; RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; RCC_OscInitStruct.HSEState = RCC_HSE_ON; RCC_OscInitStruct.LSEState = RCC_LSE_OFF; RCC_OscInitStruct.HSIState = RCC_HSI_ON; RCC_OscInitStruct.HSICalibrationValue = 16; RCC_OscInitStruct.HSEPredivValue = RCC_HSE_PREDIV_DIV1; RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; RCC_OscInitStruct.PLL.PLLMUL = RCC_PLL_MUL9; HAL_RCC_OscConfig(&RCC_OscInitStruct); // Set up periperal clocking RCC_ClkInitTypeDef RCC_ClkInitStruct; RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK |RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2; RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2; RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2); // Set up USB clock RCC_PeriphCLKInitTypeDef PeriphClkInit; PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USB; PeriphClkInit.UsbClockSelection = RCC_USBCLKSOURCE_PLL_DIV1_5; HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit); // Set up SysTTick to 1 ms // TODO: Do we really need this? SysTick is initialized multiple times in HAL HAL_SYSTICK_Config(HAL_RCC_GetHCLKFreq()/1000); HAL_SYSTICK_CLKSourceConfig(SYSTICK_CLKSOURCE_HCLK); // SysTick_IRQn interrupt configuration HAL_NVIC_SetPriority(SysTick_IRQn, 0, 0); } // Handle SysTick timer extern "C" void SysTick_Handler(void) { HAL_IncTick(); HAL_SYSTICK_IRQHandler(); } void InitBoard() { // Initialize board and HAL HAL_Init(); SystemClock_Config(); HAL_NVIC_SetPriorityGrouping(NVIC_PRIORITYGROUP_4); }
#define LED_PORT GPIOC const uint16_t LED_PIN = GPIO_PIN_13; // Class to encapsulate working with onboard LED(s) // // Note: this class initializes corresponding pins in the constructor. // May not be working properly if objects of this class are created as global variables class LEDDriver { public: LEDDriver() { // enable clock to GPIOC __HAL_RCC_GPIOC_CLK_ENABLE(); // Turn off the LED by default HAL_GPIO_WritePin(LED_PORT, LED_PIN, GPIO_PIN_SET); // Initialize PC13 pin GPIO_InitTypeDef ledPinInit; ledPinInit.Pin = LED_PIN; ledPinInit.Mode = GPIO_MODE_OUTPUT_PP; ledPinInit.Speed = GPIO_SPEED_FREQ_LOW; HAL_GPIO_Init(LED_PORT, &ledPinInit); } void turnOn() { HAL_GPIO_WritePin(LED_PORT, LED_PIN, GPIO_PIN_RESET); } void turnOff() { HAL_GPIO_WritePin(LED_PORT, LED_PIN, GPIO_PIN_SET); } void toggle() { HAL_GPIO_TogglePin(LED_PORT, LED_PIN); } };
int main(void) { InitBoard(); LEDDriver led; while(1) { HAL_Delay(500); led.toggle(); } }
// Pins assignment #define BUTTONS_PORT GPIOC const uint16_t SEL_BUTTON_PIN = GPIO_PIN_14; const uint16_t OK_BUTTON_PIN = GPIO_PIN_15; // Initialize buttons related stuff void initButtons() { // enable clock to GPIOC __HAL_RCC_GPIOC_CLK_ENABLE(); // Initialize button pins GPIO_InitTypeDef pinInit; pinInit.Mode = GPIO_MODE_INPUT; pinInit.Pull = GPIO_PULLDOWN; pinInit.Speed = GPIO_SPEED_FREQ_LOW; pinInit.Pin = SEL_BUTTON_PIN | OK_BUTTON_PIN; HAL_GPIO_Init(BUTTONS_PORT, &pinInit); … } // Reading button state (perform debounce first) inline bool getButtonState(uint16_t pin) { if(HAL_GPIO_ReadPin(BUTTONS_PORT, pin)) { // dobouncing vTaskDelay(DEBOUNCE_DURATION); if(HAL_GPIO_ReadPin(BUTTONS_PORT, pin)) return true; } return false; }
/* Definitions that map the FreeRTOS port interrupt handlers to their CMSIS standard names. */ #define vPortSVCHandler SVC_Handler #define xPortPendSVHandler PendSV_Handler #define xPortSysTickHandler HAL_SYSTICK_Callback
ld.exe: warning: changing start of section .text by 4 bytes
void vPortSVCHandler( void ) { __asm volatile ( " ldr r3, pxCurrentTCBConst2 \n" /* Restore the context. */ " ldr r1, [r3] \n" /* Use pxCurrentTCBConst to get the pxCurrentTCB address. */ " ldr r0, [r1] \n" /* The first item in pxCurrentTCB is the task top of stack. */ " ldmia r0!, {r4-r11} \n" /* Pop the registers that are not automatically saved on exception entry and the critical nesting count. */ " msr psp, r0 \n" /* Restore the task stack pointer. */ " isb \n" " mov r0, #0 \n" " msr basepri, r0 \n" " orr r14, #0xd \n" " bx r14 \n" " \n" " .align 4 \n" "pxCurrentTCBConst2: .word pxCurrentTCB \n" ); }
USBD_HandleTypeDef hUsbDeviceFS; void Reenumerate() { // Initialize PA12 pin GPIO_InitTypeDef pinInit; pinInit.Pin = GPIO_PIN_12; pinInit.Mode = GPIO_MODE_OUTPUT_PP; pinInit.Speed = GPIO_SPEED_FREQ_LOW; HAL_GPIO_Init(GPIOA, &pinInit); // Let host know to enumerate USB devices on the bus HAL_GPIO_WritePin(GPIOA, GPIO_PIN_12, GPIO_PIN_RESET); for(unsigned int i=0; i<512; i++) {}; // Restore pin mode pinInit.Mode = GPIO_MODE_INPUT; pinInit.Pull = GPIO_NOPULL; HAL_GPIO_Init(GPIOA, &pinInit); for(unsigned int i=0; i<512; i++) {}; } void initUSB() { Reenumerate(); USBD_Init(&hUsbDeviceFS, &FS_Desc, DEVICE_FS); USBD_RegisterClass(&hUsbDeviceFS, &USBD_CDC); USBD_CDC_RegisterInterface(&hUsbDeviceFS, &USBD_Interface_fops_FS); USBD_Start(&hUsbDeviceFS); }
static int8_t CDC_Control_FS (uint8_t cmd, uint8_t* pbuf, uint16_t length) { ... case CDC_SET_CONTROL_LINE_STATE: dtr_pin++; //DTR pin is enabled break; ... static int8_t CDC_Receive_FS (uint8_t* Buf, uint32_t *Len) { /* Four byte is the magic pack "1EAF" that puts the MCU into bootloader. */ if(*Len >= 4) { /** * Check if the incoming contains the string "1EAF". * If yes, check if the DTR has been set, to put the MCU into the bootloader mode. */ if(dtr_pin > 3) { if((Buf[0] == '1')&&(Buf[1] == 'E')&&(Buf[2] == 'A')&&(Buf[3] == 'F')) { HAL_NVIC_SystemReset(); } dtr_pin = 0; } } ... }
CDC_Transmit_FS((uint8_t*)"Ping\n", 5); // 5 is a strlen(“Ping”) + zero byte
GPIO_InitTypeDef GPIO_InitStruct; GPIO_InitStruct.Pin = GPIO_PIN_6|GPIO_PIN_7; GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; GPIO_InitStruct.Pull = GPIO_PULLUP; GPIO_InitStruct.Speed = GPIO_SPEED_HIGH; HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); __I2C1_CLK_ENABLE(); hi2c1.Instance = I2C1; hi2c1.Init.ClockSpeed = 400000; hi2c1.Init.DutyCycle = I2C_DUTYCYCLE_2; hi2c1.Init.OwnAddress1 = 0; hi2c1.Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT; hi2c1.Init.DualAddressMode = I2C_DUALADDRESS_DISABLED; hi2c1.Init.OwnAddress2 = 0; hi2c1.Init.GeneralCallMode = I2C_GENERALCALL_DISABLED; hi2c1.Init.NoStretchMode = I2C_NOSTRETCH_DISABLED; HAL_I2C_Init(&hi2c1);
Good (Stm32duino):
40005400: 0 0 0 1 - I2C_CR1: Peripheral enable
40005404: 0 0 1 24 - I2C_CR2: Error interrupt enabled, 36Mhz
40005408: 0 0 0 0 - I2C_OAR1: zero own address
4000540C: 0 0 0 0 - I2C_OAR2: Own address register
40005410: 0 0 0 AF - I2C_DR: data register
40005414: 0 0 0 0 - I2C_SR1: status register
40005418: 0 0 0 0 - I2C_SR2: status register
4000541C: 0 0 80 1E - I2C_CCR: 400kHz mode
40005420: 0 0 0 B - I2C_TRISE
Bad (STM32GENERIC):
40005400: 0 0 0 1 - I2C_CR1: Peripheral enable
40005404: 0 0 0 24 - I2C_CR2: 36Mhz
40005408: 0 0 40 0 - I2C_OAR1: !!! Not described bit in address register set
4000540C: 0 0 0 0 - I2C_OAR2: Own address register
40005410: 0 0 0 0 - I2C_DR: data register
40005414: 0 0 0 0 - I2C_SR1: status register
40005418: 0 0 0 2 - I2C_SR2: busy bit set
4000541C: 0 0 80 1E - I2C_CCR: 400kHz mode
40005420: 0 0 0 B - I2C_TRISE
void sendCommand(I2C_HandleTypeDef * handle, uint8_t cmd) { SerialUSB.print("Sending command "); SerialUSB.println(cmd, 16); uint8_t xBuffer[2]; xBuffer[0] = 0x00; xBuffer[1] = cmd; HAL_I2C_Master_Transmit(handle, I2C1_DEVICE_ADDRESS<<1, xBuffer, 2, 10); } ... sendCommand(handle, SSD1306_DISPLAYOFF); sendCommand(handle, SSD1306_SETDISPLAYCLOCKDIV); // 0xD5 sendCommand(handle, 0x80); // the suggested ratio 0x80 sendCommand(handle, SSD1306_SETMULTIPLEX); // 0xA8 sendCommand(handle, 0x3F); sendCommand(handle, SSD1306_SETDISPLAYOFFSET); // 0xD3 sendCommand(handle, 0x0); // no offset sendCommand(handle, SSD1306_SETSTARTLINE | 0x0); // line #0 sendCommand(handle, SSD1306_CHARGEPUMP); // 0x8D sendCommand(handle, 0x14); sendCommand(handle, SSD1306_MEMORYMODE); // 0x20 sendCommand(handle, 0x00); // 0x0 act like ks0108 sendCommand(handle, SSD1306_SEGREMAP | 0x1); sendCommand(handle, SSD1306_COMSCANDEC); sendCommand(handle, SSD1306_SETCOMPINS); // 0xDA sendCommand(handle, 0x12); sendCommand(handle, SSD1306_SETCONTRAST); // 0x81 sendCommand(handle, 0xCF); sendCommand(handle, SSD1306_SETPRECHARGE); // 0xd9 sendCommand(handle, 0xF1); sendCommand(handle, SSD1306_SETVCOMDETECT); // 0xDB sendCommand(handle, 0x40); sendCommand(handle, SSD1306_DISPLAYALLON_RESUME); // 0xA4 sendCommand(handle, SSD1306_DISPLAYON); // 0xA6 sendCommand(handle, SSD1306_NORMALDISPLAY); // 0xA6 sendCommand(handle, SSD1306_INVERTDISPLAY); sendCommand(handle, SSD1306_COLUMNADDR); sendCommand(handle, 0); // Column start address (0 = reset) sendCommand(handle, SSD1306_LCDWIDTH-1); // Column end address (127 = reset) sendCommand(handle, SSD1306_PAGEADDR); sendCommand(handle, 0); // Page start address (0 = reset) sendCommand(handle, 7); // Page end address uint8_t buf[17]; buf[0] = 0x40; for(uint8_t x=1; x<17; x++) buf[x] = 0xf0; // 4 black, 4 white lines for (uint16_t i=0; i<(SSD1306_LCDWIDTH*SSD1306_LCDHEIGHT/8); i++) { HAL_I2C_Master_Transmit(handle, I2C1_DEVICE_ADDRESS<<1, buf, 17, 10); }
uint8_t * pv = (uint8_t*)0x40005418; //I2C_SR2 register. Looking for BUSY flag SerialUSB.print("40005418 = "); SerialUSB.println(*pv, 16); // Prints 0 __HAL_RCC_I2C1_CLK_ENABLE(); SerialUSB.print("40005418 = "); SerialUSB.println(*pv, 16); // Prints 2
void stm32AfInit(const stm32_af_pin_list_type list[], int size, const void *instance, GPIO_TypeDef *port, uint32_t pin, uint32_t mode, uint32_t pull) { … GPIO_InitTypeDef GPIO_InitStruct; GPIO_InitStruct.Pin = pin; GPIO_InitStruct.Mode = mode; GPIO_InitStruct.Pull = pull; GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; HAL_GPIO_Init(port, &GPIO_InitStruct); … }
void stm32AfI2CInit(const I2C_TypeDef *instance, …) { stm32AfInit(chip_af_i2c_sda, …); stm32AfInit(chip_af_i2c_scl, …); }
/** * @brief Reset an I2C bus. * * Reset is accomplished by clocking out pulses until any hung slaves * release SDA and SCL, then generating a START condition, then a STOP * condition. * * @param dev I2C device */ void i2c_bus_reset(const i2c_dev *dev) { /* Release both lines */ i2c_master_release_bus(dev); /* * Make sure the bus is free by clocking it until any slaves release the * bus. */ while (!gpio_read_bit(sda_port(dev), dev->sda_pin)) { /* Wait for any clock stretching to finish */ while (!gpio_read_bit(scl_port(dev), dev->scl_pin)) ; delay_us(10); /* Pull low */ gpio_write_bit(scl_port(dev), dev->scl_pin, 0); delay_us(10); /* Release high again */ gpio_write_bit(scl_port(dev), dev->scl_pin, 1); delay_us(10); } /* Generate start then stop condition */ gpio_write_bit(sda_port(dev), dev->sda_pin, 0); delay_us(10); gpio_write_bit(scl_port(dev), dev->scl_pin, 0); delay_us(10); gpio_write_bit(scl_port(dev), dev->scl_pin, 1); delay_us(10); gpio_write_bit(sda_port(dev), dev->sda_pin, 1); }
for (uint16_t i = 0; i < 512; i++) { spiSend(src[i]);
// Size of UART input buffer const uint8_t gpsBufferSize = 128; // This class handles UART interface that receive chars from GPS and stores them to a buffer class GPS_UART { // UART hardware handle UART_HandleTypeDef uartHandle; // Receive ring buffer uint8_t rxBuffer[gpsBufferSize]; volatile uint8_t lastReadIndex = 0; volatile uint8_t lastReceivedIndex = 0; // GPS thread handle TaskHandle_t xGPSThread = NULL;
void init() { // Reset pointers (just in case someone calls init() multiple times) lastReadIndex = 0; lastReceivedIndex = 0; // Initialize GPS Thread handle xGPSThread = xTaskGetCurrentTaskHandle(); // Enable clocking of corresponding periperhal __HAL_RCC_GPIOA_CLK_ENABLE(); __HAL_RCC_USART1_CLK_ENABLE(); // Init pins in alternate function mode GPIO_InitTypeDef GPIO_InitStruct; GPIO_InitStruct.Pin = GPIO_PIN_9; //TX pin GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); GPIO_InitStruct.Pin = GPIO_PIN_10; //RX pin GPIO_InitStruct.Mode = GPIO_MODE_INPUT; GPIO_InitStruct.Pull = GPIO_NOPULL; HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); // Init uartHandle.Instance = USART1; uartHandle.Init.BaudRate = 9600; uartHandle.Init.WordLength = UART_WORDLENGTH_8B; uartHandle.Init.StopBits = UART_STOPBITS_1; uartHandle.Init.Parity = UART_PARITY_NONE; uartHandle.Init.Mode = UART_MODE_TX_RX; uartHandle.Init.HwFlowCtl = UART_HWCONTROL_NONE; uartHandle.Init.OverSampling = UART_OVERSAMPLING_16; HAL_UART_Init(&uartHandle); // We will be using UART interrupt to get data HAL_NVIC_SetPriority(USART1_IRQn, 6, 0); HAL_NVIC_EnableIRQ(USART1_IRQn); // We will be waiting for a single char right received right to the buffer HAL_UART_Receive_IT(&uartHandle, rxBuffer, 1); }
// Forward UART interrupt processing to HAL extern "C" void USART1_IRQHandler(void) { HAL_UART_IRQHandler(gpsUart.getUartHandle()); } // HAL calls this callback when it receives a char from UART. Forward it to the class extern "C" void HAL_UART_RxCpltCallback(UART_HandleTypeDef *uartHandle) { gpsUart.charReceivedCB(); }
// Char received, prepare for next one inline void charReceivedCB() { char lastReceivedChar = rxBuffer[lastReceivedIndex % gpsBufferSize]; lastReceivedIndex++; HAL_UART_Receive_IT(&uartHandle, rxBuffer + (lastReceivedIndex % gpsBufferSize), 1); // If a EOL symbol received, notify GPS thread that line is avaialble to read if(lastReceivedChar == '\n') vTaskNotifyGiveFromISR(xGPSThread, NULL); }
// Wait until whole line is received bool waitForString() { return ulTaskNotifyTake(pdTRUE, 10); }
void vGPSTask(void *pvParameters) { // GPS initialization must be done within GPS thread as thread handle is stored // and used later for synchronization purposes gpsUart.init(); for (;;) { // Wait until whole string is received if(!gpsUart.waitForString()) continue; // Read received string and parse GPS stream char by char while(gpsUart.available()) { int c = gpsUart.readChar(); //SerialUSB.write(c); gpsParser.handle(c); } if(gpsParser.available()) { GPSDataModel::instance().processNewGPSFix(gpsParser.read()); GPSDataModel::instance().processNewSatellitesData(gpsParser.satellites, gpsParser.sat_count); } vTaskDelay(10); } }
// Interface for hardware driver // The Adafruit_SSD1306 does not work directly with the hardware // All the communication requests are forwarded to the driver class ISSD1306Driver { public: virtual void begin() = 0; virtual void sendCommand(uint8_t cmd) = 0; virtual void sendData(uint8_t * data, size_t size) = 0; };
void DisplayDriver::sendCommand(uint8_t cmd) { HAL_I2C_Mem_Write(&handle, i2c_addr, 0x00, 1, &cmd, 1, 10); }
for (uint16_t i=0; i<size; i++) { // send a bunch of data in one xmission Wire.beginTransmission(_i2caddr); WIRE_WRITE(0x40); for (uint8_t x=0; x<16; x++) { WIRE_WRITE(data[i]); i++; } i--; Wire.endTransmission(); }
void DisplayDriver::sendData(uint8_t * data, size_t size) { HAL_I2C_Mem_Write(&handle, i2c_addr, 0x40, 1, data, size, 10); }
// DMA controller clock enable __HAL_RCC_DMA1_CLK_ENABLE(); // Initialize DMA hdma_tx.Instance = DMA1_Channel6; hdma_tx.Init.Direction = DMA_MEMORY_TO_PERIPH; hdma_tx.Init.PeriphInc = DMA_PINC_DISABLE; hdma_tx.Init.MemInc = DMA_MINC_ENABLE; hdma_tx.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE; hdma_tx.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE; hdma_tx.Init.Mode = DMA_NORMAL; hdma_tx.Init.Priority = DMA_PRIORITY_LOW; HAL_DMA_Init(&hdma_tx); // Associate the initialized DMA handle to the the I2C handle __HAL_LINKDMA(&handle, hdmatx, hdma_tx); /* DMA interrupt init */ /* DMA1_Channel6_IRQn interrupt configuration */ HAL_NVIC_SetPriority(DMA1_Channel6_IRQn, 7, 0); HAL_NVIC_EnableIRQ(DMA1_Channel6_IRQn);
extern "C" void DMA1_Channel6_IRQHandler(void) { HAL_DMA_IRQHandler(displayDriver.getDMAHandle()); } extern "C" void HAL_I2C_MemTxCpltCallback(I2C_HandleTypeDef *hi2c) { displayDriver.transferCompletedCB(); }
void DisplayDriver::sendData(uint8_t * data, size_t size) { // Start data transfer HAL_I2C_Mem_Write_DMA(&handle, i2c_addr, 0x40, 1, data, size); // Wait until transfer is completed ulTaskNotifyTake(pdTRUE, 100); } void DisplayDriver::transferCompletedCB() { // Resume display thread vTaskNotifyGiveFromISR(xDisplayThread, NULL); }
// This is custom implementation of SPI Driver class. SdFat library is // using this class to access SD card over SPI // // Main intention of this implementation is to drive data transfer // over DMA and synchronize with FreeRTOS capabilities. class SdFatSPIDriver : public SdSpiBaseDriver { // SPI module SPI_HandleTypeDef spiHandle; // GPS thread handle TaskHandle_t xSDThread = NULL; public: SdFatSPIDriver(); virtual void activate(); virtual void begin(uint8_t chipSelectPin); virtual void deactivate(); virtual uint8_t receive(); virtual uint8_t receive(uint8_t* buf, size_t n); virtual void send(uint8_t data); virtual void send(const uint8_t* buf, size_t n); virtual void select(); virtual void setSpiSettings(SPISettings spiSettings); virtual void unselect(); };
SdFatSPIDriver::SdFatSPIDriver() { } //void SdFatSPIDriver::activate(); void SdFatSPIDriver::begin(uint8_t chipSelectPin) { // Ignore passed CS pin - This driver works with predefined one (void)chipSelectPin; // Initialize GPS Thread handle xSDThread = xTaskGetCurrentTaskHandle(); // Enable clocking of corresponding periperhal __HAL_RCC_GPIOA_CLK_ENABLE(); __HAL_RCC_SPI1_CLK_ENABLE(); // Init pins GPIO_InitTypeDef GPIO_InitStruct; GPIO_InitStruct.Pin = GPIO_PIN_5|GPIO_PIN_7; //MOSI & SCK GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); GPIO_InitStruct.Pin = GPIO_PIN_6; //MISO GPIO_InitStruct.Mode = GPIO_MODE_INPUT; GPIO_InitStruct.Pull = GPIO_NOPULL; HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); GPIO_InitStruct.Pin = GPIO_PIN_4; //CS GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); // Set CS pin High by default HAL_GPIO_WritePin(GPIOA, GPIO_PIN_4, GPIO_PIN_SET); // Init SPI spiHandle.Instance = SPI1; spiHandle.Init.Mode = SPI_MODE_MASTER; spiHandle.Init.Direction = SPI_DIRECTION_2LINES; spiHandle.Init.DataSize = SPI_DATASIZE_8BIT; spiHandle.Init.CLKPolarity = SPI_POLARITY_LOW; spiHandle.Init.CLKPhase = SPI_PHASE_1EDGE; spiHandle.Init.NSS = SPI_NSS_SOFT; spiHandle.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_256; spiHandle.Init.FirstBit = SPI_FIRSTBIT_MSB; spiHandle.Init.TIMode = SPI_TIMODE_DISABLE; spiHandle.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE; spiHandle.Init.CRCPolynomial = 10; HAL_SPI_Init(&spiHandle); __HAL_SPI_ENABLE(&spiHandle); }
void SdFatSPIDriver::activate() { // No special activation needed } void SdFatSPIDriver::deactivate() { // No special deactivation needed } void SdFatSPIDriver::setSpiSettings(const SPISettings & spiSettings) { // Ignore settings - we are using same settings for all transfer }
void SdFatSPIDriver::select() { HAL_GPIO_WritePin(GPIOA, GPIO_PIN_4, GPIO_PIN_RESET); } void SdFatSPIDriver::unselect() { HAL_GPIO_WritePin(GPIOA, GPIO_PIN_4, GPIO_PIN_SET); }
uint8_t SdFatSPIDriver::receive() { uint8_t buf; uint8_t dummy = 0xff; HAL_SPI_TransmitReceive(&spiHandle, &dummy, &buf, 1, 10); return buf; } uint8_t SdFatSPIDriver::receive(uint8_t* buf, size_t n) { // TODO: Receive via DMA here memset(buf, 0xff, n); HAL_SPI_Receive(&spiHandle, buf, n, 10); return 0; } void SdFatSPIDriver::send(uint8_t data) { HAL_SPI_Transmit(&spiHandle, &data, 1, 10); } void SdFatSPIDriver::send(const uint8_t* buf, size_t n) { // TODO: Transmit over DMA here HAL_SPI_Transmit(&spiHandle, (uint8_t*)buf, n, 10); }
To sell something unnecessary, you must first buy something unnecessary (C) Prostokvashino
uint8_t sd_buf[512]; uint16_t i=0; uint32_t prev = HAL_GetTick(); while(true) { bulkFile.write(sd_buf, 512); bulkFile.write(sd_buf, 512); i++; uint32_t cur = HAL_GetTick(); if(cur-prev >= 1000) { prev = cur; usbDebugWrite("Saved %d kb\n", i); i = 0; } }
// DMA controller clock enable __HAL_RCC_DMA1_CLK_ENABLE(); // Rx DMA channel dmaHandleRx.Instance = DMA1_Channel2; dmaHandleRx.Init.Direction = DMA_PERIPH_TO_MEMORY; dmaHandleRx.Init.PeriphInc = DMA_PINC_DISABLE; dmaHandleRx.Init.MemInc = DMA_MINC_ENABLE; dmaHandleRx.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE; dmaHandleRx.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE; dmaHandleRx.Init.Mode = DMA_NORMAL; dmaHandleRx.Init.Priority = DMA_PRIORITY_LOW; HAL_DMA_Init(&dmaHandleRx); __HAL_LINKDMA(&spiHandle, hdmarx, dmaHandleRx); // Tx DMA channel dmaHandleTx.Instance = DMA1_Channel3; dmaHandleTx.Init.Direction = DMA_MEMORY_TO_PERIPH; dmaHandleTx.Init.PeriphInc = DMA_PINC_DISABLE; dmaHandleTx.Init.MemInc = DMA_MINC_ENABLE; dmaHandleTx.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE; dmaHandleTx.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE; dmaHandleTx.Init.Mode = DMA_NORMAL; dmaHandleTx.Init.Priority = DMA_PRIORITY_LOW; HAL_DMA_Init(&dmaHandleTx); __HAL_LINKDMA(&spiHandle, hdmatx, dmaHandleTx);
// Setup DMA interrupts HAL_NVIC_SetPriority(DMA1_Channel2_IRQn, 8, 0); HAL_NVIC_EnableIRQ(DMA1_Channel2_IRQn); HAL_NVIC_SetPriority(DMA1_Channel3_IRQn, 8, 0); HAL_NVIC_EnableIRQ(DMA1_Channel3_IRQn);
const size_t DMA_TRESHOLD = 16; uint8_t SdFatSPIDriver::receive(uint8_t* buf, size_t n) { memset(buf, 0xff, n); // Not using DMA for short transfers if(n <= DMA_TRESHOLD) { return HAL_SPI_TransmitReceive(&spiHandle, buf, buf, n, 10); } // Start data transfer HAL_SPI_TrsnsmitReceive_DMA(&spiHandle, buf, buf, n); // Wait until transfer is completed ulTaskNotifyTake(pdTRUE, 100); return 0; // Ok status } void SdFatSPIDriver::send(const uint8_t* buf, size_t n) { // Not using DMA for short transfers if(n <= DMA_TRESHOLD) { HAL_SPI_Transmit(&spiHandle, buf, n, 10); return; } // Start data transfer HAL_SPI_Transmit_DMA(&spiHandle, (uint8_t*)buf, n); // Wait until transfer is completed ulTaskNotifyTake(pdTRUE, 100); } void SdFatSPIDriver::dmaTransferCompletedCB() { // Resume SD thread vTaskNotifyGiveFromISR(xSDThread, NULL); }
extern SdFatSPIDriver spiDriver; extern "C" void DMA1_Channel2_IRQHandler(void) { HAL_DMA_IRQHandler(spiDriver.getHandle().hdmarx); } extern "C" void DMA1_Channel3_IRQHandler(void) { HAL_DMA_IRQHandler(spiDriver.getHandle().hdmatx); } extern "C" void HAL_SPI_TxCpltCallback(SPI_HandleTypeDef *hspi) { spiDriver.dmaTransferCompletedCB(); } extern "C" void HAL_SPI_RxCpltCallback(SPI_HandleTypeDef *hspi) { spiDriver.dmaTransferCompletedCB(); }
extern USBD_HandleTypeDef hUsbDeviceFS; void usbDebugWrite(uint8_t c) { usbDebugWrite(&c, 1); } void usbDebugWrite(const char * str) { usbDebugWrite((const uint8_t *)str, strlen(str)); } void usbDebugWrite(const uint8_t *buffer, size_t size) { // Ignore sending the message if USB is not connected if(hUsbDeviceFS.dev_state != USBD_STATE_CONFIGURED) return; // Transmit the message but no longer than timeout uint32_t timeout = HAL_GetTick() + 5; while(HAL_GetTick() < timeout) { if(CDC_Transmit_FS((uint8_t*)buffer, size) == USBD_OK) { return; } } }
#define USB_SERIAL_BUFFER_SIZE 256 uint8_t usbTxBuffer[USB_SERIAL_BUFFER_SIZE]; volatile uint16_t usbTxHead = 0; volatile uint16_t usbTxTail = 0; volatile uint16_t usbTransmitting = 0; uint16_t transmitContiguousBuffer() { uint16_t count = 0; // Transmit the contiguous data up to the end of the buffer if (usbTxHead > usbTxTail) { count = usbTxHead - usbTxTail; } else { count = sizeof(usbTxBuffer) - usbTxTail; } CDC_Transmit_FS(&usbTxBuffer[usbTxTail], count); return count; } void usbDebugWriteInternal(const char *buffer, size_t size, bool reverse = false) { // Ignore sending the message if USB is not connected if(hUsbDeviceFS.dev_state != USBD_STATE_CONFIGURED) return; // Transmit the message but no longer than timeout uint32_t timeout = HAL_GetTick() + 5; // Protect this function from multiple entrance MutexLocker locker(usbMutex); // Copy data to the buffer for(size_t i=0; i < size; i++) { if(reverse) --buffer; usbTxBuffer[usbTxHead] = *buffer; usbTxHead = (usbTxHead + 1) % sizeof(usbTxBuffer); if(!reverse) buffer++; // Wait until there is a room in the buffer, or drop on timeout while(usbTxHead == usbTxTail && HAL_GetTick() < timeout); if (usbTxHead == usbTxTail) break; } // If there is no transmittion happening if (usbTransmitting == 0) { usbTransmitting = transmitContiguousBuffer(); } } extern "C" void USBSerialTransferCompletedCB() { usbTxTail = (usbTxTail + usbTransmitting) % sizeof(usbTxBuffer); if (usbTxHead != usbTxTail) { usbTransmitting = transmitContiguousBuffer(); } else { usbTransmitting = 0; } }
static uint8_t USBD_CDC_DataIn (USBD_HandleTypeDef *pdev, uint8_t epnum) { USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*) pdev->pClassData; if(pdev->pClassData != NULL) { hcdc->TxState = 0; USBSerialTransferCompletedCB(); return USBD_OK; } else { return USBD_FAIL; } }
// sprintf implementation takes more than 10kb and adding heap to the project. I think this is // too much for the functionality I need // // Below is a homebrew printf-like dumping function which accepts: // - %d for digits // - %x for numbers as HEX // - %s for strings // - %% for percent symbol // // Implementation supports also value width as well as zero padding // Print the number to the buffer (in reverse order) // Returns number of printed symbols size_t PrintNum(unsigned int value, uint8_t radix, char * buf, uint8_t width, char padSymbol) { //TODO check negative here size_t len = 0; // Print the number do { char digit = value % radix; *(buf++) = digit < 10 ? '0' + digit : 'A' - 10 + digit; value /= radix; len++; } while (value > 0); // Add zero padding while(len < width) { *(buf++) = padSymbol; len++; } return len; } void usbDebugWrite(const char * fmt, ...) { va_list v; va_start(v, fmt); const char * chunkStart = fmt; size_t chunkSize = 0; char ch; do { // Get the next byte ch = *(fmt++); // Just copy the regular characters if(ch != '%') { chunkSize++; continue; } // We hit a special symbol. Dump string that we processed so far if(chunkSize) usbDebugWriteInternal(chunkStart, chunkSize); // Process special symbols // Check if zero padding requested char padSymbol = ' '; ch = *(fmt++); if(ch == '0') { padSymbol = '0'; ch = *(fmt++); } // Check if width specified uint8_t width = 0; if(ch > '0' && ch <= '9') { width = ch - '0'; ch = *(fmt++); } // check the format switch(ch) { case 'd': case 'u': { char buf[12]; size_t len = PrintNum(va_arg(v, int), 10, buf, width, padSymbol); usbDebugWriteInternal(buf + len, len, true); break; } case 'x': case 'X': { char buf[9]; size_t len = PrintNum(va_arg(v, int), 16, buf, width, padSymbol); usbDebugWriteInternal(buf + len, len, true); break; } case 's': { char * str = va_arg(v, char*); usbDebugWriteInternal(str, strlen(str)); break; } case '%': { usbDebugWriteInternal(fmt-1, 1); break; } default: // Otherwise store it like a regular symbol as a part of next chunk fmt--; break; } chunkStart = fmt; chunkSize=0; } while(ch != 0); if(chunkSize) usbDebugWriteInternal(chunkStart, chunkSize - 1); // Not including terminating NULL va_end(v); }
// Class to encapsulate working with onboard LED(s) // // Note: this class initializes corresponding pins in the constructor. // May not be working properly if objects of this class are created as global variables class LEDDriver { const uint32_t pin = LL_GPIO_PIN_13; public: LEDDriver() { //enable clock to the GPIOC peripheral __HAL_RCC_GPIOC_IS_CLK_ENABLED(); // Init PC 13 as output LL_GPIO_SetPinMode(GPIOC, pin, LL_GPIO_MODE_OUTPUT); LL_GPIO_SetPinOutputType(GPIOC, pin, LL_GPIO_OUTPUT_PUSHPULL); LL_GPIO_SetPinSpeed(GPIOC, pin, LL_GPIO_SPEED_FREQ_LOW); } void turnOn() { LL_GPIO_ResetOutputPin(GPIOC, pin); } void turnOff() { LL_GPIO_SetOutputPin(GPIOC, pin); } void toggle() { LL_GPIO_TogglePin(GPIOC, pin); } }; void vLEDThread(void *pvParameters) { LEDDriver led; // Just blink once in 2 seconds for (;;) { vTaskDelay(2000); led.turnOn(); vTaskDelay(100); led.turnOff(); } }
// Pins assignment const uint32_t SEL_BUTTON_PIN = LL_GPIO_PIN_14; const uint32_t OK_BUTTON_PIN = LL_GPIO_PIN_15; // Initialize buttons related stuff void initButtons() { //enable clock to the GPIOC peripheral __HAL_RCC_GPIOC_IS_CLK_ENABLED(); // Set up button pins LL_GPIO_SetPinMode(GPIOC, SEL_BUTTON_PIN, LL_GPIO_MODE_INPUT); LL_GPIO_SetPinPull(GPIOC, SEL_BUTTON_PIN, LL_GPIO_PULL_DOWN); LL_GPIO_SetPinMode(GPIOC, OK_BUTTON_PIN, LL_GPIO_MODE_INPUT); LL_GPIO_SetPinPull(GPIOC, OK_BUTTON_PIN, LL_GPIO_PULL_DOWN); } // Reading button state (perform debounce first) inline bool getButtonState(uint32_t pin) { if(LL_GPIO_IsInputPinSet(GPIOC, pin)) { // dobouncing vTaskDelay(DEBOUNCE_DURATION); if(LL_GPIO_IsInputPinSet(GPIOC, pin)) return true; } return false; }
// Init pins in alternate function mode LL_GPIO_SetPinMode(GPIOA, LL_GPIO_PIN_9, LL_GPIO_MODE_ALTERNATE); //TX pin LL_GPIO_SetPinSpeed(GPIOA, LL_GPIO_PIN_9, LL_GPIO_SPEED_FREQ_HIGH); LL_GPIO_SetPinOutputType(GPIOA, LL_GPIO_PIN_9, LL_GPIO_OUTPUT_PUSHPULL); LL_GPIO_SetPinMode(GPIOA, LL_GPIO_PIN_10, LL_GPIO_MODE_INPUT); //RX pin
// Prepare for initialization LL_USART_Disable(USART1); // Init LL_USART_SetBaudRate(USART1, HAL_RCC_GetPCLK2Freq(), 9600); LL_USART_SetDataWidth(USART1, LL_USART_DATAWIDTH_8B); LL_USART_SetStopBitsLength(USART1, LL_USART_STOPBITS_1); LL_USART_SetParity(USART1, LL_USART_PARITY_NONE); LL_USART_SetTransferDirection(USART1, LL_USART_DIRECTION_TX_RX); LL_USART_SetHWFlowCtrl(USART1, LL_USART_HWCONTROL_NONE); // We will be using UART interrupt to get data HAL_NVIC_SetPriority(USART1_IRQn, 6, 0); HAL_NVIC_EnableIRQ(USART1_IRQn); // Enable UART interrupt on byte reception LL_USART_EnableIT_RXNE(USART1); // Finally enable the peripheral LL_USART_Enable(USART1);
// Store received byte inline void charReceivedCB(uint8_t c) { rxBuffer[lastReceivedIndex % gpsBufferSize] = c; lastReceivedIndex++; // If a EOL symbol received, notify GPS thread that line is available to read if(c == '\n') vTaskNotifyGiveFromISR(xGPSThread, NULL); } extern "C" void USART1_IRQHandler(void) { uint8_t byte = LL_USART_ReceiveData8(USART1); gpsUart.charReceivedCB(byte); }
case USB_DESC_TYPE_CONFIGURATION: if(pdev->dev_speed == USBD_SPEED_HIGH ) { pbuf = (uint8_t *)pdev->pClass->GetHSConfigDescriptor(&len); pbuf[1] = USB_DESC_TYPE_CONFIGURATION; } else { pbuf = (uint8_t *)pdev->pClass->GetFSConfigDescriptor(&len); pbuf[1] = USB_DESC_TYPE_CONFIGURATION; } break;
__ALIGN_BEGIN uint8_t USBD_StrDesc[USBD_MAX_STR_DESC_SIZ] __ALIGN_END; void USBD_GetString(const char *desc, uint8_t *unicode, uint16_t *len) { uint8_t idx = 0; if (desc != NULL) { *len = USBD_GetLen(desc) * 2 + 2; unicode[idx++] = *len; unicode[idx++] = USB_DESC_TYPE_STRING; while (*desc != '\0') { unicode[idx++] = *desc++; unicode[idx++] = 0x00; } } }
Category | Subcategory | .text | .rodata | .data | .bss |
System | interrupt vector | 272 | |||
dummy ISR handlers | 178 | ||||
libc | 760 | ||||
float math | 4872 | ||||
sin/cos | 6672 | 536 | |||
main & etc | 86 | ||||
My Code | My Code | 7404 | 833 | four | 578 |
printf | 442 | ||||
Fonts | 3317 | ||||
NeoGPS | 4376 | 93 | 300 | ||
FreeRTOS | 4670 | four | 209 | ||
Adafruit GFX | 1768 | ||||
Adafruit SSD1306 | 1722 | 1024 | |||
SdFat | 5386 | 1144 | |||
USB Middleware | Core | 1740 | 333 | 2179 | |
CDC | 772 | ||||
Drivers | UART | 268 | 200 | ||
USB | 264 | 846 | |||
I2C | 316 | 164 | |||
SPI | 760 | 208 | |||
Buttons LL | 208 | ||||
LED LL | 48 | ||||
UART LL | 436 | 136 | |||
Arduino | gpio | 370 | 296 | sixteen | |
misc | 28 | 24 | |||
822 | |||||
HAL | USB LL | 4650 | |||
SysTick | 180 | ||||
NVIC | 200 | ||||
DMA | 666 | ||||
GPIO | 452 | ||||
I2C | 1560 | ||||
SPI | 2318 | ||||
RCC | 1564 | four | |||
UART | 974 | ||||
heap (not really used) | 1068 | ||||
FreeRTOS Heap | 10240 |
Source: https://habr.com/ru/post/357920/
All Articles