diff --git a/FLEXI_STM32F446RETX_BL_FLASH.ld b/FLEXI_STM32F446RETX_BL_FLASH.ld new file mode 100644 index 00000000..b95147ee --- /dev/null +++ b/FLEXI_STM32F446RETX_BL_FLASH.ld @@ -0,0 +1,178 @@ +/** + ****************************************************************************** + * @file LinkerScript.ld + * @author Auto-generated by STM32CubeIDE + * Abstract : Linker script for NUCLEO-F446RE Board embedding STM32F446RETx Device from stm32f4 series + * 512Kbytes FLASH + * 128Kbytes RAM + * + * Set heap size, stack size and stack location according + * to application requirements. + * + * Set memory bank area and size if external memory is used + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2020 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = ORIGIN(RAM) + LENGTH(RAM); /* end of "RAM" Ram type memory */ + +_Min_Heap_Size = 0x2000 ; /* required amount of heap */ +_Min_Stack_Size = 0x400 ; /* required amount of stack */ + +/* Memories definition */ +MEMORY +{ + RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K + BOOT_FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 64K + FLASH (rx) : ORIGIN = 0x8010000, LENGTH = 512K - 64K +} + +_FLASH_VectorTable = ORIGIN(FLASH); + +/* Sections */ +SECTIONS +{ + /* The startup code into "FLASH" Rom type memory */ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >FLASH + + /* The program code and other data into "FLASH" Rom type memory */ + .text : + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + } >FLASH + + /* Constant data into "FLASH" Rom type memory */ + .rodata : + { + . = ALIGN(4); + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + . = ALIGN(4); + } >FLASH + + .ARM.extab : { + . = ALIGN(4); + *(.ARM.extab* .gnu.linkonce.armextab.*) + . = ALIGN(4); + } >FLASH + + .ARM : { + . = ALIGN(4); + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + . = ALIGN(4); + } >FLASH + + .preinit_array : + { + . = ALIGN(4); + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + . = ALIGN(4); + } >FLASH + + .init_array : + { + . = ALIGN(4); + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + . = ALIGN(4); + } >FLASH + + .fini_array : + { + . = ALIGN(4); + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(SORT(.fini_array.*))) + KEEP (*(.fini_array*)) + PROVIDE_HIDDEN (__fini_array_end = .); + . = ALIGN(4); + } >FLASH + + /* Used by the startup to initialize data */ + _sidata = LOADADDR(.data); + + /* Initialized data sections into "RAM" Ram type memory */ + .data : + { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + + . = ALIGN(4); + _edata = .; /* define a global symbol at data end */ + + } >RAM AT> FLASH + + /* Uninitialized data section into "RAM" Ram type memory */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss section */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* User_heap_stack section, used to check that there is enough "RAM" Ram type memory left */ + ._user_heap_stack : + { + . = ALIGN(8); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(8); + } >RAM + + /* Remove information from the compiler libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} diff --git a/Inc/driver.h b/Inc/driver.h index 4db72400..8ce4b5ac 100644 --- a/Inc/driver.h +++ b/Inc/driver.h @@ -139,6 +139,8 @@ #include "st_morpho_dac_map.h" #elif defined(BOARD_MINI_BLACKPILL) #include "mini_blackpill_map.h" +#elif defined(BOARD_FLEXI_HAL) + #include "flexi_hal_map.h" #elif defined(BOARD_MY_MACHINE) #include "my_machine_map.h" #else // default board @@ -328,13 +330,21 @@ #define KEYPAD_TEST 0 #endif +#if IS_FLEXI_CNC +#if MODBUS_TEST + KEYPAD_TEST + MPG_TEST + TRINAMIC_TEST + BLUETOOTH_ENABLE > 2 +#error "Only one option that uses the serial port can be enabled!" +#endif +#else #if MODBUS_TEST + KEYPAD_TEST + MPG_TEST + TRINAMIC_TEST + BLUETOOTH_ENABLE > 1 #error "Only one option that uses the serial port can be enabled!" #endif +#endif #if MODBUS_TEST || KEYPAD_TEST || MPG_TEST || TRINAMIC_TEST || BLUETOOTH_ENABLE #if IS_NUCLEO_DEVKIT #define SERIAL2_MOD 1 +#elif IS_FLEXI_CNC +#define SERIAL2_MOD 3 #else #define SERIAL2_MOD 2 #endif @@ -369,7 +379,11 @@ #endif #if I2C_ENABLE && !defined(I2C_PORT) -#define I2C_PORT 2 // GPIOB, SCL_PIN = 10, SDA_PIN = 11 + #ifdef FMP_I2C + #define I2C_PORT 4 + #else + #define I2C_PORT 2 // GPIOB, SCL_PIN = 10, SDA_PIN = 11 + #endif #endif #if SPI_ENABLE && !defined(SPI_PORT) diff --git a/Inc/flexi_hal_map.h b/Inc/flexi_hal_map.h new file mode 100644 index 00000000..1cbd1857 --- /dev/null +++ b/Inc/flexi_hal_map.h @@ -0,0 +1,181 @@ +/* + generic_map.h - driver code for STM32F4xx ARM processors + + Part of grblHAL + + Copyright (c) 2020-2021 Terje Io + + Grbl is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + Grbl is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with Grbl. If not, see . +*/ + +#define IS_FLEXI_CNC 1 + +#if N_ABC_MOTORS > 2 +#error "Axis configuration is not supported!" +#endif + +#if TRINAMIC_ENABLE +#error "Trinamic plugin not supported!" +#endif + +#define BOARD_NAME "Flexi-HAL" +#ifdef I2C_ENABLE + #define FMP_I2C 1 +#endif + +//#define EEPROM_ENABLE 1 +#define STM32F446xx 1 +#define HAS_IOPORTS 1 +#define HAS_BOARD_INIT 1 + +#if MODBUS_ENABLE +#define MODBUS_SERIAL_PORT 2 +#endif + +#if MPG_MODE == 1 +#define MPG_MODE_PORT GPIOA +#define MPG_MODE_PIN 15 +#endif + +//********on first revision of this board Y step/dir was flipped. Use below config? + +// Define step pulse output pins. +#define X_STEP_PORT GPIOA +#define X_STEP_PIN 3 +#define Y_STEP_PORT GPIOC +#define Y_STEP_PIN 1 +#define Z_STEP_PORT GPIOB +#define Z_STEP_PIN 8 +#define STEP_OUTMODE GPIO_BITBAND +//#define STEP_PINMODE PINMODE_OD // Uncomment for open drain outputs + +// Define step direction output pins. +#define X_DIRECTION_PORT GPIOC +#define X_DIRECTION_PIN 2 +#define Y_DIRECTION_PORT GPIOC +#define Y_DIRECTION_PIN 0 +#define Z_DIRECTION_PORT GPIOC +#define Z_DIRECTION_PIN 15 +#define DIRECTION_OUTMODE GPIO_BITBAND +//#define DIRECTION_PINMODE PINMODE_OD // Uncomment for open drain outputs + +// Define stepper driver enable/disable output pin. +#define X_ENABLE_PORT GPIOA +#define X_ENABLE_PIN 14 +#define Y_ENABLE_PORT GPIOA +#define Y_ENABLE_PIN 14 +#define Z_ENABLE_PORT GPIOA +#define Z_ENABLE_PIN 13 +//#define STEPPERS_ENABLE_PORT GPIOA +//#define STEPPERS_ENABLE_PIN 14 +#define STEPPERS_ENABLE_OUTMODE GPIO_BITBAND + +// Define homing/hard limit switch input pins. +#define X_LIMIT_PORT GPIOA +#define X_LIMIT_PIN 5 +#define Y_LIMIT_PORT GPIOB +#define Y_LIMIT_PIN 9 +#define Z_LIMIT_PORT GPIOC +#define Z_LIMIT_PIN 13 +#define LIMIT_INMODE GPIO_BITBAND + +// Define ganged axis or A axis step pulse and step direction output pins. +#if N_ABC_MOTORS > 0 +#define M3_AVAILABLE +#define M3_STEP_PORT GPIOD +#define M3_STEP_PIN 2 +#define M3_DIRECTION_PORT GPIOC +#define M3_DIRECTION_PIN 12 +#define M3_LIMIT_PORT GPIOB +#define M3_LIMIT_PIN 6 +#define M3_ENABLE_PORT GPIOA +#define M3_ENABLE_PIN 14 +#endif + +// Define ganged axis or A axis step pulse and step direction output pins. +#if N_ABC_MOTORS == 2 +#define M4_AVAILABLE +#define M4_STEP_PORT GPIOB +#define M4_STEP_PIN 14 +#define M4_DIRECTION_PORT GPIOB +#define M4_DIRECTION_PIN 15 +#define M4_LIMIT_PORT GPIOC +#define M4_LIMIT_PIN 14 +#define M4_ENABLE_PORT GPIOA +#define M4_ENABLE_PIN 14 +#endif + +// Define spindle enable and spindle direction output pins. +#define SPINDLE_ENABLE_PORT GPIOB +#define SPINDLE_ENABLE_PIN 2 +#define SPINDLE_DIRECTION_PORT GPIOB +#define SPINDLE_DIRECTION_PIN 1 +#define SPINDLE_OUTMODE GPIO_BITBAND + +// Define spindle PWM output pin. +#define SPINDLE_PWM_PORT_BASE GPIOA_BASE +#define SPINDLE_PWM_PIN 8 + +// Define flood and mist coolant enable output pins. +#define COOLANT_FLOOD_PORT GPIOC +#define COOLANT_FLOOD_PIN 9 +#define COOLANT_MIST_PORT GPIOA +#define COOLANT_MIST_PIN 7 +#define COOLANT_OUTMODE GPIO_BITBAND + +#define AUXOUTPUT0_PORT GPIOB +#define AUXOUTPUT0_PIN 13 +#define AUXOUTPUT1_PORT GPIOB +#define AUXOUTPUT1_PIN 0 +#define AUXOUTPUT2_PORT GPIOA +#define AUXOUTPUT2_PIN 4 +#define AUXOUTPUT3_PORT GPIOA +#define AUXOUTPUT3_PIN 6 +#define AUXOUTPUT_OUTMODE GPIO_BITBAND + +#define AUXINPUT0_PORT GPIOA +#define AUXINPUT0_PIN 0 +#define AUXINPUT1_PORT GPIOA +#define AUXINPUT1_PIN 1 +#define AUXINPUT2_PORT GPIOA +#define AUXINPUT2_PIN 2 + + +// Define user-control controls (cycle start, reset, feed hold) input pins. +#define RESET_PORT GPIOB +#define RESET_PIN 12 +#define FEED_HOLD_PORT GPIOC +#define FEED_HOLD_PIN 8 +#define CYCLE_START_PORT GPIOC +#define CYCLE_START_PIN 11 +#if SAFETY_DOOR_ENABLE +#define SAFETY_DOOR_PORT GPIOC +#define SAFETY_DOOR_PIN 4 +#endif +#define CONTROL_INMODE GPIO_BITBAND + +// Define probe switch input pin. +#define PROBE_PORT GPIOB +#define PROBE_PIN 7 + +#if I2C_STROBE_ENABLE +#define I2C_STROBE_PORT GPIOB +#define I2C_STROBE_PIN 10 +#endif + +#if SDCARD_ENABLE +#define SD_CS_PORT GPIOA +#define SD_CS_PIN 3 +#define SPI_PORT 1 // GPIOA, SCK_PIN = 5, MISO_PIN = 6, MOSI_PIN = 7 +#endif diff --git a/Inc/my_machine.h b/Inc/my_machine.h index 4a476b79..9d8eb7d1 100644 --- a/Inc/my_machine.h +++ b/Inc/my_machine.h @@ -34,6 +34,7 @@ //#define BOARD_BTT_SKR_20 // F407 based 3D Printer board //#define BOARD_BTT_SKR_20_DAC // F407 based 3D Printer board, uses analog output (DAC) for spindle speed control //#define BOARD_FYSETC_S6 // F446 based 3D Printer board +#define BOARD_FLEXI_HAL // F446 CNC board //#define BOARD_MY_MACHINE // Add my_machine_map.h before enabling this! // WARNING: BOARD_BTT_SKR_20 may fry your Trinamic drivers due to bad hardware design. diff --git a/Src/flexi_hal.c b/Src/flexi_hal.c new file mode 100644 index 00000000..c24ed318 --- /dev/null +++ b/Src/flexi_hal.c @@ -0,0 +1,235 @@ +/* + flexi_hal.c - driver code for STM32F4xx ARM processors on Flexi-HAL board + + Part of grblHAL + + Copyright (c) 2020-2021 Terje Io + Modifications for Flexi-Hal Copyright (c) 2022 Expatria Technologies + + Grbl is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + Grbl is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with Grbl. If not, see . +*/ + +#include "driver.h" + +#if defined(BOARD_FLEXI_HAL) + +#include +#include + +#include "main.h" +#include "i2c.h" +#include "grbl/protocol.h" +#include "grbl/settings.h" + +static uint8_t keycode = 0; +static keycode_callback_ptr keypad_callback = NULL; +static bool pendant_tx_active = 0; + + #define I2C1_SCL_PIN 6 + #define I2C1_SDA_PIN 7 + +static FMPI2C_HandleTypeDef i2c_port = { + .Instance = FMPI2C1, + //.Init.Timing = 0xC0000E12, //100 KHz + //.Init.Timing = 0x0020081B, //1000 KHz + .Init.Timing =0x00401650, //400 KHz + .Init.OwnAddress1 = 0, + .Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT, + .Init.DualAddressMode = I2C_DUALADDRESS_DISABLE, + .Init.OwnAddress2 = 0, + .Init.OwnAddress2Masks = FMPI2C_OA2_NOMASK, + .Init.GeneralCallMode = I2C_GENERALCALL_DISABLE, + .Init.NoStretchMode = I2C_NOSTRETCH_DISABLE +}; + +void i2c_init (void) +{ + GPIO_InitTypeDef GPIO_InitStruct = { + .Pin = (1 << I2C1_SCL_PIN)|(1 << I2C1_SDA_PIN), + .Mode = GPIO_MODE_AF_OD, + .Pull = GPIO_PULLUP, + .Speed = GPIO_SPEED_FREQ_VERY_HIGH, + .Alternate = GPIO_AF4_FMPI2C1 + }; + HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); + + __HAL_RCC_FMPI2C1_CLK_ENABLE(); + HAL_FMPI2CEx_ConfigAnalogFilter(&i2c_port, FMPI2C_ANALOGFILTER_ENABLE); + + HAL_FMPI2C_Init(&i2c_port); + __HAL_FMPI2C_ENABLE(&i2c_port); + + /* FMPI2C1 interrupt Init */ + HAL_NVIC_SetPriority(FMPI2C1_EV_IRQn, 0, 0); + HAL_NVIC_EnableIRQ(FMPI2C1_EV_IRQn); + + static const periph_pin_t scl = { + .function = Output_SCK, + .group = PinGroup_I2C, + .port = GPIOC, + .pin = 6, + .mode = { .mask = PINMODE_OD } + }; + + static const periph_pin_t sda = { + .function = Bidirectional_SDA, + .group = PinGroup_I2C, + .port = GPIOC, + .pin = 7, + .mode = { .mask = PINMODE_OD } + }; + + + hal.periph_port.register_pin(&scl); + hal.periph_port.register_pin(&sda); +} + +void FMPI2C1_EV_IRQHandler(void) +{ + HAL_FMPI2C_EV_IRQHandler(&i2c_port); +} + +void FMPI2C1_ER_IRQHandler(void) +{ + HAL_FMPI2C_ER_IRQHandler(&i2c_port); +} + +void I2C_Send (uint32_t i2cAddr, uint8_t *buf, uint16_t bytes, bool block) +{ + //wait for bus to be ready + while (HAL_FMPI2C_GetState(&i2c_port) != HAL_FMPI2C_STATE_READY); + + HAL_FMPI2C_Master_Transmit_IT(&i2c_port, i2cAddr<<1, buf, bytes); + + if (block) + while (HAL_FMPI2C_GetState(&i2c_port) != HAL_FMPI2C_STATE_READY); +} + +nvs_transfer_result_t i2c_nvs_transfer (nvs_transfer_t *i2c, bool read) +{ + while (HAL_FMPI2C_GetState(&i2c_port) != HAL_FMPI2C_STATE_READY); + + HAL_StatusTypeDef ret; + + if(read) + ret = HAL_FMPI2C_Mem_Read(&i2c_port, i2c->address << 1, i2c->word_addr, i2c->word_addr_bytes, i2c->data, i2c->count, 100); + else { + ret = HAL_FMPI2C_Mem_Write(&i2c_port, i2c->address << 1, i2c->word_addr, i2c->word_addr_bytes, i2c->data, i2c->count, 100); +#if !EEPROM_IS_FRAM + hal.delay_ms(6, NULL); +#endif + } + i2c->data += i2c->count; + + return ret == HAL_OK ? NVS_TransferResult_OK : NVS_TransferResult_Failed; +} + +void I2C_PendantRead (uint32_t i2cAddr, uint8_t memaddress, uint8_t size, uint8_t * data, keycode_callback_ptr callback) +{ + + uint32_t ms = hal.get_elapsed_ticks(); //50 ms timeout + uint32_t timeout_ms = ms + 50; + + if(keypad_callback != NULL || pendant_tx_active) //we are in the middle of a read + return; + + keycode = 'r'; + keypad_callback = callback; + + while((HAL_FMPI2C_Mem_Read_IT(&i2c_port, i2cAddr << 1, memaddress, 1, data, size)) != HAL_OK){ + if (ms > timeout_ms){ + keypad_callback = NULL; + keycode = 0; + i2c_init(); + return; + } + hal.delay_ms(1, NULL); + ms = hal.get_elapsed_ticks(); + } +} + +void I2C_PendantWrite (uint32_t i2cAddr, uint8_t *buf, uint16_t bytes) +{ + + uint32_t ms = hal.get_elapsed_ticks(); //50 ms timeout + uint32_t timeout_ms = ms + 50; + + if(keypad_callback != NULL || pendant_tx_active) //we are in the middle of a read + return; + pendant_tx_active = 1; + + while((HAL_FMPI2C_Master_Transmit_IT(&i2c_port, i2cAddr<<1, buf, bytes) != HAL_OK)){ + if (ms > timeout_ms){ + pendant_tx_active = 0; + i2c_init(); + return; + } + hal.delay_ms(1, NULL); + ms = hal.get_elapsed_ticks(); + } +} + +void HAL_FMPI2C_MemRxCpltCallback(FMPI2C_HandleTypeDef *hi2c) +{ + if(keypad_callback && keycode != 0) { + keypad_callback(keycode); + keypad_callback = NULL; + } +} + +void HAL_FMPI2C_MasterRxCpltCallback(FMPI2C_HandleTypeDef *hi2c) +{ + + if(keypad_callback && keycode != 0) { + keypad_callback(keycode); + keypad_callback = NULL; + } +} + +void HAL_FMPI2C_MasterTxCpltCallback(FMPI2C_HandleTypeDef *hi2c) +{ + pendant_tx_active = 0; +} + +void I2C_GetKeycode (uint32_t i2cAddr, keycode_callback_ptr callback) +{ + keycode = 0; + keypad_callback = callback; + + HAL_FMPI2C_Master_Receive_IT(&i2c_port, i2cAddr << 1, &keycode, 1); +} + +// called from stream drivers while tx is blocking, returns false to terminate + +#if 0 +bool flexi_stream_tx_blocking (void) +{ + // TODO: Restructure st_prep_buffer() calls to be executed here during a long print. + + grbl.on_execute_realtime(state_get()); + + return !(sys.rt_exec_state & EXEC_RESET); +} +#endif + +void board_init (void) +{ +//put new stuff here. + + +} + +#endif + + diff --git a/Src/i2c.c b/Src/i2c.c index a495041b..8c27add4 100644 --- a/Src/i2c.c +++ b/Src/i2c.c @@ -24,6 +24,8 @@ #include "i2c.h" #include "grbl/hal.h" +#if !defined(BOARD_FLEXI_HAL) + #if KEYPAD_ENABLE == 1 #include "keypad/keypad.h" #endif @@ -253,3 +255,5 @@ TMC_spi_status_t tmc_spi_write (trinamic_motor_t driver, TMC_spi_datagram_t *reg #endif // TRINAMIC_ENABLE && TRINAMIC_I2C #endif // I2C_ENABLE + +#endif // Flexi_hal \ No newline at end of file diff --git a/platformio.ini b/platformio.ini index 6266f798..2811cc0d 100644 --- a/platformio.ini +++ b/platformio.ini @@ -257,4 +257,19 @@ lib_deps = ${common.lib_deps} lib_extra_dirs = ${common.lib_extra_dirs} # Alternatively, place the .pio/build//firmware.bin on the NODE_F4xxRE drive ; change MCU frequency -upload_protocol = dfu +upload_protocol = dfu + +[env:f446re_flexi_cnc] +board = genericSTM32F446RE +; change microcontroller +board_build.mcu = stm32f446ret6 +board_build.ldscript = FLEXI_STM32F446RETX_BL_FLASH.ld +build_flags = ${common.build_flags} + -D HSE_VALUE=25000000 + -D EEPROM_ENABLE=2 + -D HAS_BOOTLOADER=1 +lib_deps = ${common.lib_deps} + eeprom +lib_extra_dirs = ${common.lib_extra_dirs} +# Alternatively, place the .pio/build//firmware.bin on the NODE_F4xxRE drive +upload_protocol = stlink