Update HAL/STM32 platform to 8.0 (#18496)
This commit is contained in:
		
				
					committed by
					
						 Scott Lahteine
						Scott Lahteine
					
				
			
			
				
	
			
			
			
						parent
						
							5fcfecc56e
						
					
				
				
					commit
					784016a25e
				
			
							
								
								
									
										1
									
								
								.github/workflows/test-builds.yml
									
									
									
									
										vendored
									
									
								
							
							
						
						
									
										1
									
								
								.github/workflows/test-builds.yml
									
									
									
									
										vendored
									
									
								
							| @@ -70,6 +70,7 @@ jobs: | |||||||
|         - mks_robin_stm32 |         - mks_robin_stm32 | ||||||
|         - ARMED |         - ARMED | ||||||
|         - FYSETC_S6 |         - FYSETC_S6 | ||||||
|  |         - STM32F070CB_malyan | ||||||
|         - STM32F070RB_malyan |         - STM32F070RB_malyan | ||||||
|         - malyan_M300 |         - malyan_M300 | ||||||
|         - mks_robin_lite |         - mks_robin_lite | ||||||
|   | |||||||
| @@ -694,7 +694,7 @@ ifeq ($(HARDWARE_VARIANT), Teensy) | |||||||
|   LIB_CXXSRC += usb_api.cpp |   LIB_CXXSRC += usb_api.cpp | ||||||
|  |  | ||||||
| else ifeq ($(HARDWARE_VARIANT), archim) | else ifeq ($(HARDWARE_VARIANT), archim) | ||||||
|   CDEFS      += -DARDUINO_SAM_ARCHIM -DARDUINO_ARCH_SAM -D__SAM3X8E__ -DUSB_VID=0x27b1 -DUSB_PID=0x0001 -DUSBCON '-DUSB_MANUFACTURER="UltiMachine"' '-DUSB_PRODUCT="Archim"' |   CDEFS      += -DARDUINO_SAM_ARCHIM -DARDUINO_ARCH_SAM -D__SAM3X8E__ -DUSB_VID=0x27b1 -DUSB_PID=0x0001 -DUSBCON '-DUSB_MANUFACTURER="UltiMachine"' '-DUSB_PRODUCT_STRING="Archim"' | ||||||
|   LIB_CXXSRC += variant.cpp IPAddress.cpp Reset.cpp RingBuffer.cpp Stream.cpp UARTClass.cpp  USARTClass.cpp abi.cpp new.cpp watchdog.cpp CDC.cpp PluggableUSB.cpp USBCore.cpp |   LIB_CXXSRC += variant.cpp IPAddress.cpp Reset.cpp RingBuffer.cpp Stream.cpp UARTClass.cpp  USARTClass.cpp abi.cpp new.cpp watchdog.cpp CDC.cpp PluggableUSB.cpp USBCore.cpp | ||||||
|   LIB_SRC    += cortex_handlers.c iar_calls_sam3.c syscalls_sam3.c dtostrf.c itoa.c |   LIB_SRC    += cortex_handlers.c iar_calls_sam3.c syscalls_sam3.c dtostrf.c itoa.c | ||||||
|  |  | ||||||
|   | |||||||
| @@ -1,396 +0,0 @@ | |||||||
| /* |  | ||||||
|  * SoftwareSerial.cpp (formerly NewSoftSerial.cpp) |  | ||||||
|  * |  | ||||||
|  * Multi-instance software serial library for Arduino/Wiring |  | ||||||
|  * -- Interrupt-driven receive and other improvements by ladyada |  | ||||||
|  *    <https://ladyada.net> |  | ||||||
|  * -- Tuning, circular buffer, derivation from class Print/Stream, |  | ||||||
|  *    multi-instance support, porting to 8MHz processors, |  | ||||||
|  *    various optimizations, PROGMEM delay tables, inverse logic and |  | ||||||
|  *    direct port writing by Mikal Hart <http://www.arduiniana.org> |  | ||||||
|  * -- Pin change interrupt macros by Paul Stoffregen <https://www.pjrc.com> |  | ||||||
|  * -- 20MHz processor support by Garrett Mace <http://www.macetech.com> |  | ||||||
|  * -- ATmega1280/2560 support by Brett Hagman <https://www.roguerobotics.com> |  | ||||||
|  * -- STM32 support by Armin van der Togt |  | ||||||
|  * |  | ||||||
|  * This library is free software; you can redistribute it and/or |  | ||||||
|  * modify it under the terms of the GNU Lesser General Public |  | ||||||
|  * License as published by the Free Software Foundation; either |  | ||||||
|  * version 2.1 of the License, or (at your option) any later version. |  | ||||||
|  * |  | ||||||
|  * This library 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 |  | ||||||
|  * Lesser General Public License for more details. |  | ||||||
|  * |  | ||||||
|  * You should have received a copy of the GNU Lesser General Public |  | ||||||
|  * License along with this library; if not, write to the Free Software |  | ||||||
|  * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA |  | ||||||
|  * |  | ||||||
|  * The latest version of this library can always be found at |  | ||||||
|  * http://arduiniana.org. |  | ||||||
|  */ |  | ||||||
|  |  | ||||||
| // |  | ||||||
| // Includes |  | ||||||
| // |  | ||||||
| #if defined(PLATFORMIO) && defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) |  | ||||||
|  |  | ||||||
| #include "../../inc/MarlinConfig.h" |  | ||||||
|  |  | ||||||
| #include "SoftwareSerial.h" |  | ||||||
|  |  | ||||||
| #define OVERSAMPLE 3 // in RX, Timer will generate interruption OVERSAMPLE time during a bit. Thus OVERSAMPLE ticks in a bit. (interrupt not synchonized with edge). |  | ||||||
|  |  | ||||||
| // defined in bit-periods |  | ||||||
| #define HALFDUPLEX_SWITCH_DELAY 5 |  | ||||||
| // It's best to define TIMER_SERIAL in variant.h. If not defined, we choose one here |  | ||||||
| // The order is based on (lack of) features and compare channels, we choose the simplest available |  | ||||||
| // because we only need an update interrupt |  | ||||||
| #if !defined(TIMER_SERIAL) |  | ||||||
| #if  defined(TIM18_BASE) |  | ||||||
| #define TIMER_SERIAL TIM18 |  | ||||||
| #elif defined(TIM7_BASE) |  | ||||||
| #define TIMER_SERIAL TIM7 |  | ||||||
| #elif defined(TIM6_BASE) |  | ||||||
| #define TIMER_SERIAL TIM6 |  | ||||||
| #elif defined(TIM22_BASE) |  | ||||||
| #define TIMER_SERIAL TIM22 |  | ||||||
| #elif defined(TIM21_BASE) |  | ||||||
| #define TIMER_SERIAL TIM21 |  | ||||||
| #elif defined(TIM17_BASE) |  | ||||||
| #define TIMER_SERIAL TIM17 |  | ||||||
| #elif defined(TIM16_BASE) |  | ||||||
| #define TIMER_SERIAL TIM16 |  | ||||||
| #elif defined(TIM15_BASE) |  | ||||||
| #define TIMER_SERIAL TIM15 |  | ||||||
| #elif defined(TIM14_BASE) |  | ||||||
| #define TIMER_SERIAL TIM14 |  | ||||||
| #elif defined(TIM13_BASE) |  | ||||||
| #define TIMER_SERIAL TIM13 |  | ||||||
| #elif defined(TIM11_BASE) |  | ||||||
| #define TIMER_SERIAL TIM11 |  | ||||||
| #elif defined(TIM10_BASE) |  | ||||||
| #define TIMER_SERIAL TIM10 |  | ||||||
| #elif defined(TIM12_BASE) |  | ||||||
| #define TIMER_SERIAL TIM12 |  | ||||||
| #elif defined(TIM19_BASE) |  | ||||||
| #define TIMER_SERIAL TIM19 |  | ||||||
| #elif defined(TIM9_BASE) |  | ||||||
| #define TIMER_SERIAL TIM9 |  | ||||||
| #elif defined(TIM5_BASE) |  | ||||||
| #define TIMER_SERIAL TIM5 |  | ||||||
| #elif defined(TIM4_BASE) |  | ||||||
| #define TIMER_SERIAL TIM4 |  | ||||||
| #elif defined(TIM3_BASE) |  | ||||||
| #define TIMER_SERIAL TIM3 |  | ||||||
| #elif defined(TIM2_BASE) |  | ||||||
| #define TIMER_SERIAL TIM2 |  | ||||||
| #elif defined(TIM20_BASE) |  | ||||||
| #define TIMER_SERIAL TIM20 |  | ||||||
| #elif defined(TIM8_BASE) |  | ||||||
| #define TIMER_SERIAL TIM8 |  | ||||||
| #elif defined(TIM1_BASE) |  | ||||||
| #define TIMER_SERIAL TIM1 |  | ||||||
| #else |  | ||||||
| #error No suitable timer found for SoftwareSerial, define TIMER_SERIAL in variant.h |  | ||||||
| #endif |  | ||||||
| #endif |  | ||||||
| // |  | ||||||
| // Statics |  | ||||||
| // |  | ||||||
| HardwareTimer SoftwareSerial::timer(TIMER_SERIAL); |  | ||||||
| const IRQn_Type SoftwareSerial::timer_interrupt_number = static_cast<IRQn_Type>(getTimerUpIrq(TIMER_SERIAL)); |  | ||||||
| uint32_t SoftwareSerial::timer_interrupt_priority = NVIC_EncodePriority(NVIC_GetPriorityGrouping(), TIM_IRQ_PRIO, TIM_IRQ_SUBPRIO); |  | ||||||
| SoftwareSerial *SoftwareSerial::active_listener = nullptr; |  | ||||||
| SoftwareSerial *volatile SoftwareSerial::active_out = nullptr; |  | ||||||
| SoftwareSerial *volatile SoftwareSerial::active_in = nullptr; |  | ||||||
| int32_t SoftwareSerial::tx_tick_cnt = 0; // OVERSAMPLE ticks needed for a bit |  | ||||||
| int32_t volatile SoftwareSerial::rx_tick_cnt = 0;  // OVERSAMPLE ticks needed for a bit |  | ||||||
| uint32_t SoftwareSerial::tx_buffer = 0; |  | ||||||
| int32_t SoftwareSerial::tx_bit_cnt = 0; |  | ||||||
| uint32_t SoftwareSerial::rx_buffer = 0; |  | ||||||
| int32_t SoftwareSerial::rx_bit_cnt = -1; // rx_bit_cnt = -1 :  waiting for start bit |  | ||||||
| uint32_t SoftwareSerial::cur_speed = 0; |  | ||||||
|  |  | ||||||
| void SoftwareSerial::setInterruptPriority(uint32_t preemptPriority, uint32_t subPriority) { |  | ||||||
|   timer_interrupt_priority = NVIC_EncodePriority(NVIC_GetPriorityGrouping(), preemptPriority, subPriority); |  | ||||||
| } |  | ||||||
|  |  | ||||||
| // |  | ||||||
| // Private methods |  | ||||||
| // |  | ||||||
|  |  | ||||||
| void SoftwareSerial::setSpeed(uint32_t speed) { |  | ||||||
|   if (speed != cur_speed) { |  | ||||||
|     timer.pause(); |  | ||||||
|     if (speed != 0) { |  | ||||||
|       // Disable the timer |  | ||||||
|       uint32_t clock_rate, cmp_value; |  | ||||||
|       // Get timer clock |  | ||||||
|       clock_rate = timer.getTimerClkFreq(); |  | ||||||
|       int pre = 1; |  | ||||||
|       // Calculate prescale an compare value |  | ||||||
|       do { |  | ||||||
|         cmp_value = clock_rate / (speed * OVERSAMPLE); |  | ||||||
|         if (cmp_value >= UINT16_MAX) { |  | ||||||
|           clock_rate /= 2; |  | ||||||
|           pre *= 2; |  | ||||||
|         } |  | ||||||
|       } while (cmp_value >= UINT16_MAX); |  | ||||||
|       timer.setPrescaleFactor(pre); |  | ||||||
|       timer.setOverflow(cmp_value); |  | ||||||
|       timer.setCount(0); |  | ||||||
|       timer.attachInterrupt(&handleInterrupt); |  | ||||||
|       timer.resume(); |  | ||||||
|       NVIC_SetPriority(timer_interrupt_number, timer_interrupt_priority); |  | ||||||
|     } |  | ||||||
|     else |  | ||||||
|       timer.detachInterrupt(); |  | ||||||
|     cur_speed = speed; |  | ||||||
|   } |  | ||||||
| } |  | ||||||
|  |  | ||||||
| // This function sets the current object as the "listening" |  | ||||||
| // one and returns true if it replaces another |  | ||||||
| bool SoftwareSerial::listen() { |  | ||||||
|   if (active_listener != this) { |  | ||||||
|     // wait for any transmit to complete as we may change speed |  | ||||||
|     while (active_out); |  | ||||||
|     active_listener->stopListening(); |  | ||||||
|     rx_tick_cnt = 1; // 1 : next interrupt will decrease rx_tick_cnt to 0 which means RX pin level will be considered. |  | ||||||
|     rx_bit_cnt = -1; // rx_bit_cnt = -1 :  waiting for start bit |  | ||||||
|     setSpeed(_speed); |  | ||||||
|     active_listener = this; |  | ||||||
|     if (!_half_duplex) active_in = this; |  | ||||||
|     return true; |  | ||||||
|   } |  | ||||||
|   return false; |  | ||||||
| } |  | ||||||
|  |  | ||||||
| // Stop listening. Returns true if we were actually listening. |  | ||||||
| bool SoftwareSerial::stopListening() { |  | ||||||
|   if (active_listener == this) { |  | ||||||
|     // wait for any output to complete |  | ||||||
|     while (active_out); |  | ||||||
|     if (_half_duplex) setRXTX(false); |  | ||||||
|     active_listener = nullptr; |  | ||||||
|     active_in = nullptr; |  | ||||||
|     // turn off ints |  | ||||||
|     setSpeed(0); |  | ||||||
|     return true; |  | ||||||
|   } |  | ||||||
|   return false; |  | ||||||
| } |  | ||||||
|  |  | ||||||
| inline void SoftwareSerial::setTX() { |  | ||||||
|   if (_inverse_logic) |  | ||||||
|     LL_GPIO_ResetOutputPin(_transmitPinPort, _transmitPinNumber); |  | ||||||
|   else |  | ||||||
|     LL_GPIO_SetOutputPin(_transmitPinPort, _transmitPinNumber); |  | ||||||
|   pinMode(_transmitPin, OUTPUT); |  | ||||||
| } |  | ||||||
|  |  | ||||||
| inline void SoftwareSerial::setRX() { |  | ||||||
|   pinMode(_receivePin, _inverse_logic ? INPUT_PULLDOWN : INPUT_PULLUP); // pullup for normal logic! |  | ||||||
| } |  | ||||||
|  |  | ||||||
| inline void SoftwareSerial::setRXTX(bool input) { |  | ||||||
|   if (_half_duplex) { |  | ||||||
|     if (input) { |  | ||||||
|       if (active_in != this) { |  | ||||||
|         setRX(); |  | ||||||
|         rx_bit_cnt = -1; // rx_bit_cnt = -1 :  waiting for start bit |  | ||||||
|         rx_tick_cnt = 2; // 2 : next interrupt will be discarded. 2 interrupts required to consider RX pin level |  | ||||||
|         active_in = this; |  | ||||||
|       } |  | ||||||
|     } |  | ||||||
|     else { |  | ||||||
|       if (active_in == this) { |  | ||||||
|         setTX(); |  | ||||||
|         active_in = nullptr; |  | ||||||
|       } |  | ||||||
|     } |  | ||||||
|   } |  | ||||||
| } |  | ||||||
|  |  | ||||||
| inline void SoftwareSerial::send() { |  | ||||||
|   if (--tx_tick_cnt <= 0) { // if tx_tick_cnt > 0 interrupt is discarded. Only when tx_tick_cnt reaches 0 is TX pin set. |  | ||||||
|     if (tx_bit_cnt++ < 10) { // tx_bit_cnt < 10 transmission is not finished (10 = 1 start +8 bits + 1 stop) |  | ||||||
|       // Send data (including start and stop bits) |  | ||||||
|       if (tx_buffer & 1) |  | ||||||
|         LL_GPIO_SetOutputPin(_transmitPinPort, _transmitPinNumber); |  | ||||||
|       else |  | ||||||
|         LL_GPIO_ResetOutputPin(_transmitPinPort, _transmitPinNumber); |  | ||||||
|       tx_buffer >>= 1; |  | ||||||
|       tx_tick_cnt = OVERSAMPLE; // Wait OVERSAMPLE ticks to send next bit |  | ||||||
|     } |  | ||||||
|     else { // Transmission finished |  | ||||||
|       tx_tick_cnt = 1; |  | ||||||
|       if (_output_pending) { |  | ||||||
|         active_out = nullptr; |  | ||||||
|  |  | ||||||
|         // In half-duplex mode wait HALFDUPLEX_SWITCH_DELAY bit-periods after the byte has |  | ||||||
|         // been transmitted before allowing the switch to RX mode |  | ||||||
|       } |  | ||||||
|       else if (tx_bit_cnt > 10 + OVERSAMPLE * HALFDUPLEX_SWITCH_DELAY) { |  | ||||||
|         if (_half_duplex && active_listener == this) setRXTX(true); |  | ||||||
|         active_out = nullptr; |  | ||||||
|       } |  | ||||||
|     } |  | ||||||
|   } |  | ||||||
| } |  | ||||||
|  |  | ||||||
| // |  | ||||||
| // The receive routine called by the interrupt handler |  | ||||||
| // |  | ||||||
| inline void SoftwareSerial::recv() { |  | ||||||
|   if (--rx_tick_cnt <= 0) { // if rx_tick_cnt > 0 interrupt is discarded. Only when rx_tick_cnt reaches 0 is RX pin considered |  | ||||||
|     bool inbit = LL_GPIO_IsInputPinSet(_receivePinPort, _receivePinNumber) ^ _inverse_logic; |  | ||||||
|     if (rx_bit_cnt == -1) {  // rx_bit_cnt = -1 :  waiting for start bit |  | ||||||
|       if (!inbit) { |  | ||||||
|         // got start bit |  | ||||||
|         rx_bit_cnt = 0; // rx_bit_cnt == 0 : start bit received |  | ||||||
|         rx_tick_cnt = OVERSAMPLE + 1; // Wait 1 bit (OVERSAMPLE ticks) + 1 tick in order to sample RX pin in the middle of the edge (and not too close to the edge) |  | ||||||
|         rx_buffer = 0; |  | ||||||
|       } |  | ||||||
|       else |  | ||||||
|         rx_tick_cnt = 1; // Waiting for start bit, but wrong level. Wait for next Interrupt to check RX pin level |  | ||||||
|     } |  | ||||||
|     else if (rx_bit_cnt >= 8) { // rx_bit_cnt >= 8 : waiting for stop bit |  | ||||||
|       if (inbit) { |  | ||||||
|         // Stop-bit read complete. Add to buffer. |  | ||||||
|         uint8_t next = (_receive_buffer_tail + 1) % _SS_MAX_RX_BUFF; |  | ||||||
|         if (next != _receive_buffer_head) { |  | ||||||
|           // save new data in buffer: tail points to byte destination |  | ||||||
|           _receive_buffer[_receive_buffer_tail] = rx_buffer; // save new byte |  | ||||||
|           _receive_buffer_tail = next; |  | ||||||
|         } |  | ||||||
|         else // rx_bit_cnt = x  with x = [0..7] correspond to new bit x received |  | ||||||
|           _buffer_overflow = true; |  | ||||||
|       } |  | ||||||
|       // Full trame received. Restart waiting for start bit at next interrupt |  | ||||||
|       rx_tick_cnt = 1; |  | ||||||
|       rx_bit_cnt = -1; |  | ||||||
|     } |  | ||||||
|     else { |  | ||||||
|       // data bits |  | ||||||
|       rx_buffer >>= 1; |  | ||||||
|       if (inbit) rx_buffer |= 0x80; |  | ||||||
|       rx_bit_cnt++; // Prepare for next bit |  | ||||||
|       rx_tick_cnt = OVERSAMPLE; // Wait OVERSAMPLE ticks before sampling next bit |  | ||||||
|     } |  | ||||||
|   } |  | ||||||
| } |  | ||||||
|  |  | ||||||
| // |  | ||||||
| // Interrupt handling |  | ||||||
| // |  | ||||||
|  |  | ||||||
| /* static */ |  | ||||||
| inline void SoftwareSerial::handleInterrupt(HardwareTimer*) { |  | ||||||
|   if (active_in)   active_in->recv(); |  | ||||||
|   if (active_out) active_out->send(); |  | ||||||
| } |  | ||||||
|  |  | ||||||
| // |  | ||||||
| // Constructor |  | ||||||
| // |  | ||||||
| SoftwareSerial::SoftwareSerial(uint16_t receivePin, uint16_t transmitPin, bool inverse_logic /* = false */) : |  | ||||||
|   _receivePin(receivePin), |  | ||||||
|   _transmitPin(transmitPin), |  | ||||||
|   _receivePinPort(digitalPinToPort(receivePin)), |  | ||||||
|   _receivePinNumber(STM_LL_GPIO_PIN(digitalPinToPinName(receivePin))), |  | ||||||
|   _transmitPinPort(digitalPinToPort(transmitPin)), |  | ||||||
|   _transmitPinNumber(STM_LL_GPIO_PIN(digitalPinToPinName(transmitPin))), |  | ||||||
|   _speed(0), |  | ||||||
|   _buffer_overflow(false), |  | ||||||
|   _inverse_logic(inverse_logic), |  | ||||||
|   _half_duplex(receivePin == transmitPin), |  | ||||||
|   _output_pending(0), |  | ||||||
|   _receive_buffer_tail(0), |  | ||||||
|   _receive_buffer_head(0) |  | ||||||
| { |  | ||||||
|   if ((receivePin < NUM_DIGITAL_PINS) || (transmitPin < NUM_DIGITAL_PINS)) { |  | ||||||
|     /* Enable GPIO clock for tx and rx pin*/ |  | ||||||
|     set_GPIO_Port_Clock(STM_PORT(digitalPinToPinName(transmitPin))); |  | ||||||
|     set_GPIO_Port_Clock(STM_PORT(digitalPinToPinName(receivePin))); |  | ||||||
|   } |  | ||||||
|   else |  | ||||||
|     _Error_Handler("ERROR: invalid pin number\n", -1); |  | ||||||
| } |  | ||||||
|  |  | ||||||
| // |  | ||||||
| // Destructor |  | ||||||
| // |  | ||||||
| SoftwareSerial::~SoftwareSerial() { end(); } |  | ||||||
|  |  | ||||||
| // |  | ||||||
| // Public methods |  | ||||||
| // |  | ||||||
|  |  | ||||||
| void SoftwareSerial::begin(long speed) { |  | ||||||
|   #ifdef FORCE_BAUD_RATE |  | ||||||
|     speed = FORCE_BAUD_RATE; |  | ||||||
|   #endif |  | ||||||
|   _speed = speed; |  | ||||||
|   if (!_half_duplex) { |  | ||||||
|     setTX(); |  | ||||||
|     setRX(); |  | ||||||
|     listen(); |  | ||||||
|   } |  | ||||||
|   else |  | ||||||
|     setTX(); |  | ||||||
| } |  | ||||||
|  |  | ||||||
| void SoftwareSerial::end() { |  | ||||||
|   stopListening(); |  | ||||||
| } |  | ||||||
|  |  | ||||||
| // Read data from buffer |  | ||||||
| int SoftwareSerial::read() { |  | ||||||
|   // Empty buffer? |  | ||||||
|   if (_receive_buffer_head == _receive_buffer_tail) return -1; |  | ||||||
|  |  | ||||||
|   // Read from "head" |  | ||||||
|   uint8_t d = _receive_buffer[_receive_buffer_head]; // grab next byte |  | ||||||
|   _receive_buffer_head = (_receive_buffer_head + 1) % _SS_MAX_RX_BUFF; |  | ||||||
|   return d; |  | ||||||
| } |  | ||||||
|  |  | ||||||
| int SoftwareSerial::available() { |  | ||||||
|   return (_receive_buffer_tail + _SS_MAX_RX_BUFF - _receive_buffer_head) % _SS_MAX_RX_BUFF; |  | ||||||
| } |  | ||||||
|  |  | ||||||
| size_t SoftwareSerial::write(uint8_t b) { |  | ||||||
|   // wait for previous transmit to complete |  | ||||||
|   _output_pending = 1; |  | ||||||
|   while (active_out) { /* nada */ } |  | ||||||
|   // add start and stop bits. |  | ||||||
|   tx_buffer = b << 1 | 0x200; |  | ||||||
|   if (_inverse_logic) tx_buffer = ~tx_buffer; |  | ||||||
|   tx_bit_cnt = 0; |  | ||||||
|   tx_tick_cnt = OVERSAMPLE; |  | ||||||
|   setSpeed(_speed); |  | ||||||
|   if (_half_duplex) setRXTX(false); |  | ||||||
|   _output_pending = 0; |  | ||||||
|   // make us active |  | ||||||
|   active_out = this; |  | ||||||
|   return 1; |  | ||||||
| } |  | ||||||
|  |  | ||||||
| void SoftwareSerial::flush() { |  | ||||||
|   noInterrupts(); |  | ||||||
|   _receive_buffer_head = _receive_buffer_tail = 0; |  | ||||||
|   interrupts(); |  | ||||||
| } |  | ||||||
|  |  | ||||||
| int SoftwareSerial::peek() { |  | ||||||
|   // Empty buffer? |  | ||||||
|   if (_receive_buffer_head == _receive_buffer_tail) return -1; |  | ||||||
|  |  | ||||||
|   // Read from "head" |  | ||||||
|   return _receive_buffer[_receive_buffer_head]; |  | ||||||
| } |  | ||||||
|  |  | ||||||
| #endif // ARDUINO_ARCH_STM32 && !STM32GENERIC |  | ||||||
| @@ -1,114 +0,0 @@ | |||||||
| /** |  | ||||||
|  * SoftwareSerial.h (formerly NewSoftSerial.h) |  | ||||||
|  * |  | ||||||
|  * Multi-instance software serial library for Arduino/Wiring |  | ||||||
|  * -- Interrupt-driven receive and other improvements by ladyada |  | ||||||
|  *    (https://ladyada.net) |  | ||||||
|  * -- Tuning, circular buffer, derivation from class Print/Stream, |  | ||||||
|  *    multi-instance support, porting to 8MHz processors, |  | ||||||
|  *    various optimizations, PROGMEM delay tables, inverse logic and |  | ||||||
|  *    direct port writing by Mikal Hart (http://www.arduiniana.org) |  | ||||||
|  * -- Pin change interrupt macros by Paul Stoffregen (https://www.pjrc.com) |  | ||||||
|  * -- 20MHz processor support by Garrett Mace (http://www.macetech.com) |  | ||||||
|  * -- ATmega1280/2560 support by Brett Hagman (https://www.roguerobotics.com/) |  | ||||||
|  * |  | ||||||
|  * This library is free software; you can redistribute it and/or |  | ||||||
|  * modify it under the terms of the GNU Lesser General Public |  | ||||||
|  * License as published by the Free Software Foundation; either |  | ||||||
|  * version 2.1 of the License, or (at your option) any later version. |  | ||||||
|  * |  | ||||||
|  * This library 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 |  | ||||||
|  * Lesser General Public License for more details. |  | ||||||
|  * |  | ||||||
|  * You should have received a copy of the GNU Lesser General Public |  | ||||||
|  * License along with this library; if not, write to the Free Software |  | ||||||
|  * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA |  | ||||||
|  * |  | ||||||
|  * The latest version of this library can always be found at |  | ||||||
|  * http://arduiniana.org. |  | ||||||
|  */ |  | ||||||
| #pragma once |  | ||||||
|  |  | ||||||
| #include <Arduino.h> |  | ||||||
|  |  | ||||||
| /****************************************************************************** |  | ||||||
|  * Definitions |  | ||||||
|  ******************************************************************************/ |  | ||||||
|  |  | ||||||
| #define _SS_MAX_RX_BUFF 64 // RX buffer size |  | ||||||
|  |  | ||||||
| class SoftwareSerial : public Stream { |  | ||||||
|   private: |  | ||||||
|     // per object data |  | ||||||
|     uint16_t _receivePin; |  | ||||||
|     uint16_t _transmitPin; |  | ||||||
|     GPIO_TypeDef *_receivePinPort; |  | ||||||
|     uint32_t _receivePinNumber; |  | ||||||
|     GPIO_TypeDef *_transmitPinPort; |  | ||||||
|     uint32_t _transmitPinNumber; |  | ||||||
|     uint32_t _speed; |  | ||||||
|  |  | ||||||
|     uint16_t _buffer_overflow: 1; |  | ||||||
|     uint16_t _inverse_logic: 1; |  | ||||||
|     uint16_t _half_duplex: 1; |  | ||||||
|     uint16_t _output_pending: 1; |  | ||||||
|  |  | ||||||
|     unsigned char _receive_buffer[_SS_MAX_RX_BUFF]; |  | ||||||
|     volatile uint8_t _receive_buffer_tail; |  | ||||||
|     volatile uint8_t _receive_buffer_head; |  | ||||||
|  |  | ||||||
|     uint32_t delta_start = 0; |  | ||||||
|  |  | ||||||
|     // static data |  | ||||||
|     static HardwareTimer timer; |  | ||||||
|     static const IRQn_Type timer_interrupt_number; |  | ||||||
|     static uint32_t timer_interrupt_priority; |  | ||||||
|     static SoftwareSerial *active_listener; |  | ||||||
|     static SoftwareSerial *volatile active_out; |  | ||||||
|     static SoftwareSerial *volatile active_in; |  | ||||||
|     static int32_t tx_tick_cnt; |  | ||||||
|     static volatile int32_t rx_tick_cnt; |  | ||||||
|     static uint32_t tx_buffer; |  | ||||||
|     static int32_t tx_bit_cnt; |  | ||||||
|     static uint32_t rx_buffer; |  | ||||||
|     static int32_t rx_bit_cnt; |  | ||||||
|     static uint32_t cur_speed; |  | ||||||
|  |  | ||||||
|     // private methods |  | ||||||
|     void send(); |  | ||||||
|     void recv(); |  | ||||||
|     void setTX(); |  | ||||||
|     void setRX(); |  | ||||||
|     void setSpeed(uint32_t speed); |  | ||||||
|     void setRXTX(bool input); |  | ||||||
|     static void handleInterrupt(HardwareTimer *timer); |  | ||||||
|  |  | ||||||
|   public: |  | ||||||
|     // public methods |  | ||||||
|  |  | ||||||
|     SoftwareSerial(uint16_t receivePin, uint16_t transmitPin, bool inverse_logic=false); |  | ||||||
|     virtual ~SoftwareSerial(); |  | ||||||
|     void begin(long speed); |  | ||||||
|     bool listen(); |  | ||||||
|     void end(); |  | ||||||
|     bool isListening() { return active_listener == this; } |  | ||||||
|     bool stopListening(); |  | ||||||
|     bool overflow() { |  | ||||||
|       bool ret = _buffer_overflow; |  | ||||||
|       if (ret) _buffer_overflow = false; |  | ||||||
|       return ret; |  | ||||||
|     } |  | ||||||
|     int peek(); |  | ||||||
|  |  | ||||||
|     virtual size_t write(uint8_t byte); |  | ||||||
|     virtual int read(); |  | ||||||
|     virtual int available(); |  | ||||||
|     virtual void flush(); |  | ||||||
|     operator bool() { return true; } |  | ||||||
|  |  | ||||||
|     static void setInterruptPriority(uint32_t preemptPriority, uint32_t subPriority); |  | ||||||
|  |  | ||||||
|     using Print::write; |  | ||||||
| }; |  | ||||||
| @@ -110,7 +110,6 @@ | |||||||
| // ------------------------ | // ------------------------ | ||||||
|  |  | ||||||
| HardwareTimer *timer_instance[NUM_HARDWARE_TIMERS] = { NULL }; | HardwareTimer *timer_instance[NUM_HARDWARE_TIMERS] = { NULL }; | ||||||
| bool timer_enabled[NUM_HARDWARE_TIMERS] = { false }; |  | ||||||
|  |  | ||||||
| // ------------------------ | // ------------------------ | ||||||
| // Public functions | // Public functions | ||||||
| @@ -135,6 +134,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { | |||||||
|          * which changes the prescaler when an IRQ frequency change is needed |          * which changes the prescaler when an IRQ frequency change is needed | ||||||
|          * (for example when steppers are turned on) |          * (for example when steppers are turned on) | ||||||
|          */ |          */ | ||||||
|  |  | ||||||
|         timer_instance[timer_num]->setPrescaleFactor(STEPPER_TIMER_PRESCALE); //the -1 is done internally |         timer_instance[timer_num]->setPrescaleFactor(STEPPER_TIMER_PRESCALE); //the -1 is done internally | ||||||
|         timer_instance[timer_num]->setOverflow(_MIN(hal_timer_t(HAL_TIMER_TYPE_MAX), (HAL_TIMER_RATE) / (STEPPER_TIMER_PRESCALE) /* /frequency */), TICK_FORMAT); |         timer_instance[timer_num]->setOverflow(_MIN(hal_timer_t(HAL_TIMER_TYPE_MAX), (HAL_TIMER_RATE) / (STEPPER_TIMER_PRESCALE) /* /frequency */), TICK_FORMAT); | ||||||
|         break; |         break; | ||||||
| @@ -145,15 +145,13 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { | |||||||
|         break; |         break; | ||||||
|     } |     } | ||||||
|  |  | ||||||
|  |     // Disable preload. Leaving it default-enabled can cause the timer to stop if it happens | ||||||
|  |     // to exit the ISR after the start time for the next interrupt has already passed. | ||||||
|  |     timer_instance[timer_num]->setPreloadEnable(false); | ||||||
|  |  | ||||||
|     HAL_timer_enable_interrupt(timer_num); |     HAL_timer_enable_interrupt(timer_num); | ||||||
|  |  | ||||||
|     /* |     // Start the timer. | ||||||
|      * Initializes (and unfortunately starts) the timer. |  | ||||||
|      * This is needed to set correct IRQ priority at the moment but causes |  | ||||||
|      * no harm since every call to HAL_timer_start() is actually followed by |  | ||||||
|      * a call to HAL_timer_enable_interrupt() which means that there isn't |  | ||||||
|      * a case in which you want the timer to run without a callback. |  | ||||||
|      */ |  | ||||||
|     timer_instance[timer_num]->resume(); // First call to resume() MUST follow the attachInterrupt() |     timer_instance[timer_num]->resume(); // First call to resume() MUST follow the attachInterrupt() | ||||||
|  |  | ||||||
|     // This is fixed in Arduino_Core_STM32 1.8. |     // This is fixed in Arduino_Core_STM32 1.8. | ||||||
| @@ -161,47 +159,34 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { | |||||||
|     // timer_instance[timer_num]->setInterruptPriority |     // timer_instance[timer_num]->setInterruptPriority | ||||||
|     switch (timer_num) { |     switch (timer_num) { | ||||||
|       case STEP_TIMER_NUM: |       case STEP_TIMER_NUM: | ||||||
|         HAL_NVIC_SetPriority(STEP_TIMER_IRQ_NAME, STEP_TIMER_IRQ_PRIO, 0); |         timer_instance[timer_num]->setInterruptPriority(STEP_TIMER_IRQ_PRIO, 0); | ||||||
|         break; |         break; | ||||||
|       case TEMP_TIMER_NUM: |       case TEMP_TIMER_NUM: | ||||||
|         HAL_NVIC_SetPriority(TEMP_TIMER_IRQ_NAME, TEMP_TIMER_IRQ_PRIO, 0); |         timer_instance[timer_num]->setInterruptPriority(TEMP_TIMER_IRQ_PRIO, 0); | ||||||
|         break; |         break; | ||||||
|     } |     } | ||||||
|   } |   } | ||||||
| } | } | ||||||
|  |  | ||||||
| void HAL_timer_enable_interrupt(const uint8_t timer_num) { | void HAL_timer_enable_interrupt(const uint8_t timer_num) { | ||||||
|   if (HAL_timer_initialized(timer_num) && !timer_enabled[timer_num]) { |   if (HAL_timer_initialized(timer_num) && !timer_instance[timer_num]->hasInterrupt()) { | ||||||
|     timer_enabled[timer_num] = true; |  | ||||||
|     switch (timer_num) { |     switch (timer_num) { | ||||||
|       case STEP_TIMER_NUM: |       case STEP_TIMER_NUM: | ||||||
|       timer_instance[timer_num]->attachInterrupt(Step_Handler); |         timer_instance[timer_num]->attachInterrupt(Step_Handler); | ||||||
|       break; |         break; | ||||||
|     case TEMP_TIMER_NUM: |       case TEMP_TIMER_NUM: | ||||||
|       timer_instance[timer_num]->attachInterrupt(Temp_Handler); |         timer_instance[timer_num]->attachInterrupt(Temp_Handler); | ||||||
|       break; |         break; | ||||||
|     } |     } | ||||||
|   } |   } | ||||||
| } | } | ||||||
|  |  | ||||||
| void HAL_timer_disable_interrupt(const uint8_t timer_num) { | void HAL_timer_disable_interrupt(const uint8_t timer_num) { | ||||||
|   if (HAL_timer_interrupt_enabled(timer_num)) { |   if (HAL_timer_initialized(timer_num)) timer_instance[timer_num]->detachInterrupt(); | ||||||
|     timer_instance[timer_num]->detachInterrupt(); |  | ||||||
|     timer_enabled[timer_num] = false; |  | ||||||
|   } |  | ||||||
| } | } | ||||||
|  |  | ||||||
| bool HAL_timer_interrupt_enabled(const uint8_t timer_num) { | bool HAL_timer_interrupt_enabled(const uint8_t timer_num) { | ||||||
|   return HAL_timer_initialized(timer_num) && timer_enabled[timer_num]; |   return HAL_timer_initialized(timer_num) && timer_instance[timer_num]->hasInterrupt(); | ||||||
| } |  | ||||||
|  |  | ||||||
| // Only for use within the HAL |  | ||||||
| TIM_TypeDef * HAL_timer_device(const uint8_t timer_num) { |  | ||||||
|   switch (timer_num) { |  | ||||||
|     case STEP_TIMER_NUM: return STEP_TIMER_DEV; |  | ||||||
|     case TEMP_TIMER_NUM: return TEMP_TIMER_DEV; |  | ||||||
|   } |  | ||||||
|   return nullptr; |  | ||||||
| } | } | ||||||
|  |  | ||||||
| void SetTimerInterruptPriorities() { | void SetTimerInterruptPriorities() { | ||||||
| @@ -209,4 +194,87 @@ void SetTimerInterruptPriorities() { | |||||||
|   TERN_(HAS_SERVOS, libServo::setInterruptPriority(SERVO_TIMER_IRQ_PRIO, 0)); |   TERN_(HAS_SERVOS, libServo::setInterruptPriority(SERVO_TIMER_IRQ_PRIO, 0)); | ||||||
| } | } | ||||||
|  |  | ||||||
|  | // This is a terrible hack to replicate the behavior used in the framework's SoftwareSerial.cpp | ||||||
|  | // to choose a serial timer. It will select TIM7 on most boards used by Marlin, but this is more | ||||||
|  | // resiliant to new MCUs which may not have a TIM7. Best practice is to explicitly specify | ||||||
|  | // TIMER_SERIAL to avoid relying on framework selections which may not be predictable. | ||||||
|  | #if !defined(TIMER_SERIAL) | ||||||
|  |   #if defined (TIM18_BASE) | ||||||
|  |     #define TIMER_SERIAL TIM18 | ||||||
|  |   #elif defined (TIM7_BASE) | ||||||
|  |     #define TIMER_SERIAL TIM7 | ||||||
|  |   #elif defined (TIM6_BASE) | ||||||
|  |     #define TIMER_SERIAL TIM6 | ||||||
|  |   #elif defined (TIM22_BASE) | ||||||
|  |     #define TIMER_SERIAL TIM22 | ||||||
|  |   #elif defined (TIM21_BASE) | ||||||
|  |     #define TIMER_SERIAL TIM21 | ||||||
|  |   #elif defined (TIM17_BASE) | ||||||
|  |     #define TIMER_SERIAL TIM17 | ||||||
|  |   #elif defined (TIM16_BASE) | ||||||
|  |     #define TIMER_SERIAL TIM16 | ||||||
|  |   #elif defined (TIM15_BASE) | ||||||
|  |     #define TIMER_SERIAL TIM15 | ||||||
|  |   #elif defined (TIM14_BASE) | ||||||
|  |     #define TIMER_SERIAL TIM14 | ||||||
|  |   #elif defined (TIM13_BASE) | ||||||
|  |     #define TIMER_SERIAL TIM13 | ||||||
|  |   #elif defined (TIM11_BASE) | ||||||
|  |     #define TIMER_SERIAL TIM11 | ||||||
|  |   #elif defined (TIM10_BASE) | ||||||
|  |     #define TIMER_SERIAL TIM10 | ||||||
|  |   #elif defined (TIM12_BASE) | ||||||
|  |     #define TIMER_SERIAL TIM12 | ||||||
|  |   #elif defined (TIM19_BASE) | ||||||
|  |     #define TIMER_SERIAL TIM19 | ||||||
|  |   #elif defined (TIM9_BASE) | ||||||
|  |     #define TIMER_SERIAL TIM9 | ||||||
|  |   #elif defined (TIM5_BASE) | ||||||
|  |     #define TIMER_SERIAL TIM5 | ||||||
|  |   #elif defined (TIM4_BASE) | ||||||
|  |     #define TIMER_SERIAL TIM4 | ||||||
|  |   #elif defined (TIM3_BASE) | ||||||
|  |     #define TIMER_SERIAL TIM3 | ||||||
|  |   #elif defined (TIM2_BASE) | ||||||
|  |     #define TIMER_SERIAL TIM2 | ||||||
|  |   #elif defined (TIM20_BASE) | ||||||
|  |     #define TIMER_SERIAL TIM20 | ||||||
|  |   #elif defined (TIM8_BASE) | ||||||
|  |     #define TIMER_SERIAL TIM8 | ||||||
|  |   #elif defined (TIM1_BASE) | ||||||
|  |     #define TIMER_SERIAL TIM1 | ||||||
|  |   #else | ||||||
|  |     #error No suitable timer found for SoftwareSerial, define TIMER_SERIAL in variant.h | ||||||
|  |   #endif | ||||||
|  | #endif | ||||||
|  |  | ||||||
|  | // Place all timers used into an array, then recursively check for duplicates during compilation. | ||||||
|  | // This does not currently account for timers used for PWM, such as for fans. | ||||||
|  | // Timers are actually pointers. Convert to integers to simplify constexpr logic. | ||||||
|  | static constexpr uintptr_t timers_in_use[] = { | ||||||
|  |   uintptr_t(TEMP_TIMER_DEV),  // Override in pins file | ||||||
|  |   uintptr_t(STEP_TIMER_DEV),  // Override in pins file | ||||||
|  |   #if HAS_TMC_SW_SERIAL | ||||||
|  |     uintptr_t(TIMER_SERIAL),  // Set in variant.h, or as a define in platformio.h if not present in variant.h | ||||||
|  |   #endif | ||||||
|  |   #if ENABLED(SPEAKER) | ||||||
|  |     uintptr_t(TIMER_TONE),    // Set in variant.h, or as a define in platformio.h if not present in variant.h | ||||||
|  |   #endif | ||||||
|  |   #if HAS_SERVOS | ||||||
|  |     uintptr_t(TIMER_SERVO),   // Set in variant.h, or as a define in platformio.h if not present in variant.h | ||||||
|  |   #endif | ||||||
|  |   }; | ||||||
|  |  | ||||||
|  | static constexpr bool verify_no_duplicate_timers() { | ||||||
|  |   LOOP_L_N(i, COUNT(timers_in_use)) | ||||||
|  |     LOOP_S_L_N(j, i + 1, COUNT(timers_in_use)) | ||||||
|  |       if (timers_in_use[i] == timers_in_use[j]) return false; | ||||||
|  |   return true; | ||||||
|  | } | ||||||
|  |  | ||||||
|  | // If this assertion fails at compile time, review the timers_in_use array. If default_envs is | ||||||
|  | // defined properly in platformio.ini, VS Code can evaluate the array when hovering over it, | ||||||
|  | // making it easy to identify the conflicting timers. | ||||||
|  | static_assert(verify_no_duplicate_timers(), "One or more timer conflict detected"); | ||||||
|  |  | ||||||
| #endif // ARDUINO_ARCH_STM32 && !STM32GENERIC | #endif // ARDUINO_ARCH_STM32 && !STM32GENERIC | ||||||
|   | |||||||
| @@ -30,8 +30,18 @@ | |||||||
|  |  | ||||||
| #define FORCE_INLINE __attribute__((always_inline)) inline | #define FORCE_INLINE __attribute__((always_inline)) inline | ||||||
|  |  | ||||||
|  | // STM32 timers may be 16 or 32 bit. Limiting HAL_TIMER_TYPE_MAX to 16 bits | ||||||
|  | // avoids issues with STM32F0 MCUs, which seem to pause timers if UINT32_MAX | ||||||
|  | // is written to the register. STM32F4 timers do not manifest this issue, | ||||||
|  | // even when writing to 16 bit timers. | ||||||
|  | // | ||||||
|  | // The range of the timer can be queried at runtime using IS_TIM_32B_COUNTER_INSTANCE. | ||||||
|  | // This is a more expensive check than a simple compile-time constant, so its | ||||||
|  | // implementation is deferred until the desire for a 32-bit range outweighs the cost | ||||||
|  | // of adding a run-time check and HAL_TIMER_TYPE_MAX is refactored to allow unique | ||||||
|  | // values for each timer. | ||||||
| #define hal_timer_t uint32_t | #define hal_timer_t uint32_t | ||||||
| #define HAL_TIMER_TYPE_MAX 0xFFFFFFFF // Timers can be 16 or 32 bit | #define HAL_TIMER_TYPE_MAX UINT16_MAX | ||||||
|  |  | ||||||
| #ifndef STEP_TIMER_NUM | #ifndef STEP_TIMER_NUM | ||||||
|   #define STEP_TIMER_NUM        0  // Timer Index for Stepper |   #define STEP_TIMER_NUM        0  // Timer Index for Stepper | ||||||
| @@ -61,14 +71,14 @@ | |||||||
| #define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM) | #define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM) | ||||||
| #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM) | #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM) | ||||||
|  |  | ||||||
| extern void Step_Handler(HardwareTimer *htim); | extern void Step_Handler(); | ||||||
| extern void Temp_Handler(HardwareTimer *htim); | extern void Temp_Handler(); | ||||||
|  |  | ||||||
| #ifndef HAL_STEP_TIMER_ISR | #ifndef HAL_STEP_TIMER_ISR | ||||||
|   #define HAL_STEP_TIMER_ISR() void Step_Handler(HardwareTimer *htim) |   #define HAL_STEP_TIMER_ISR() void Step_Handler() | ||||||
| #endif | #endif | ||||||
| #ifndef HAL_TEMP_TIMER_ISR | #ifndef HAL_TEMP_TIMER_ISR | ||||||
|   #define HAL_TEMP_TIMER_ISR() void Temp_Handler(HardwareTimer *htim) |   #define HAL_TEMP_TIMER_ISR() void Temp_Handler() | ||||||
| #endif | #endif | ||||||
|  |  | ||||||
| // ------------------------ | // ------------------------ | ||||||
| @@ -90,8 +100,6 @@ bool HAL_timer_interrupt_enabled(const uint8_t timer_num); | |||||||
| // Exposed here to allow all timer priority information to reside in timers.cpp | // Exposed here to allow all timer priority information to reside in timers.cpp | ||||||
| void SetTimerInterruptPriorities(); | void SetTimerInterruptPriorities(); | ||||||
|  |  | ||||||
| //TIM_TypeDef* HAL_timer_device(const uint8_t timer_num); no need to be public for now. not public = not used externally |  | ||||||
|  |  | ||||||
| // FORCE_INLINE because these are used in performance-critical situations | // FORCE_INLINE because these are used in performance-critical situations | ||||||
| FORCE_INLINE bool HAL_timer_initialized(const uint8_t timer_num) { | FORCE_INLINE bool HAL_timer_initialized(const uint8_t timer_num) { | ||||||
|   return timer_instance[timer_num] != NULL; |   return timer_instance[timer_num] != NULL; | ||||||
|   | |||||||
| @@ -282,7 +282,7 @@ | |||||||
|  |  | ||||||
| #define BOARD_STM32F103RE             4000  // STM32F103RE Libmaple-based STM32F1 controller | #define BOARD_STM32F103RE             4000  // STM32F103RE Libmaple-based STM32F1 controller | ||||||
| #define BOARD_MALYAN_M200             4001  // STM32C8T6  Libmaple-based STM32F1 controller | #define BOARD_MALYAN_M200             4001  // STM32C8T6  Libmaple-based STM32F1 controller | ||||||
| #define BOARD_MALYAN_M200_V2          4002  // STM32F070RB  Libmaple-based STM32F0 controller | #define BOARD_MALYAN_M200_V2          4002  // STM32F070CB  STM32F0 controller | ||||||
| #define BOARD_STM3R_MINI              4003  // STM32F103RE  Libmaple-based STM32F1 controller | #define BOARD_STM3R_MINI              4003  // STM32F103RE  Libmaple-based STM32F1 controller | ||||||
| #define BOARD_GTM32_PRO_VB            4004  // STM32F103VET6 controller | #define BOARD_GTM32_PRO_VB            4004  // STM32F103VET6 controller | ||||||
| #define BOARD_MORPHEUS                4005  // STM32F103C8 / STM32F103CB  Libmaple-based STM32F1 controller | #define BOARD_MORPHEUS                4005  // STM32F103C8 / STM32F103CB  Libmaple-based STM32F1 controller | ||||||
|   | |||||||
| @@ -480,7 +480,7 @@ | |||||||
| // STM32 ARM Cortex-M0 | // STM32 ARM Cortex-M0 | ||||||
| // | // | ||||||
| #elif MB(MALYAN_M200_V2) | #elif MB(MALYAN_M200_V2) | ||||||
|   #include "stm32f0/pins_MALYAN_M200_V2.h"      // STM32F0                                env:STM32F070RB_malyan |   #include "stm32f0/pins_MALYAN_M200_V2.h"      // STM32F0                                env:STM32F070RB_malyan env:STM32F070CB_malyan | ||||||
| #elif MB(MALYAN_M300) | #elif MB(MALYAN_M300) | ||||||
|   #include "stm32f0/pins_MALYAN_M300.h"         // STM32F070                              env:malyan_M300 |   #include "stm32f0/pins_MALYAN_M300.h"         // STM32F070                              env:malyan_M300 | ||||||
|  |  | ||||||
|   | |||||||
| @@ -21,7 +21,7 @@ | |||||||
|  */ |  */ | ||||||
| #pragma once | #pragma once | ||||||
|  |  | ||||||
| #ifndef TARGET_STM32F4 | #ifndef STM32F4 | ||||||
|   #error "Oops! Select an STM32F4 board in 'Tools > Board.'" |   #error "Oops! Select an STM32F4 board in 'Tools > Board.'" | ||||||
| #elif HOTENDS > 1 || E_STEPPERS > 1 | #elif HOTENDS > 1 || E_STEPPERS > 1 | ||||||
|   #error "BIGTREE BTT002 V1.0 supports up to 1 hotends / E-steppers." |   #error "BIGTREE BTT002 V1.0 supports up to 1 hotends / E-steppers." | ||||||
|   | |||||||
| @@ -21,7 +21,7 @@ | |||||||
|  */ |  */ | ||||||
| #pragma once | #pragma once | ||||||
|  |  | ||||||
| #ifndef TARGET_STM32F4 | #ifndef STM32F4 | ||||||
|   #error "Oops! Select an STM32F4 board in 'Tools > Board.'" |   #error "Oops! Select an STM32F4 board in 'Tools > Board.'" | ||||||
| #elif HOTENDS > 8 || E_STEPPERS > 8 | #elif HOTENDS > 8 || E_STEPPERS > 8 | ||||||
|   #error "BIGTREE GTR V1.0 supports up to 8 hotends / E-steppers." |   #error "BIGTREE GTR V1.0 supports up to 8 hotends / E-steppers." | ||||||
|   | |||||||
| @@ -21,7 +21,7 @@ | |||||||
|  */ |  */ | ||||||
| #pragma once | #pragma once | ||||||
|  |  | ||||||
| #ifndef TARGET_STM32F4 | #ifndef STM32F4 | ||||||
|   #error "Oops! Select an STM32F4 board in 'Tools > Board.'" |   #error "Oops! Select an STM32F4 board in 'Tools > Board.'" | ||||||
| #endif | #endif | ||||||
|  |  | ||||||
|   | |||||||
| @@ -42,11 +42,12 @@ | |||||||
| // Configure Timers | // Configure Timers | ||||||
| // TIM6 is used for TONE | // TIM6 is used for TONE | ||||||
| // TIM7 is used for SERVO | // TIM7 is used for SERVO | ||||||
| // TIMER_SERIAL defaults to TIM7 so we'll override it here | // TIMER_SERIAL defaults to TIM7 and must be overridden in the platformio.h file if SERVO will also be used. | ||||||
| // | //              This will be difficult to solve from the Arduino IDE, without modifying the RUMBA32 variant | ||||||
| #define STEP_TIMER                            10 | //              included with the STM32 framework. | ||||||
| #define TEMP_TIMER                            14 |  | ||||||
| #define TIMER_SERIAL                        TIM9 | #define STEP_TIMER 10 | ||||||
|  | #define TEMP_TIMER 14 | ||||||
| #define HAL_TIMER_RATE                     F_CPU | #define HAL_TIMER_RATE                     F_CPU | ||||||
|  |  | ||||||
| // | // | ||||||
|   | |||||||
| @@ -15,7 +15,8 @@ | |||||||
|       ] |       ] | ||||||
|     ], |     ], | ||||||
|     "mcu": "stm32f407zgt6", |     "mcu": "stm32f407zgt6", | ||||||
|     "variant": "LERDGE" |     "variant": "LERDGE", | ||||||
|  |     "ldscript": "LERDGE.ld" | ||||||
|   }, |   }, | ||||||
|   "debug": { |   "debug": { | ||||||
|     "jlink_device": "STM32F407ZG", |     "jlink_device": "STM32F407ZG", | ||||||
|   | |||||||
| @@ -4,7 +4,7 @@ | |||||||
|     "extra_flags": "-DSTM32F070xB", |     "extra_flags": "-DSTM32F070xB", | ||||||
|     "f_cpu": "48000000L", |     "f_cpu": "48000000L", | ||||||
|     "mcu": "stm32f070rbt6", |     "mcu": "stm32f070rbt6", | ||||||
|     "variant": "MALYANM200_F070CB", |     "variant": "MALYANMx00_F070CB", | ||||||
|     "vec_tab_addr": "0x8002000" |     "vec_tab_addr": "0x8002000" | ||||||
|   }, |   }, | ||||||
|   "debug": { |   "debug": { | ||||||
|   | |||||||
| @@ -4,7 +4,7 @@ | |||||||
|     "extra_flags": "-DSTM32F446xx", |     "extra_flags": "-DSTM32F446xx", | ||||||
|     "f_cpu": "180000000L", |     "f_cpu": "180000000L", | ||||||
|     "mcu": "stm32f446ret6", |     "mcu": "stm32f446ret6", | ||||||
|     "variant": "FYSETC_S6" |     "variant": "MARLIN_FYSETC_S6" | ||||||
|   }, |   }, | ||||||
|   "connectivity": [ |   "connectivity": [ | ||||||
|     "can" |     "can" | ||||||
| @@ -1,33 +0,0 @@ | |||||||
| from os.path import join |  | ||||||
| Import("env") |  | ||||||
|  |  | ||||||
| import os,shutil |  | ||||||
| from SCons.Script import DefaultEnvironment |  | ||||||
| from platformio import util |  | ||||||
|  |  | ||||||
| env = DefaultEnvironment() |  | ||||||
| platform = env.PioPlatform() |  | ||||||
| board = env.BoardConfig() |  | ||||||
|  |  | ||||||
| FRAMEWORK_DIR = platform.get_package_dir("framework-arduinoststm32") |  | ||||||
| #FRAMEWORK_DIR = platform.get_package_dir("framework-arduinoststm32@3.10500.190327") |  | ||||||
| CMSIS_DIR = os.path.join(FRAMEWORK_DIR, "CMSIS", "CMSIS") |  | ||||||
| assert os.path.isdir(FRAMEWORK_DIR) |  | ||||||
| assert os.path.isdir(CMSIS_DIR) |  | ||||||
| assert os.path.isdir("buildroot/share/PlatformIO/variants") |  | ||||||
|  |  | ||||||
| mcu_type = board.get("build.mcu")[:-2] |  | ||||||
| variant = board.get("build.variant") |  | ||||||
| series = mcu_type[:7].upper() + "xx" |  | ||||||
| variant_dir = os.path.join(FRAMEWORK_DIR, "variants", variant) |  | ||||||
|  |  | ||||||
| source_dir = os.path.join("buildroot/share/PlatformIO/variants", variant) |  | ||||||
| assert os.path.isdir(source_dir) |  | ||||||
|  |  | ||||||
| if not os.path.isdir(variant_dir): |  | ||||||
|     os.mkdir(variant_dir) |  | ||||||
|  |  | ||||||
| for file_name in os.listdir(source_dir): |  | ||||||
|     full_file_name = os.path.join(source_dir, file_name) |  | ||||||
|     if os.path.isfile(full_file_name): |  | ||||||
|         shutil.copy(full_file_name, variant_dir) |  | ||||||
| @@ -115,7 +115,7 @@ extern "C" { | |||||||
| #define NUM_ANALOG_FIRST        80 | #define NUM_ANALOG_FIRST        80 | ||||||
| 
 | 
 | ||||||
| // PWM resolution
 | // PWM resolution
 | ||||||
| #define PWM_RESOLUTION          12 | // #define PWM_RESOLUTION          12
 | ||||||
| #define PWM_FREQUENCY           20000 // >= 20 Khz => inaudible noise for fans
 | #define PWM_FREQUENCY           20000 // >= 20 Khz => inaudible noise for fans
 | ||||||
| #define PWM_MAX_DUTY_CYCLE      255 | #define PWM_MAX_DUTY_CYCLE      255 | ||||||
| 
 | 
 | ||||||
							
								
								
									
										15
									
								
								buildroot/tests/STM32F070CB_malyan-tests
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										15
									
								
								buildroot/tests/STM32F070CB_malyan-tests
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,15 @@ | |||||||
|  | #!/usr/bin/env bash | ||||||
|  | # | ||||||
|  | # Build tests for STM32F070CB Malyan M200 v2 | ||||||
|  | # | ||||||
|  |  | ||||||
|  | # exit on first failure | ||||||
|  | set -e | ||||||
|  |  | ||||||
|  | restore_configs | ||||||
|  | opt_set MOTHERBOARD BOARD_MALYAN_M200_V2 | ||||||
|  | opt_set SERIAL_PORT -1 | ||||||
|  | exec_test $1 $2 "Malyan M200 v2 Default Config" | ||||||
|  |  | ||||||
|  | # cleanup | ||||||
|  | restore_configs | ||||||
| @@ -661,13 +661,10 @@ board     = nxp_lpc1769 | |||||||
| # HAL/STM32 Base Environment values | # HAL/STM32 Base Environment values | ||||||
| # | # | ||||||
| [common_stm32] | [common_stm32] | ||||||
| platform      = ststm32@~6.1.0 | platform      = ststm32@~8.0 | ||||||
| platform_packages = framework-arduinoststm32@>=4.10700,<4.10800 |  | ||||||
| lib_ignore    = SoftwareSerial |  | ||||||
| build_flags   = ${common.build_flags} | build_flags   = ${common.build_flags} | ||||||
|   -IMarlin/src/HAL/STM32 -std=gnu++14 |   -std=gnu++14 | ||||||
|   -DUSBCON -DUSBD_USE_CDC |   -DUSBCON -DUSBD_USE_CDC | ||||||
|   -DUSBD_VID=0x0483 |  | ||||||
|   -DTIM_IRQ_PRIO=13 |   -DTIM_IRQ_PRIO=13 | ||||||
| build_unflags = -std=gnu++11 | build_unflags = -std=gnu++11 | ||||||
| src_filter    = ${common.default_src_filter} +<src/HAL/STM32> | src_filter    = ${common.default_src_filter} +<src/HAL/STM32> | ||||||
| @@ -676,7 +673,7 @@ src_filter    = ${common.default_src_filter} +<src/HAL/STM32> | |||||||
| # HAL/STM32F1 Common Environment values | # HAL/STM32F1 Common Environment values | ||||||
| # | # | ||||||
| [common_stm32f1] | [common_stm32f1] | ||||||
| platform      = ${common_stm32.platform} | platform      = ststm32@~6.1 | ||||||
| build_flags   = !python Marlin/src/HAL/STM32F1/build_flags.py | build_flags   = !python Marlin/src/HAL/STM32F1/build_flags.py | ||||||
|   ${common.build_flags} -std=gnu++14 -DHAVE_SW_SERIAL |   ${common.build_flags} -std=gnu++14 -DHAVE_SW_SERIAL | ||||||
| build_unflags = -std=gnu11 -std=gnu++11 | build_unflags = -std=gnu11 -std=gnu++11 | ||||||
| @@ -828,7 +825,6 @@ platform      = ${common_stm32.platform} | |||||||
| extends       = common_stm32 | extends       = common_stm32 | ||||||
| board         = armed_v1 | board         = armed_v1 | ||||||
| build_flags   = ${common_stm32.build_flags} | build_flags   = ${common_stm32.build_flags} | ||||||
|   '-DUSB_PRODUCT="ARMED_V1"' |  | ||||||
|   -O2 -ffreestanding -fsigned-char -fno-move-loop-invariants -fno-strict-aliasing |   -O2 -ffreestanding -fsigned-char -fno-move-loop-invariants -fno-strict-aliasing | ||||||
|  |  | ||||||
| # | # | ||||||
| @@ -1008,20 +1004,29 @@ lib_ignore    = ${common_stm32f1.lib_ignore} | |||||||
| platform    = ${common_stm32.platform} | platform    = ${common_stm32.platform} | ||||||
| extends     = common_stm32 | extends     = common_stm32 | ||||||
| board       = malyanM200v2 | board       = malyanM200v2 | ||||||
| build_flags = ${common_stm32.build_flags} -DSTM32F0xx -DUSB_PRODUCT=\"STM32F070RB\" -DHAL_PCD_MODULE_ENABLED | build_flags = ${common_stm32.build_flags} -DHAL_PCD_MODULE_ENABLED | ||||||
|   -O2 -ffreestanding -fsigned-char -fno-move-loop-invariants -fno-strict-aliasing -std=gnu11 -std=gnu++11 |   -O2 -ffreestanding -fsigned-char -fno-move-loop-invariants -fno-strict-aliasing | ||||||
|   -DCUSTOM_STARTUP_FILE |   -DCUSTOM_STARTUP_FILE | ||||||
| lib_ignore  = SoftwareSerial |  | ||||||
|  | # | ||||||
|  | # Malyan M200 v2 (STM32F070CB) | ||||||
|  | # | ||||||
|  | [env:STM32F070CB_malyan] | ||||||
|  | platform    = ${common_stm32.platform} | ||||||
|  | extends     = common_stm32 | ||||||
|  | board       = malyanm200_f070cb | ||||||
|  | build_flags = ${common_stm32.build_flags} | ||||||
|  |   -DHAL_PCD_MODULE_ENABLED -DDISABLE_GENERIC_SERIALUSB -DHAL_UART_MODULE_ENABLED -DCUSTOM_STARTUP_FILE | ||||||
|  |  | ||||||
| # | # | ||||||
| # Malyan M300 (STM32F070CB) | # Malyan M300 (STM32F070CB) | ||||||
| # | # | ||||||
| [env:malyan_M300] | [env:malyan_M300] | ||||||
| platform    = ststm32@>=6.1.0,<6.2.0 | platform    = ${common_stm32.platform} | ||||||
|  | extends     = common_stm32 | ||||||
| board       = malyanm300_f070cb | board       = malyanm300_f070cb | ||||||
| build_flags = ${common.build_flags} | build_flags = ${common_stm32.build_flags} | ||||||
|   -DUSBCON -DUSBD_VID=0x0483 "-DUSB_MANUFACTURER=\"Unknown\"" "-DUSB_PRODUCT=\"MALYAN_M300\"" |   -DHAL_PCD_MODULE_ENABLED -DDISABLE_GENERIC_SERIALUSB -DHAL_UART_MODULE_ENABLED | ||||||
|   -DHAL_PCD_MODULE_ENABLED -DUSBD_USE_CDC -DDISABLE_GENERIC_SERIALUSB -DHAL_UART_MODULE_ENABLED |  | ||||||
| src_filter  = ${common.default_src_filter} +<src/HAL/STM32> | src_filter  = ${common.default_src_filter} +<src/HAL/STM32> | ||||||
|  |  | ||||||
| # | # | ||||||
| @@ -1074,13 +1079,11 @@ platform          = ${common_stm32.platform} | |||||||
| extends           = common_stm32 | extends           = common_stm32 | ||||||
| board             = STEVAL_STM32F401VE | board             = STEVAL_STM32F401VE | ||||||
| build_flags       = ${common_stm32.build_flags} | build_flags       = ${common_stm32.build_flags} | ||||||
|   -DTARGET_STM32F4 -DARDUINO_STEVAL -DSTM32F401xE |   -DARDUINO_STEVAL -DSTM32F401xE | ||||||
|   -DUSB_PRODUCT=\"STEVAL_F401VE\" |  | ||||||
|   -DDISABLE_GENERIC_SERIALUSB -DUSBD_USE_CDC_COMPOSITE -DUSE_USB_FS |   -DDISABLE_GENERIC_SERIALUSB -DUSBD_USE_CDC_COMPOSITE -DUSE_USB_FS | ||||||
| extra_scripts     = ${common.extra_scripts} | extra_scripts     = ${common.extra_scripts} | ||||||
|   pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py |   pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py | ||||||
|   buildroot/share/PlatformIO/scripts/STEVAL__F401XX.py |   buildroot/share/PlatformIO/scripts/STEVAL__F401XX.py | ||||||
| lib_ignore        = SoftwareSerial |  | ||||||
|  |  | ||||||
| # | # | ||||||
| # FLYF407ZG | # FLYF407ZG | ||||||
| @@ -1090,8 +1093,7 @@ platform          = ${common_stm32.platform} | |||||||
| extends           = common_stm32 | extends           = common_stm32 | ||||||
| board             = FLYF407ZG | board             = FLYF407ZG | ||||||
| build_flags       = ${common_stm32.build_flags} | build_flags       = ${common_stm32.build_flags} | ||||||
|   -DSTM32F4 -DUSB_PRODUCT=\"STM32F407ZG\" |   -DVECT_TAB_OFFSET=0x8000 | ||||||
|   -DTARGET_STM32F4 -DVECT_TAB_OFFSET=0x8000 |  | ||||||
| extra_scripts     = ${common.extra_scripts} | extra_scripts     = ${common.extra_scripts} | ||||||
|   pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py |   pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py | ||||||
|  |  | ||||||
| @@ -1101,14 +1103,13 @@ extra_scripts     = ${common.extra_scripts} | |||||||
| [env:FYSETC_S6] | [env:FYSETC_S6] | ||||||
| platform          = ${common_stm32.platform} | platform          = ${common_stm32.platform} | ||||||
| extends           = common_stm32 | extends           = common_stm32 | ||||||
| platform_packages = ${common_stm32.platform_packages} | platform_packages = tool-stm32duino | ||||||
|    tool-stm32duino | board             = marlin_fysetc_s6 | ||||||
| board             = fysetc_s6 |  | ||||||
| build_flags       = ${common_stm32.build_flags} | build_flags       = ${common_stm32.build_flags} | ||||||
|   -DTARGET_STM32F4 -DVECT_TAB_OFFSET=0x10000 |   -DVECT_TAB_OFFSET=0x10000 | ||||||
|   -DHAL_PCD_MODULE_ENABLED '-DUSB_PRODUCT="FYSETC_S6"' |   -DHAL_PCD_MODULE_ENABLED | ||||||
| extra_scripts     = ${common.extra_scripts} | extra_scripts     = ${common.extra_scripts} | ||||||
|   pre:buildroot/share/PlatformIO/scripts/fysetc_STM32S6.py |   pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py | ||||||
| debug_tool        = stlink | debug_tool        = stlink | ||||||
| upload_protocol   = dfu | upload_protocol   = dfu | ||||||
| upload_command    = dfu-util -a 0 -s 0x08010000:leave -D "$SOURCE" | upload_command    = dfu-util -a 0 -s 0x08010000:leave -D "$SOURCE" | ||||||
| @@ -1123,12 +1124,10 @@ platform          = ${common_stm32.platform} | |||||||
| extends           = common_stm32 | extends           = common_stm32 | ||||||
| board             = blackSTM32F407VET6 | board             = blackSTM32F407VET6 | ||||||
| build_flags       = ${common_stm32.build_flags} | build_flags       = ${common_stm32.build_flags} | ||||||
|   -DTARGET_STM32F4 -DARDUINO_BLACK_F407VE |   -DARDUINO_BLACK_F407VE | ||||||
|   -DUSB_PRODUCT=\"BLACK_F407VE\" |  | ||||||
|   -DUSBD_USE_CDC_COMPOSITE -DUSE_USB_FS |   -DUSBD_USE_CDC_COMPOSITE -DUSE_USB_FS | ||||||
| extra_scripts     = ${common.extra_scripts} | extra_scripts     = ${common.extra_scripts} | ||||||
|   pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py |   pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py | ||||||
| lib_ignore        = SoftwareSerial |  | ||||||
|  |  | ||||||
| # | # | ||||||
| # BigTreeTech SKR Pro (STM32F407ZGT6 ARM Cortex-M4) | # BigTreeTech SKR Pro (STM32F407ZGT6 ARM Cortex-M4) | ||||||
| @@ -1138,8 +1137,7 @@ platform          = ${common_stm32.platform} | |||||||
| extends           = common_stm32 | extends           = common_stm32 | ||||||
| board             = BigTree_SKR_Pro | board             = BigTree_SKR_Pro | ||||||
| build_flags       = ${common_stm32.build_flags} | build_flags       = ${common_stm32.build_flags} | ||||||
|   -DUSB_PRODUCT=\"STM32F407ZG\" |   -DSTM32F407_5ZX -DVECT_TAB_OFFSET=0x8000 | ||||||
|   -DTARGET_STM32F4 -DSTM32F407_5ZX -DVECT_TAB_OFFSET=0x8000 |  | ||||||
| extra_scripts     = ${common.extra_scripts} | extra_scripts     = ${common.extra_scripts} | ||||||
|   pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py |   pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py | ||||||
| #upload_protocol   = stlink | #upload_protocol   = stlink | ||||||
| @@ -1151,14 +1149,13 @@ debug_init_break  = | |||||||
| # Bigtreetech GTR V1.0 (STM32F407IGT6 ARM Cortex-M4) | # Bigtreetech GTR V1.0 (STM32F407IGT6 ARM Cortex-M4) | ||||||
| # | # | ||||||
| [env:BIGTREE_GTR_V1_0] | [env:BIGTREE_GTR_V1_0] | ||||||
| platform          = ststm32@>=5.7.0,<6.2.0 | platform          = ${common_stm32.platform} | ||||||
| extends           = common_stm32 | extends           = common_stm32 | ||||||
| board             = BigTree_GTR_v1 | board             = BigTree_GTR_v1 | ||||||
| extra_scripts     = ${common.extra_scripts} | extra_scripts     = ${common.extra_scripts} | ||||||
|   pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py |   pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py | ||||||
| build_flags       = ${common_stm32.build_flags} | build_flags       = ${common_stm32.build_flags} | ||||||
|   -DUSB_PRODUCT=\"STM32F407IG\" |   -DSTM32F407IX -DVECT_TAB_OFFSET=0x8000 | ||||||
|   -DTARGET_STM32F4 -DSTM32F407IX -DVECT_TAB_OFFSET=0x8000 |  | ||||||
|  |  | ||||||
| # | # | ||||||
| # BigTreeTech BTT002 V1.0 (STM32F407VGT6 ARM Cortex-M4) | # BigTreeTech BTT002 V1.0 (STM32F407VGT6 ARM Cortex-M4) | ||||||
| @@ -1168,8 +1165,7 @@ platform          = ${common_stm32.platform} | |||||||
| extends           = common_stm32 | extends           = common_stm32 | ||||||
| board             = BigTree_Btt002 | board             = BigTree_Btt002 | ||||||
| build_flags       = ${common_stm32.build_flags} | build_flags       = ${common_stm32.build_flags} | ||||||
|   -DUSB_PRODUCT=\"STM32F407VG\" |   -DSTM32F407_5VX -DVECT_TAB_OFFSET=0x8000 | ||||||
|   -DTARGET_STM32F4 -DSTM32F407_5VX -DVECT_TAB_OFFSET=0x8000 |  | ||||||
|   -DHAVE_HWSERIAL2 |   -DHAVE_HWSERIAL2 | ||||||
|   -DHAVE_HWSERIAL3 |   -DHAVE_HWSERIAL3 | ||||||
|   -DPIN_SERIAL2_RX=PD_6 |   -DPIN_SERIAL2_RX=PD_6 | ||||||
| @@ -1226,10 +1222,10 @@ platform      = ${common_stm32.platform} | |||||||
| extends       = common_stm32 | extends       = common_stm32 | ||||||
| build_flags   = ${common_stm32.build_flags} | build_flags   = ${common_stm32.build_flags} | ||||||
|   -Os |   -Os | ||||||
|   "-DUSB_PRODUCT=\"RUMBA32\"" |  | ||||||
|   -DHAL_PCD_MODULE_ENABLED |   -DHAL_PCD_MODULE_ENABLED | ||||||
|   -DDISABLE_GENERIC_SERIALUSB |   -DDISABLE_GENERIC_SERIALUSB | ||||||
|   -DHAL_UART_MODULE_ENABLED |   -DHAL_UART_MODULE_ENABLED | ||||||
|  |   -DTIMER_SERIAL=TIM9 | ||||||
| board         = rumba32_f446ve | board         = rumba32_f446ve | ||||||
| upload_protocol = dfu | upload_protocol = dfu | ||||||
| monitor_speed = 500000 | monitor_speed = 500000 | ||||||
|   | |||||||
		Reference in New Issue
	
	Block a user