Reorganize HAL (#14832)

This commit is contained in:
Scott Lahteine 2019-09-02 19:49:58 -05:00 committed by GitHub
parent cdd5056aba
commit 75efa3cdac
Signed by: GitHub
GPG key ID: 4AEE18F83AFDEB23
142 changed files with 547 additions and 422 deletions

View file

@ -240,10 +240,10 @@ jobs:
build_marlin_pio ./ ${TEST_PLATFORM}
restore_configs
echo testing STM32F1 targets...
export TEST_PLATFORM="-e STM32F1"
export TEST_PLATFORM="-e STM32F103R"
restore_configs
echo use_example_configs STM32/STM32F10
use_example_configs STM32/STM32F10
echo use_example_configs STM32/STM32F103R
use_example_configs STM32/STM32F103R
build_marlin_pio ./ ${TEST_PLATFORM}
restore_configs
echo use_example_configs STM32/stm32f103ret6

View file

@ -9,37 +9,46 @@ notifications:
email: false
env:
- TEST_PLATFORM="ARMED"
#- TEST_PLATFORM="at90usb1286_cdc"
#- TEST_PLATFORM="at90usb1286_dfu"
# Base Environments
- TEST_PLATFORM="DUE"
- TEST_PLATFORM="esp32"
- TEST_PLATFORM="fysetc_f6_13"
- TEST_PLATFORM="jgaurora_a5s_a1"
- TEST_PLATFORM="linux_native"
- TEST_PLATFORM="LPC1768"
- TEST_PLATFORM="LPC1769"
#- TEST_PLATFORM="malyanm200"
- TEST_PLATFORM="megaatmega1280"
- TEST_PLATFORM="megaatmega2560"
- TEST_PLATFORM="SAMD51_grandcentral_m4"
- TEST_PLATFORM="STM32F103R"
- TEST_PLATFORM="teensy31"
- TEST_PLATFORM="teensy35"
# Extended AVR Environments
- TEST_PLATFORM="fysetc_f6_13"
- TEST_PLATFORM="megaatmega1280"
- TEST_PLATFORM="rambo"
- TEST_PLATFORM="sanguino_atmega1284p"
- TEST_PLATFORM="sanguino_atmega644p"
# Extended STM32 Environments
- TEST_PLATFORM="ARMED"
- TEST_PLATFORM="BIGTREE_BTT002"
- TEST_PLATFORM="BIGTREE_SKR_PRO"
- TEST_PLATFORM="STM32F103R_bigtree"
- TEST_PLATFORM="jgaurora_a5s_a1"
- TEST_PLATFORM="STM32F103V_longer"
- TEST_PLATFORM="STM32F407VE_black"
# Non-working environment tests
#- TEST_PLATFORM="at90usb1286_cdc"
#- TEST_PLATFORM="at90usb1286_dfu"
#- TEST_PLATFORM="malyanm200"
#- TEST_PLATFORM="mks_robin"
#- TEST_PLATFORM="mks_robin_lite"
#- TEST_PLATFORM="mks_robin_mini"
#- TEST_PLATFORM="mks_robin_nano"
- TEST_PLATFORM="rambo"
- TEST_PLATFORM="adafruit_grandcentral_m4"
- TEST_PLATFORM="sanguino_atmega1284p"
- TEST_PLATFORM="sanguino_atmega644p"
- TEST_PLATFORM="STM32F1"
- TEST_PLATFORM="BIGTREE_SKR_MINI"
#- TEST_PLATFORM="fysetc_STM32F1"
- TEST_PLATFORM="alfawise_U20"
#- TEST_PLATFORM="STM32F103R_bigtree"
#- TEST_PLATFORM="STM32F103R_fysetc"
#- TEST_PLATFORM="STM32F4"
- TEST_PLATFORM="black_stm32f407ve"
- TEST_PLATFORM="BIGTREE_SKR_PRO"
#- TEST_PLATFORM="STM32F7"
- TEST_PLATFORM="teensy31"
- TEST_PLATFORM="teensy35"
before_install:
#

View file

@ -20,9 +20,9 @@
#include "../shared/Marduino.h"
#include "../shared/HAL_SPI.h"
#include "fastio_AVR.h"
#include "watchdog_AVR.h"
#include "math_AVR.h"
#include "fastio.h"
#include "watchdog.h"
#include "math.h"
#ifdef USBCON
#include "HardwareSerial.h"

View file

@ -26,7 +26,7 @@
#ifdef __AVR__
#include "fastio_AVR.h"
#include "fastio.h"
#ifdef FASTIO_EXT_START

View file

@ -29,7 +29,7 @@
* Logical Pin : 00 01 02 03 04 05 06 07 08 09 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 | 78 79 80 xx xx 84 85 71 70 xx xx xx xx xx 81 82 83 xx xx 72 72 75 76 77 74 xx xx xx xx xx
*/
#include "../fastio_AVR.h"
#include "../fastio.h"
// change for your board
#define DEBUG_LED DIO21

View file

@ -28,7 +28,7 @@
* Port: A0 A1 A2 A3 A4 A5 A6 A7 B0 B1 B2 B3 B4 B5 B6 B7 C0 C1 C2 C3 C4 C5 C6 C7 D0 D1 D2 D3 D4 D5 D6 D7 E0 E1 E2 E3 E4 E5 E6 E7 F0 F1 F2 F3 F4 F5 F6 F7 G0 G1 G2 G3 G4 G5
*/
#include "../fastio_AVR.h"
#include "../fastio.h"
// change for your board
#define DEBUG_LED DIO46

View file

@ -28,7 +28,7 @@
* Port: B0 B1 B2 B3 B4 B5 C0 C1 C2 C3 C4 C5 C6 C7 D0 D1 D2 D3 D4 D5 D6 D7
*/
#include "../fastio_AVR.h"
#include "../fastio.h"
#define DEBUG_LED AIO5

View file

@ -54,7 +54,7 @@
* +--------+
*/
#include "../fastio_AVR.h"
#include "../fastio.h"
#define DEBUG_LED DIO0

View file

@ -29,7 +29,7 @@
* The logical pins 46 and 47 are not supported by Teensyduino, but are supported below as E2 and E3
*/
#include "../fastio_AVR.h"
#include "../fastio.h"
// change for your board
#define DEBUG_LED DIO31 /* led D5 red */

View file

@ -26,7 +26,7 @@
#if ENABLED(USE_WATCHDOG)
#include "watchdog_AVR.h"
#include "watchdog.h"
#include "../../Marlin.h"

View file

@ -32,9 +32,9 @@
#include "../shared/Marduino.h"
#include "../shared/math_32bit.h"
#include "../shared/HAL_SPI.h"
#include "fastio_Due.h"
#include "watchdog_Due.h"
#include "HAL_timers_Due.h"
#include "fastio.h"
#include "watchdog.h"
#include "timers.h"
#include <stdint.h>
@ -58,8 +58,8 @@
#define NUM_SERIAL 1
#endif
#include "MarlinSerial_Due.h"
#include "MarlinSerialUSB_Due.h"
#include "MarlinSerial.h"
#include "MarlinSerialUSB.h"
// On AVR this is in math.h?
#define square(x) ((x)*(x))

View file

@ -34,7 +34,7 @@
#include "../../inc/MarlinConfig.h"
#include "HAL.h"
#include "InterruptVectors_Due.h"
#include "InterruptVectors.h"
/* The relocated Exception/Interrupt Table - According to the ARM
reference manual, alignment to 128 bytes should suffice, but in

View file

@ -29,8 +29,8 @@
#include "../../inc/MarlinConfig.h"
#include "MarlinSerial_Due.h"
#include "InterruptVectors_Due.h"
#include "MarlinSerial.h"
#include "InterruptVectors.h"
#include "../../Marlin.h"
template<typename Cfg> typename MarlinSerial<Cfg>::ring_buffer_r MarlinSerial<Cfg>::rx_buffer = { 0, 0, { 0 } };

View file

@ -31,7 +31,7 @@
#if SERIAL_PORT == -1
#include "MarlinSerialUSB_Due.h"
#include "MarlinSerialUSB.h"
#if ENABLED(EMERGENCY_PARSER)
#include "../../feature/emergency_parser.h"

View file

@ -31,7 +31,7 @@
#include "../../inc/MarlinConfig.h"
#include "HAL.h"
#include "HAL_timers_Due.h"
#include "timers.h"
static pin_t tone_pin;
volatile static int32_t toggles;

View file

@ -71,7 +71,7 @@ void spiSend(uint8_t b);
void spiSend(const uint8_t* buf, size_t n);
#include "../../shared/Marduino.h"
#include "../fastio_Due.h"
#include "../fastio.h"
void u8g_SetPIOutput_DUE_hw_spi(u8g_t *u8g, uint8_t pin_index) {
PIO_Configure(g_APinDescription[u8g->pin_list[pin_index]].pPort, PIO_OUTPUT_1,

View file

@ -34,7 +34,7 @@
#include "../../inc/MarlinConfig.h"
#include "HAL.h"
#include "HAL_timers_Due.h"
#include "timers.h"
// ------------------------
// Local defines

View file

@ -24,7 +24,7 @@
#include "../../inc/MarlinConfig.h"
#include "../../Marlin.h"
#include "watchdog_Due.h"
#include "watchdog.h"
// Override Arduino runtime to either config or disable the watchdog
//

View file

@ -23,7 +23,7 @@
#ifdef ARDUINO_ARCH_ESP32
#include "HAL.h"
#include "HAL_timers_ESP32.h"
#include "timers.h"
#include <rom/rtc.h>
#include <driver/adc.h>
#include <esp_adc_cal.h>

View file

@ -30,11 +30,11 @@
#include "../shared/math_32bit.h"
#include "../shared/HAL_SPI.h"
#include "fastio_ESP32.h"
#include "watchdog_ESP32.h"
#include "fastio.h"
#include "watchdog.h"
#include "i2s.h"
#include "HAL_timers_ESP32.h"
#include "timers.h"
#include "WebSocketSerial.h"
#include "FlushableHardwareSerial.h"

View file

@ -25,7 +25,7 @@
#if HAS_SERVOS
#include "HAL_Servo_ESP32.h"
#include "Servo.h"
// Adjacent channels (0/1, 2/3 etc.) share the same timer and therefore the same frequency and resolution settings on ESP32,
// so we only allocate servo channels up high to avoid side effects with regards to analogWrite (fans, leds, laser pwm etc.)

View file

@ -30,7 +30,7 @@
#include "HAL.h"
#include "HAL_timers_ESP32.h"
#include "timers.h"
// ------------------------
// Local defines

View file

@ -26,7 +26,7 @@
#if ENABLED(USE_WATCHDOG)
#include "watchdog_ESP32.h"
#include "watchdog.h"
void watchdogSetup(void) {
// do whatever. don't remove this function.

View file

@ -56,7 +56,7 @@ uint8_t _getc();
#include "../shared/HAL_SPI.h"
#include "fastio.h"
#include "watchdog.h"
#include "HAL_timers.h"
#include "timers.h"
#include "serial.h"
#define SHARED_SERVOS HAS_SERVOS

View file

@ -90,7 +90,7 @@ void eeprom_read_block(void *__dst, const void *__src, size_t __n) { }
void eeprom_update_block(const void *__src, void *__dst, size_t __n) { }
char *dtostrf (double __val, signed char __width, unsigned char __prec, char *__s) {
char *dtostrf(double __val, signed char __width, unsigned char __prec, char *__s) {
char format_string[20];
snprintf(format_string, 20, "%%%d.%df", __width, __prec);
sprintf(__s, format_string, __val);

View file

@ -109,13 +109,13 @@ uint16_t analogRead(pin_t);
// EEPROM
void eeprom_write_byte(unsigned char *pos, unsigned char value);
unsigned char eeprom_read_byte(unsigned char *pos);
void eeprom_read_block (void *__dst, const void *__src, size_t __n);
void eeprom_update_block (const void *__src, void *__dst, size_t __n);
void eeprom_read_block(void *__dst, const void *__src, size_t __n);
void eeprom_update_block(const void *__src, void *__dst, size_t __n);
int32_t random(int32_t);
int32_t random(int32_t, int32_t);
void randomSeed(uint32_t);
char *dtostrf (double __val, signed char __width, unsigned char __prec, char *__s);
char *dtostrf(double __val, signed char __width, unsigned char __prec, char *__s);
int map(uint16_t x, uint16_t in_min, uint16_t in_max, uint16_t out_min, uint16_t out_max);

View file

@ -25,7 +25,7 @@
#include "hardware/Timer.h"
#include "../../inc/MarlinConfig.h"
#include "HAL_timers.h"
#include "timers.h"
/**
* Use POSIX signals to attempt to emulate Interrupts

View file

@ -41,7 +41,7 @@ extern "C" volatile uint32_t _millis;
#include "../shared/HAL_SPI.h"
#include "fastio.h"
#include "watchdog.h"
#include "HAL_timers.h"
#include "timers.h"
#include "MarlinSerial.h"
#include <adc.h>

View file

@ -38,7 +38,7 @@ extern "C" {
#include "../../sd/cardreader.h"
#include "../../inc/MarlinConfig.h"
#include "HAL.h"
#include "HAL_timers.h"
#include "timers.h"
extern uint32_t MSC_SD_Init(uint8_t pdrv);
extern "C" int isLPC1769();

View file

@ -29,7 +29,7 @@
#ifdef TARGET_LPC1768
#include "../../inc/MarlinConfig.h"
#include "HAL_timers.h"
#include "timers.h"
void HAL_timer_init(void) {
SBI(LPC_SC->PCONP, SBIT_TIMER0); // Power ON Timer 0

View file

@ -25,9 +25,9 @@
#include "../shared/Marduino.h"
#include "../shared/math_32bit.h"
#include "../shared/HAL_SPI.h"
#include "fastio_SAMD51.h"
#include "watchdog_SAMD51.h"
#include "HAL_timers_SAMD51.h"
#include "fastio.h"
#include "watchdog.h"
#include "timers.h"
#ifdef ADAFRUIT_GRAND_CENTRAL_M4
#include "MarlinSerial_AGCM4.h"

View file

@ -33,7 +33,7 @@
#include "../shared/servo.h"
#include "../shared/servo_private.h"
#include "SAMD51.h"
#include "HAL_timers_SAMD51.h"
#include "timers.h"
#define __TC_GCLK_ID(t) TC##t##_GCLK_ID
#define _TC_GCLK_ID(t) __TC_GCLK_ID(t)

View file

@ -25,7 +25,7 @@
// Includes
// --------------------------------------------------------------------------
#include "../../inc/MarlinConfig.h"
#include "HAL_timers_SAMD51.h"
#include "timers.h"
// --------------------------------------------------------------------------
// Local defines

View file

@ -25,7 +25,7 @@
#if ENABLED(USE_WATCHDOG)
#include "watchdog_SAMD51.h"
#include "watchdog.h"
void watchdog_init(void) {
// The low-power oscillator used by the WDT runs at 32,768 Hz with

View file

@ -28,8 +28,8 @@
#include "../shared/Marduino.h"
#include "../shared/math_32bit.h"
#include "../shared/HAL_SPI.h"
#include "fastio_STM32.h"
#include "watchdog_STM32.h"
#include "fastio.h"
#include "watchdog.h"
#include "../../inc/MarlinConfigPre.h"
@ -96,7 +96,7 @@
#define NUM_SERIAL 1
#endif
#include "HAL_timers_STM32.h"
#include "timers.h"
/**
* TODO: review this to return 1 for pins that are not analog input

View file

@ -26,7 +26,7 @@
#if HAS_SERVOS
#include "HAL_Servo_STM32.h"
#include "Servo.h"
uint8_t servoPin[MAX_SERVOS] = { 0 };

View file

@ -29,9 +29,11 @@
#ifdef BOARD_NR_GPIO_PINS // Only in STM32GENERIC (Maple)
#ifdef __STM32F1__
#include "../HAL_STM32F1/fastio_STM32F1.h"
#include "../HAL_STM32F1/fastio.h"
#elif defined(STM32F4) || defined(STM32F7)
#include "../HAL_STM32_F4_F7/fastio_STM32_F4_F7.h"
#include "../HAL_STM32_F4_F7/fastio.h"
#else
#include "fastio.h"
#endif
extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS];

View file

@ -24,7 +24,7 @@
#include "HAL.h"
#include "HAL_timers_STM32.h"
#include "timers.h"
// ------------------------
// Local defines

View file

@ -28,7 +28,7 @@
#include "../../inc/MarlinConfig.h"
#include "watchdog_STM32.h"
#include "watchdog.h"
#include <IWatchdog.h>
void watchdog_init() { IWatchdog.begin(4000000); } // 4 sec timeout

View file

@ -33,10 +33,10 @@
#include "../shared/math_32bit.h"
#include "../shared/HAL_SPI.h"
#include "fastio_STM32F1.h"
#include "watchdog_STM32F1.h"
#include "fastio.h"
#include "watchdog.h"
#include "HAL_timers_STM32F1.h"
#include "timers.h"
#include <stdint.h>
#include <util/atomic.h>

View file

@ -33,7 +33,7 @@
#ifdef __STM32F1__
#include "../../inc/MarlinConfig.h"
#include "SPI.h"
#include <SPI.h>
// ------------------------
// Public functions

View file

@ -31,7 +31,7 @@
#ifdef __STM32F1__
#include "SPI.h"
#include <SPI.h>
#include <libmaple/timer.h>
#include <libmaple/util.h>

View file

@ -29,8 +29,8 @@
uint8_t ServoCount = 0;
#include "HAL_Servo_STM32F1.h"
#include "HAL_timers_STM32F1.h"
#include "Servo.h"
#include "timers.h"
//#include "Servo.h"

View file

@ -29,7 +29,7 @@
#if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY)
#include "HAL_sdio_STM32F1.h"
#include "sdio.h"
SDIO_CardInfoTypeDef SdCard;

View file

@ -28,7 +28,7 @@
#include "HAL.h"
#include "HAL_timers_STM32F1.h"
#include "timers.h"
// ------------------------
// Local defines

View file

@ -31,7 +31,7 @@
#if ENABLED(USE_WATCHDOG)
#include <libmaple/iwdg.h>
#include "watchdog_STM32F1.h"
#include "watchdog.h"
void watchdog_reset() {
#if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED)

View file

@ -28,10 +28,10 @@
#include "../shared/math_32bit.h"
#include "../shared/HAL_SPI.h"
#include "fastio_STM32_F4_F7.h"
#include "watchdog_STM32_F4_F7.h"
#include "fastio.h"
#include "watchdog.h"
#include "HAL_timers_STM32_F4_F7.h"
#include "timers.h"
#include "../../inc/MarlinConfigPre.h"

View file

@ -32,12 +32,12 @@
#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7))
#include "HAL.h"
#include "../shared/HAL_SPI.h"
#include <pins_arduino.h>
#include "spi_pins.h"
#include "../../core/macros.h"
#include "../../inc/MarlinConfig.h"
#include <SPI.h>
#include <pins_arduino.h>
#include "../shared/HAL_SPI.h"
#include "spi_pins.h"
// ------------------------
// Public Variables
@ -72,7 +72,7 @@ static SPISettings spiConfig;
* @details Only configures SS pin since libmaple creates and initialize the SPI object
*/
void spiBegin(void) {
#if !PIN_EXISTS(SS)
#if !defined(SS_PIN) || SS_PIN < 0
#error SS_PIN not defined!
#endif

View file

@ -23,7 +23,7 @@
#if defined(STM32GENERIC) && defined(STM32F4)
#include "../HAL.h"
#include "HAL_timers_STM32F4.h"
#include "timers.h"
// ------------------------
// Local defines

View file

@ -23,7 +23,7 @@
#if defined(STM32GENERIC) && defined(STM32F7)
#include "../HAL.h"
#include "HAL_timers_STM32F7.h"
#include "timers.h"
// ------------------------
// Local defines

View file

@ -27,7 +27,7 @@
#if HAS_SERVOS
#include "HAL_Servo_STM32_F4_F7.h"
#include "Servo.h"
int8_t libServo::attach(const int pin) {
if (this->servoIndex >= MAX_SERVOS) return -1;

View file

@ -0,0 +1,310 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
* Copyright (c) 2017 Victor Perez
*
* This program 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.
*
* This program 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 this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Fast I/O interfaces for STM32F4/7
* These use GPIO functions instead of Direct Port Manipulation, as on AVR.
*/
#ifndef PWM
#define PWM OUTPUT
#endif
#define READ(IO) digitalRead(IO)
#define WRITE(IO,V) digitalWrite(IO,V)
#define _GET_MODE(IO)
#define _SET_MODE(IO,M) pinMode(IO, M)
#define _SET_OUTPUT(IO) pinMode(IO, OUTPUT) /*!< Output Push Pull Mode & GPIO_NOPULL */
#define OUT_WRITE(IO,V) do{ _SET_OUTPUT(IO); WRITE(IO,V); }while(0)
#define SET_INPUT(IO) _SET_MODE(IO, INPUT) /*!< Input Floating Mode */
#define SET_INPUT_PULLUP(IO) _SET_MODE(IO, INPUT_PULLUP) /*!< Input with Pull-up activation */
#define SET_INPUT_PULLDOWN(IO) _SET_MODE(IO, INPUT_PULLDOWN) /*!< Input with Pull-down activation */
#define SET_OUTPUT(IO) OUT_WRITE(IO, LOW)
#define SET_PWM(IO) _SET_MODE(IO, PWM)
#define TOGGLE(IO) OUT_WRITE(IO, !READ(IO))
#define IS_INPUT(IO)
#define IS_OUTPUT(IO)
#define PWM_PIN(P) true
// digitalRead/Write wrappers
#define extDigitalRead(IO) digitalRead(IO)
#define extDigitalWrite(IO,V) digitalWrite(IO,V)
//
// Pins Definitions
//
#define PORTA 0
#define PORTB 1
#define PORTC 2
#define PORTD 3
#define PORTE 4
#define PORTF 5
#define PORTG 6
#define _STM32_PIN(P,PN) ((PORT##P * 16) + PN)
#undef PA0
#define PA0 _STM32_PIN(A, 0)
#undef PA1
#define PA1 _STM32_PIN(A, 1)
#undef PA2
#define PA2 _STM32_PIN(A, 2)
#undef PA3
#define PA3 _STM32_PIN(A, 3)
#undef PA4
#define PA4 _STM32_PIN(A, 4)
#undef PA5
#define PA5 _STM32_PIN(A, 5)
#undef PA6
#define PA6 _STM32_PIN(A, 6)
#undef PA7
#define PA7 _STM32_PIN(A, 7)
#undef PA8
#define PA8 _STM32_PIN(A, 8)
#undef PA9
#define PA9 _STM32_PIN(A, 9)
#undef PA10
#define PA10 _STM32_PIN(A, 10)
#undef PA11
#define PA11 _STM32_PIN(A, 11)
#undef PA12
#define PA12 _STM32_PIN(A, 12)
#undef PA13
#define PA13 _STM32_PIN(A, 13)
#undef PA14
#define PA14 _STM32_PIN(A, 14)
#undef PA15
#define PA15 _STM32_PIN(A, 15)
#undef PB0
#define PB0 _STM32_PIN(B, 0)
#undef PB1
#define PB1 _STM32_PIN(B, 1)
#undef PB2
#define PB2 _STM32_PIN(B, 2)
#undef PB3
#define PB3 _STM32_PIN(B, 3)
#undef PB4
#define PB4 _STM32_PIN(B, 4)
#undef PB5
#define PB5 _STM32_PIN(B, 5)
#undef PB6
#define PB6 _STM32_PIN(B, 6)
#undef PB7
#define PB7 _STM32_PIN(B, 7)
#undef PB8
#define PB8 _STM32_PIN(B, 8)
#undef PB9
#define PB9 _STM32_PIN(B, 9)
#undef PB10
#define PB10 _STM32_PIN(B, 10)
#undef PB11
#define PB11 _STM32_PIN(B, 11)
#undef PB12
#define PB12 _STM32_PIN(B, 12)
#undef PB13
#define PB13 _STM32_PIN(B, 13)
#undef PB14
#define PB14 _STM32_PIN(B, 14)
#undef PB15
#define PB15 _STM32_PIN(B, 15)
#undef PC0
#define PC0 _STM32_PIN(C, 0)
#undef PC1
#define PC1 _STM32_PIN(C, 1)
#undef PC2
#define PC2 _STM32_PIN(C, 2)
#undef PC3
#define PC3 _STM32_PIN(C, 3)
#undef PC4
#define PC4 _STM32_PIN(C, 4)
#undef PC5
#define PC5 _STM32_PIN(C, 5)
#undef PC6
#define PC6 _STM32_PIN(C, 6)
#undef PC7
#define PC7 _STM32_PIN(C, 7)
#undef PC8
#define PC8 _STM32_PIN(C, 8)
#undef PC9
#define PC9 _STM32_PIN(C, 9)
#undef PC10
#define PC10 _STM32_PIN(C, 10)
#undef PC11
#define PC11 _STM32_PIN(C, 11)
#undef PC12
#define PC12 _STM32_PIN(C, 12)
#undef PC13
#define PC13 _STM32_PIN(C, 13)
#undef PC14
#define PC14 _STM32_PIN(C, 14)
#undef PC15
#define PC15 _STM32_PIN(C, 15)
#undef PD0
#define PD0 _STM32_PIN(D, 0)
#undef PD1
#define PD1 _STM32_PIN(D, 1)
#undef PD2
#define PD2 _STM32_PIN(D, 2)
#undef PD3
#define PD3 _STM32_PIN(D, 3)
#undef PD4
#define PD4 _STM32_PIN(D, 4)
#undef PD5
#define PD5 _STM32_PIN(D, 5)
#undef PD6
#define PD6 _STM32_PIN(D, 6)
#undef PD7
#define PD7 _STM32_PIN(D, 7)
#undef PD8
#define PD8 _STM32_PIN(D, 8)
#undef PD9
#define PD9 _STM32_PIN(D, 9)
#undef PD10
#define PD10 _STM32_PIN(D, 10)
#undef PD11
#define PD11 _STM32_PIN(D, 11)
#undef PD12
#define PD12 _STM32_PIN(D, 12)
#undef PD13
#define PD13 _STM32_PIN(D, 13)
#undef PD14
#define PD14 _STM32_PIN(D, 14)
#undef PD15
#define PD15 _STM32_PIN(D, 15)
#undef PE0
#define PE0 _STM32_PIN(E, 0)
#undef PE1
#define PE1 _STM32_PIN(E, 1)
#undef PE2
#define PE2 _STM32_PIN(E, 2)
#undef PE3
#define PE3 _STM32_PIN(E, 3)
#undef PE4
#define PE4 _STM32_PIN(E, 4)
#undef PE5
#define PE5 _STM32_PIN(E, 5)
#undef PE6
#define PE6 _STM32_PIN(E, 6)
#undef PE7
#define PE7 _STM32_PIN(E, 7)
#undef PE8
#define PE8 _STM32_PIN(E, 8)
#undef PE9
#define PE9 _STM32_PIN(E, 9)
#undef PE10
#define PE10 _STM32_PIN(E, 10)
#undef PE11
#define PE11 _STM32_PIN(E, 11)
#undef PE12
#define PE12 _STM32_PIN(E, 12)
#undef PE13
#define PE13 _STM32_PIN(E, 13)
#undef PE14
#define PE14 _STM32_PIN(E, 14)
#undef PE15
#define PE15 _STM32_PIN(E, 15)
#ifdef STM32F7
#undef PORTF
#define PORTF 5
#undef PF0
#define PF0 _STM32_PIN(F, 0)
#undef PF1
#define PF1 _STM32_PIN(F, 1)
#undef PF2
#define PF2 _STM32_PIN(F, 2)
#undef PF3
#define PF3 _STM32_PIN(F, 3)
#undef PF4
#define PF4 _STM32_PIN(F, 4)
#undef PF5
#define PF5 _STM32_PIN(F, 5)
#undef PF6
#define PF6 _STM32_PIN(F, 6)
#undef PF7
#define PF7 _STM32_PIN(F, 7)
#undef PF8
#define PF8 _STM32_PIN(F, 8)
#undef PF9
#define PF9 _STM32_PIN(F, 9)
#undef PF10
#define PF10 _STM32_PIN(F, 10)
#undef PF11
#define PF11 _STM32_PIN(F, 11)
#undef PF12
#define PF12 _STM32_PIN(F, 12)
#undef PF13
#define PF13 _STM32_PIN(F, 13)
#undef PF14
#define PF14 _STM32_PIN(F, 14)
#undef PF15
#define PF15 _STM32_PIN(F, 15)
#undef PORTG
#define PORTG 6
#undef PG0
#define PG0 _STM32_PIN(G, 0)
#undef PG1
#define PG1 _STM32_PIN(G, 1)
#undef PG2
#define PG2 _STM32_PIN(G, 2)
#undef PG3
#define PG3 _STM32_PIN(G, 3)
#undef PG4
#define PG4 _STM32_PIN(G, 4)
#undef PG5
#define PG5 _STM32_PIN(G, 5)
#undef PG6
#define PG6 _STM32_PIN(G, 6)
#undef PG7
#define PG7 _STM32_PIN(G, 7)
#undef PG8
#define PG8 _STM32_PIN(G, 8)
#undef PG9
#define PG9 _STM32_PIN(G, 9)
#undef PG10
#define PG10 _STM32_PIN(G, 10)
#undef PG11
#define PG11 _STM32_PIN(G, 11)
#undef PG12
#define PG12 _STM32_PIN(G, 12)
#undef PG13
#define PG13 _STM32_PIN(G, 13)
#undef PG14
#define PG14 _STM32_PIN(G, 14)
#undef PG15
#define PG15 _STM32_PIN(G, 15)
#endif // STM32GENERIC && STM32F7

View file

@ -1,210 +0,0 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
* Copyright (c) 2017 Victor Perez
*
* This program 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.
*
* This program 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 this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Fast I/O interfaces for STM32F4/7
* These use GPIO functions instead of Direct Port Manipulation, as on AVR.
*/
#ifndef PWM
#define PWM OUTPUT
#endif
#define READ(IO) digitalRead(IO)
#define WRITE(IO,V) digitalWrite(IO,V)
#define _GET_MODE(IO)
#define _SET_MODE(IO,M) pinMode(IO, M)
#define _SET_OUTPUT(IO) pinMode(IO, OUTPUT) /*!< Output Push Pull Mode & GPIO_NOPULL */
#define OUT_WRITE(IO,V) do{ _SET_OUTPUT(IO); WRITE(IO,V); }while(0)
#define SET_INPUT(IO) _SET_MODE(IO, INPUT) /*!< Input Floating Mode */
#define SET_INPUT_PULLUP(IO) _SET_MODE(IO, INPUT_PULLUP) /*!< Input with Pull-up activation */
#define SET_INPUT_PULLDOWN(IO) _SET_MODE(IO, INPUT_PULLDOWN) /*!< Input with Pull-down activation */
#define SET_OUTPUT(IO) OUT_WRITE(IO, LOW)
#define SET_PWM(IO) _SET_MODE(IO, PWM)
#define TOGGLE(IO) OUT_WRITE(IO, !READ(IO))
#define IS_INPUT(IO)
#define IS_OUTPUT(IO)
#define PWM_PIN(P) true
// digitalRead/Write wrappers
#define extDigitalRead(IO) digitalRead(IO)
#define extDigitalWrite(IO,V) digitalWrite(IO,V)
//
// Pins Definitions
//
#define PORTA 0
#define PORTB 1
#define PORTC 2
#define PORTD 3
#define PORTE 4
#define PORTF 5
#define PORTG 6
#define _STM32_PIN(P,PN) ((PORT##P * 16) + PN)
#ifndef PA0
#define PA0 _STM32_PIN(A, 0)
#define PA1 _STM32_PIN(A, 1)
#define PA2 _STM32_PIN(A, 2)
#define PA3 _STM32_PIN(A, 3)
#define PA4 _STM32_PIN(A, 4)
#define PA5 _STM32_PIN(A, 5)
#define PA6 _STM32_PIN(A, 6)
#define PA7 _STM32_PIN(A, 7)
#define PA8 _STM32_PIN(A, 8)
#define PA9 _STM32_PIN(A, 9)
#define PA10 _STM32_PIN(A, 10)
#define PA11 _STM32_PIN(A, 11)
#define PA12 _STM32_PIN(A, 12)
#define PA13 _STM32_PIN(A, 13)
#define PA14 _STM32_PIN(A, 14)
#define PA15 _STM32_PIN(A, 15)
#endif
#ifndef PB0
#define PB0 _STM32_PIN(B, 0)
#define PB1 _STM32_PIN(B, 1)
#define PB2 _STM32_PIN(B, 2)
#define PB3 _STM32_PIN(B, 3)
#define PB4 _STM32_PIN(B, 4)
#define PB5 _STM32_PIN(B, 5)
#define PB6 _STM32_PIN(B, 6)
#define PB7 _STM32_PIN(B, 7)
#define PB8 _STM32_PIN(B, 8)
#define PB9 _STM32_PIN(B, 9)
#define PB10 _STM32_PIN(B, 10)
#define PB11 _STM32_PIN(B, 11)
#define PB12 _STM32_PIN(B, 12)
#define PB13 _STM32_PIN(B, 13)
#define PB14 _STM32_PIN(B, 14)
#define PB15 _STM32_PIN(B, 15)
#endif
#ifndef PC0
#define PC0 _STM32_PIN(C, 0)
#define PC1 _STM32_PIN(C, 1)
#define PC2 _STM32_PIN(C, 2)
#define PC3 _STM32_PIN(C, 3)
#define PC4 _STM32_PIN(C, 4)
#define PC5 _STM32_PIN(C, 5)
#define PC6 _STM32_PIN(C, 6)
#define PC7 _STM32_PIN(C, 7)
#define PC8 _STM32_PIN(C, 8)
#define PC9 _STM32_PIN(C, 9)
#define PC10 _STM32_PIN(C, 10)
#define PC11 _STM32_PIN(C, 11)
#define PC12 _STM32_PIN(C, 12)
#define PC13 _STM32_PIN(C, 13)
#define PC14 _STM32_PIN(C, 14)
#define PC15 _STM32_PIN(C, 15)
#endif
#ifndef PD0
#define PD0 _STM32_PIN(D, 0)
#define PD1 _STM32_PIN(D, 1)
#define PD2 _STM32_PIN(D, 2)
#define PD3 _STM32_PIN(D, 3)
#define PD4 _STM32_PIN(D, 4)
#define PD5 _STM32_PIN(D, 5)
#define PD6 _STM32_PIN(D, 6)
#define PD7 _STM32_PIN(D, 7)
#define PD8 _STM32_PIN(D, 8)
#define PD9 _STM32_PIN(D, 9)
#define PD10 _STM32_PIN(D, 10)
#define PD11 _STM32_PIN(D, 11)
#define PD12 _STM32_PIN(D, 12)
#define PD13 _STM32_PIN(D, 13)
#define PD14 _STM32_PIN(D, 14)
#define PD15 _STM32_PIN(D, 15)
#endif
#ifndef PE0
#define PE0 _STM32_PIN(E, 0)
#define PE1 _STM32_PIN(E, 1)
#define PE2 _STM32_PIN(E, 2)
#define PE3 _STM32_PIN(E, 3)
#define PE4 _STM32_PIN(E, 4)
#define PE5 _STM32_PIN(E, 5)
#define PE6 _STM32_PIN(E, 6)
#define PE7 _STM32_PIN(E, 7)
#define PE8 _STM32_PIN(E, 8)
#define PE9 _STM32_PIN(E, 9)
#define PE10 _STM32_PIN(E, 10)
#define PE11 _STM32_PIN(E, 11)
#define PE12 _STM32_PIN(E, 12)
#define PE13 _STM32_PIN(E, 13)
#define PE14 _STM32_PIN(E, 14)
#define PE15 _STM32_PIN(E, 15)
#endif
#ifdef STM32F7
#ifndef PF0
#define PORTF 5
#define PF0 _STM32_PIN(F, 0)
#define PF1 _STM32_PIN(F, 1)
#define PF2 _STM32_PIN(F, 2)
#define PF3 _STM32_PIN(F, 3)
#define PF4 _STM32_PIN(F, 4)
#define PF5 _STM32_PIN(F, 5)
#define PF6 _STM32_PIN(F, 6)
#define PF7 _STM32_PIN(F, 7)
#define PF8 _STM32_PIN(F, 8)
#define PF9 _STM32_PIN(F, 9)
#define PF10 _STM32_PIN(F, 10)
#define PF11 _STM32_PIN(F, 11)
#define PF12 _STM32_PIN(F, 12)
#define PF13 _STM32_PIN(F, 13)
#define PF14 _STM32_PIN(F, 14)
#define PF15 _STM32_PIN(F, 15)
#endif
#ifndef PG0
#define PORTG 6
#define PG0 _STM32_PIN(G, 0)
#define PG1 _STM32_PIN(G, 1)
#define PG2 _STM32_PIN(G, 2)
#define PG3 _STM32_PIN(G, 3)
#define PG4 _STM32_PIN(G, 4)
#define PG5 _STM32_PIN(G, 5)
#define PG6 _STM32_PIN(G, 6)
#define PG7 _STM32_PIN(G, 7)
#define PG8 _STM32_PIN(G, 8)
#define PG9 _STM32_PIN(G, 9)
#define PG10 _STM32_PIN(G, 10)
#define PG11 _STM32_PIN(G, 11)
#define PG12 _STM32_PIN(G, 12)
#define PG13 _STM32_PIN(G, 13)
#define PG14 _STM32_PIN(G, 14)
#define PG15 _STM32_PIN(G, 15)
#endif
#endif // STM32GENERIC && STM32F7

View file

@ -22,7 +22,7 @@
#pragma once
#ifdef STM32F4
#include "STM32F4/HAL_timers_STM32F4.h"
#include "STM32F4/timers.h"
#else
#include "STM32F7/HAL_timers_STM32F7.h"
#include "STM32F7/timers.h"
#endif

View file

@ -26,7 +26,7 @@
#if ENABLED(USE_WATCHDOG)
#include "watchdog_STM32_F4_F7.h"
#include "watchdog.h"
IWDG_HandleTypeDef hiwdg;

View file

@ -31,10 +31,10 @@
#include "../shared/math_32bit.h"
#include "../shared/HAL_SPI.h"
#include "fastio_Teensy.h"
#include "watchdog_Teensy.h"
#include "fastio.h"
#include "watchdog.h"
#include "HAL_timers_Teensy.h"
#include "timers.h"
#include <stdint.h>

View file

@ -25,7 +25,7 @@
#if HAS_SERVOS
#include "HAL_Servo_Teensy.h"
#include "Servo.h"
uint8_t servoPin[MAX_SERVOS] = { 0 };

View file

@ -27,7 +27,7 @@
#ifdef __MK20DX256__
#include "HAL.h"
#include "HAL_timers_Teensy.h"
#include "timers.h"
/** \brief Instruction Synchronization Barrier
Instruction Synchronization Barrier flushes the pipeline in the processor,

View file

@ -26,7 +26,7 @@
#if ENABLED(USE_WATCHDOG)
#include "watchdog_Teensy.h"
#include "watchdog.h"
void watchdog_init() {
WDOG_TOVALH = 0;

View file

@ -31,10 +31,10 @@
#include "../shared/math_32bit.h"
#include "../shared/HAL_SPI.h"
#include "fastio_Teensy.h"
#include "watchdog_Teensy.h"
#include "fastio.h"
#include "watchdog.h"
#include "HAL_timers_Teensy.h"
#include "timers.h"
#include <stdint.h>
#include <util/atomic.h>

View file

@ -4,7 +4,7 @@
#if HAS_SERVOS
#include "HAL_Servo_Teensy.h"
#include "Servo.h"
uint8_t servoPin[MAX_SERVOS] = { 0 };

View file

@ -28,7 +28,7 @@
#if defined(__MK64FX512__) || defined(__MK66FX1M0__)
#include "HAL.h"
#include "HAL_timers_Teensy.h"
#include "timers.h"
/** \brief Instruction Synchronization Barrier
Instruction Synchronization Barrier flushes the pipeline in the processor,

View file

@ -26,7 +26,7 @@
#if ENABLED(USE_WATCHDOG)
#include "watchdog_Teensy.h"
#include "watchdog.h"
void watchdog_init() {
WDOG_TOVALH = 0;

View file

@ -68,19 +68,19 @@
*/
#if IS_TEENSY32
#include "../HAL_TEENSY31_32/HAL_Servo_Teensy.h"
#include "../HAL_TEENSY31_32/Servo.h"
#elif IS_TEENSY35 || IS_TEENSY36
#include "../HAL_TEENSY35_36/HAL_Servo_Teensy.h"
#include "../HAL_TEENSY35_36/Servo.h"
#elif defined(TARGET_LPC1768)
#include "../HAL_LPC1768/HAL_Servo_LPC1768.h"
#include "../HAL_LPC1768/Servo.h"
#elif defined(__STM32F1__) || defined(TARGET_STM32F1)
#include "../HAL_STM32F1/HAL_Servo_STM32F1.h"
#include "../HAL_STM32F1/Servo.h"
#elif defined(STM32GENERIC) && defined(STM32F4)
#include "../HAL_STM32F4/HAL_Servo_STM32F4.h"
#include "../HAL_STM32_F4_F7/Servo.h"
#elif defined(ARDUINO_ARCH_STM32)
#include "../HAL_STM32/HAL_Servo_STM32.h"
#include "../HAL_STM32/Servo.h"
#elif defined(ARDUINO_ARCH_ESP32)
#include "../HAL_ESP32/HAL_Servo_ESP32.h"
#include "../HAL_ESP32/Servo.h"
#else
#include <stdint.h>

View file

@ -255,9 +255,9 @@
// STM32 ARM Cortex-M3
//
#define BOARD_STM32F1R 4000 // STM32R Libmaple-based STM32F1 controller
#define BOARD_MALYAN_M200 4001 // STM32C8T6 Libmaple-based STM32F1 controller
#define BOARD_STM3R_MINI 4002 // STM32 Libmaple-based STM32F1 controller
#define BOARD_STM32F103R 4000 // STM32F103R Libmaple-based STM32F1 controller
#define BOARD_MALYAN_M200 4001 // STM32C8T6 Libmaple-based STM32F1 controller
#define BOARD_STM3R_MINI 4002 // STM32F103R Libmaple-based STM32F1 controller
#define BOARD_GTM32_PRO_VB 4003 // STM32F103VET6 controller
#define BOARD_MORPHEUS 4004 // STM32F103C8 / STM32F103CB Libmaple-based STM32F1 controller
#define BOARD_CHITU3D 4005 // Chitu3D (STM32F103RET6)

View file

@ -395,6 +395,7 @@
#define BOARD_RURAMPS4D -1002
#define BOARD_FORMBOT_TREX2 -1003
#define BOARD_BIQU_SKR_V1_1 -1004
#define BOARD_STM32F1R -1005
#if MB(MKS_13)
#error "BOARD_MKS_13 has been renamed BOARD_MKS_GEN_13. Please update your configuration."
#elif MB(TRIGORILLA)
@ -405,12 +406,15 @@
#error "FORMBOT_TREX2 has been renamed BOARD_FORMBOT_TREX2PLUS. Please update your configuration."
#elif MB(BIQU_SKR_V1_1)
#error "BOARD_BIQU_SKR_V1_1 has been renamed BOARD_BIGTREE_SKR_V1_1. Please update your configuration."
#elif MB(STM32F1R)
#error "BOARD_STM32F1R has been renamed BOARD_STM32F103R. Please update your configuration."
#endif
#undef BOARD_MKS_13
#undef BOARD_TRIGORILLA
#undef BOARD_RURAMPS4D
#undef BOARD_FORMBOT_TREX2
#undef BOARD_BIQU_SKR_V1_1
#undef BOARD_STM32F1R
/**
* Marlin release, version and default string
@ -1108,6 +1112,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
#error "TOUCH_MI_PROBE requires Z_MIN_PROBE_ENDSTOP_INVERTING to be set to false."
#elif DISABLED(BABYSTEP_ZPROBE_OFFSET)
#error "TOUCH_MI_PROBE requires BABYSTEPPING with BABYSTEP_ZPROBE_OFFSET."
#elif !HAS_RESUME_CONTINUE
#error "TOUCH_MI_PROBE currently requires an LCD controller or EMERGENCY_PARSER."
#endif
#endif

View file

@ -442,18 +442,18 @@
// STM32 ARM Cortex-M3
//
#elif MB(STM32F1R)
#include "stm32/pins_STM32F1R.h" // STM32F1 env:STM32F1
#elif MB(STM32F103R)
#include "stm32/pins_STM32F1R.h" // STM32F1 env:STM32F103R
#elif MB(MALYAN_M200)
#include "stm32/pins_MALYAN_M200.h" // STM32F1 env:malyanm200
#elif MB(STM3R_MINI)
#include "stm32/pins_STM3R_MINI.h" // STM32F1 env:STM32F1
#include "stm32/pins_STM3R_MINI.h" // STM32F1 env:STM32F103R
#elif MB(GTM32_PRO_VB)
#include "stm32/pins_GTM32_PRO_VB.h" // STM32F1 env:STM32F1
#include "stm32/pins_GTM32_PRO_VB.h" // STM32F1 env:STM32F103R
#elif MB(MORPHEUS)
#include "stm32/pins_MORPHEUS.h" // STM32F1 env:STM32F1
#include "stm32/pins_MORPHEUS.h" // STM32F1 env:STM32F103R
#elif MB(CHITU3D)
#include "stm32/pins_CHITU3D.h" // STM32F1 env:STM32F1
#include "stm32/pins_CHITU3D.h" // STM32F1 env:STM32F103R
#elif MB(MKS_ROBIN)
#include "stm32/pins_MKS_ROBIN.h" // STM32F1 env:mks_robin
#elif MB(MKS_ROBIN_MINI)
@ -463,21 +463,21 @@
#elif MB(MKS_ROBIN_LITE)
#include "stm32/pins_MKS_ROBIN_LITE.h" // STM32F1 env:mks_robin_lite
#elif MB(BIGTREE_SKR_MINI_V1_1)
#include "stm32/pins_BIGTREE_SKR_MINI_V1_1.h" // STM32F1 env:BIGTREE_SKR_MINI
#include "stm32/pins_BIGTREE_SKR_MINI_V1_1.h" // STM32F1 env:STM32F103R_bigtree
#elif MB(BIGTREE_SKR_MINI_E3)
#include "stm32/pins_BIGTREE_SKR_MINI_E3.h" // STM32F1 env:BIGTREE_SKR_MINI
#include "stm32/pins_BIGTREE_SKR_MINI_E3.h" // STM32F1 env:STM32F103R_bigtree
#elif MB(BIGTREE_SKR_E3_DIP)
#include "stm32/pins_BIGTREE_SKR_E3_DIP.h" // STM32F1 env:BIGTREE_SKR_MINI
#include "stm32/pins_BIGTREE_SKR_E3_DIP.h" // STM32F1 env:STM32F103R_bigtree
#elif MB(JGAURORA_A5S_A1)
#include "stm32/pins_JGAURORA_A5S_A1.h" // STM32F1 env:jgaurora_a5s_a1
#elif MB(FYSETC_AIO_II)
#include "stm32/pins_FYSETC_AIO_II.h" // STM32F1 env:fysetc_STM32F1
#include "stm32/pins_FYSETC_AIO_II.h" // STM32F1 env:STM32F103R_fysetc
#elif MB(FYSETC_CHEETAH)
#include "stm32/pins_FYSETC_CHEETAH.h" // STM32F1 env:fysetc_STM32F1
#include "stm32/pins_FYSETC_CHEETAH.h" // STM32F1 env:STM32F103R_fysetc
#elif MB(FYSETC_CHEETAH_V12)
#include "stm32/pins_FYSETC_CHEETAH_V12.h" // STM32F1 env:fysetc_STM32F1
#include "stm32/pins_FYSETC_CHEETAH_V12.h" // STM32F1 env:STM32F103R_fysetc
#elif MB(LONGER3D_LK)
#include "stm32/pins_LONGER3D_LK.h" // STM32F1 env:alfawise_U20
#include "stm32/pins_LONGER3D_LK.h" // STM32F1 env:STM32F103V_longer
//
// ARM Cortex-M4F
@ -501,7 +501,7 @@
#elif MB(RUMBA32)
#include "stm32/pins_RUMBA32.h" // STM32F4 env:RUMBA32
#elif MB(BLACK_STM32F407VE)
#include "stm32/pins_BLACK_STM32F407VE.h" // STM32F4 env:black_stm32f407ve
#include "stm32/pins_BLACK_STM32F407VE.h" // STM32F4 env:STM32F407VE_black
#elif MB(STEVAL)
#include "stm32/pins_STEVAL.h" // STM32F4 env:STM32F4
#elif MB(BIGTREE_SKR_PRO_V1_1)
@ -530,7 +530,7 @@
//
#elif MB(AGCM4_RURAMPS4D_13)
#include "samd/pins_AGCM4_RURAMPS4D_13.h" // SAMD51 env:adafruit_grandcentral_m4
#include "samd/pins_AGCM4_RURAMPS4D_13.h" // SAMD51 env:SAMD51_grandcentral_m4
//
// Linux Native Debug board

View file

@ -21,6 +21,10 @@
*/
#pragma once
/**
* To build with Arduino IDE use "Discovery F407VG"
* To build with PlatformIO use environment "STM32F4"
*/
#if !defined(STM32F4) && !defined(STM32F4xx)
#error "Oops! Select an STM32F4 board in 'Tools > Board.'"
#elif HOTENDS > 2 || E_STEPPERS > 2

View file

@ -5,7 +5,7 @@ for define in env['CPPDEFINES']:
if define[0] == "VECT_TAB_ADDR":
env['CPPDEFINES'].remove(define)
env['CPPDEFINES'].append(("VECT_TAB_ADDR", "0x08010000"))
env.Replace(LDSCRIPT_PATH="buildroot/share/PlatformIO/ldscripts/alfawise_Ux0.ld")
env.Replace(LDSCRIPT_PATH="buildroot/share/PlatformIO/ldscripts/longer_STM32.ld")
# Rename ${PROGNAME}.bin and save it as 'project.bin' (No encryption on the Longer3D)
def encrypt(source, target, env):

View file

@ -26,8 +26,8 @@ case $TESTENV in
lpc?(8)) TESTENV='LPC1768' ;;
lpc9) TESTENV='LPC1769' ;;
mega) TESTENV='megaatmega2560' ;;
stm) TESTENV='STM32F1' ;;
f1) TESTENV='STM32F1' ;;
stm) TESTENV='STM32F103R' ;;
f1) TESTENV='STM32F103R' ;;
f4) TESTENV='STM32F4' ;;
f7) TESTENV='STM32F7' ;;
teensy) TESTENV='teensy31' ;;

View file

@ -0,0 +1,18 @@
#!/usr/bin/env bash
#
# Build tests for STM32F407VET6 BigTreeTech BTT002
#
# exit on first failure
set -e
#
# Build with the default configurations
#
restore_configs
opt_set MOTHERBOARD BOARD_BIGTREE_BTT002_V1_0
opt_set SERIAL_PORT 1
exec_test $1 $2 "BigTreeTech BTT002 Default Configuration"
# clean up
restore_configs

View file

@ -1,6 +1,6 @@
#!/usr/bin/env bash
#
# Build tests for STM32F4 BigTree_SKR_Pro
# Build tests for STM32F407ZG BigTreeTech SKR Pro
#
# exit on first failure
@ -12,7 +12,7 @@ set -e
restore_configs
opt_set MOTHERBOARD BOARD_BIGTREE_SKR_PRO_V1_1
opt_set SERIAL_PORT 1
exec_test $1 $2 "Default Configuration"
exec_test $1 $2 "BigTreeTech SKR Pro Default Configuration"
# clean up
restore_configs

View file

@ -9,9 +9,9 @@ set -e
#
# Build with the default configurations
#
restore_configs
opt_set MOTHERBOARD BOARD_RAMPS_14_RE_ARM_EFB
exec_test $1 $2 "Default Configuration"
#restore_configs
#opt_set MOTHERBOARD BOARD_RAMPS_14_RE_ARM_EFB
#exec_test $1 $2 "Default Configuration"
restore_configs
opt_set MOTHERBOARD BOARD_RAMPS_14_RE_ARM_EFB
@ -19,9 +19,9 @@ opt_enable VIKI2 SDSUPPORT SERIAL_PORT2 NEOPIXEL_LED BAUD_RATE_GCODE
opt_set NEOPIXEL_PIN P1_16
exec_test $1 $2 "ReARM EFB VIKI2, SDSUPPORT, 2 Serial ports (USB CDC + UART0), NeoPixel"
restore_configs
use_example_configs Mks/Sbase
exec_test $1 $2 "MKS SBASE Example Config"
#restore_configs
#use_example_configs Mks/Sbase
#exec_test $1 $2 "MKS SBASE Example Config"
restore_configs
opt_set MOTHERBOARD BOARD_MKS_SBASE
@ -47,21 +47,5 @@ opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER SDSUPPORT ADAPTIVE_FAN_
opt_set GRID_MAX_POINTS_X 16
exec_test $1 $2 "Re-ARM with Many Features"
restore_configs
opt_set MOTHERBOARD BOARD_RAMPS_14_RE_ARM_EFB
opt_enable COREYX USE_XMAX_PLUG DAC_MOTOR_CURRENT_DEFAULT \
REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT BABYSTEPPING \
AUTO_BED_LEVELING_UBL RESTORE_LEVELING_AFTER_G28 EEPROM_SETTINGS \
FILAMENT_LCD_DISPLAY FILAMENT_WIDTH_SENSOR FAN_SOFT_PWM \
SHOW_TEMP_ADC_VALUES HOME_Y_BEFORE_X EMERGENCY_PARSER FAN_KICKSTART_TIME \
SD_ABORT_ON_ENDSTOP_HIT ADVANCED_OK GCODE_MACROS \
VOLUMETRIC_DEFAULT_ON NO_WORKSPACE_OFFSETS ACTION_ON_KILL \
EXTRA_FAN_SPEED FWRETRACT Z_DUAL_STEPPER_DRIVERS Z_DUAL_ENDSTOPS \
MENU_ADDAUTOSTART SDCARD_SORT_ALPHA
opt_set FAN_MIN_PWM 50
opt_set FAN_KICKSTART_TIME 100
opt_set XY_FREQUENCY_LIMIT 15
exec_test $1 $2 "Re-ARM with Many less common options"
# clean up
restore_configs

View file

@ -24,22 +24,22 @@ opt_enable VIKI2 SDSUPPORT ADAPTIVE_FAN_SLOWING NO_FAN_SLOWING_IN_PID_TUNING \
Z_SAFE_HOMING ADVANCED_PAUSE_FEATURE PARK_HEAD_ON_PAUSE BAUD_RATE_GCODE \
LCD_INFO_MENU ARC_SUPPORT BEZIER_CURVE_SUPPORT EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES SDCARD_SORT_ALPHA
opt_set GRID_MAX_POINTS_X 16
exec_test $1 $2 "Smoothieboard Many Features"
exec_test $1 $2 "Smoothieboard with many features"
restore_configs
opt_set MOTHERBOARD BOARD_AZTEEG_X5_MINI_WIFI
opt_enable COREYX USE_XMAX_PLUG DAC_MOTOR_CURRENT_DEFAULT \
REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT BABYSTEPPING \
AUTO_BED_LEVELING_UBL RESTORE_LEVELING_AFTER_G28 EEPROM_SETTINGS \
FILAMENT_LCD_DISPLAY FILAMENT_WIDTH_SENSOR FAN_SOFT_PWM \
SHOW_TEMP_ADC_VALUES HOME_Y_BEFORE_X EMERGENCY_PARSER FAN_KICKSTART_TIME \
SD_ABORT_ON_ENDSTOP_HIT ADVANCED_OK GCODE_MACROS BAUD_RATE_GCODE \
VOLUMETRIC_DEFAULT_ON NO_WORKSPACE_OFFSETS ACTION_ON_KILL \
EXTRA_FAN_SPEED FWRETRACT MENU_ADDAUTOSTART SDCARD_SORT_ALPHA
opt_set FAN_MIN_PWM 50
opt_set FAN_KICKSTART_TIME 100
opt_set XY_FREQUENCY_LIMIT 15
exec_test $1 $2 "Azteeg X5 MINI WIFI Many less common options"
#restore_configs
#opt_set MOTHERBOARD BOARD_AZTEEG_X5_MINI_WIFI
#opt_enable COREYX USE_XMAX_PLUG DAC_MOTOR_CURRENT_DEFAULT \
# REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT BABYSTEPPING \
# AUTO_BED_LEVELING_UBL RESTORE_LEVELING_AFTER_G28 EEPROM_SETTINGS \
# FILAMENT_LCD_DISPLAY FILAMENT_WIDTH_SENSOR FAN_SOFT_PWM \
# SHOW_TEMP_ADC_VALUES HOME_Y_BEFORE_X EMERGENCY_PARSER FAN_KICKSTART_TIME \
# SD_ABORT_ON_ENDSTOP_HIT ADVANCED_OK GCODE_MACROS BAUD_RATE_GCODE \
# VOLUMETRIC_DEFAULT_ON NO_WORKSPACE_OFFSETS ACTION_ON_KILL \
# EXTRA_FAN_SPEED FWRETRACT MENU_ADDAUTOSTART SDCARD_SORT_ALPHA
#opt_set FAN_MIN_PWM 50
#opt_set FAN_KICKSTART_TIME 100
#opt_set XY_FREQUENCY_LIMIT 15
#exec_test $1 $2 "Azteeg X5 MINI WIFI Many less common options"
restore_configs
use_example_configs delta/generic
@ -51,7 +51,7 @@ opt_set Y_DRIVER_TYPE TMC2130
opt_set Z_DRIVER_TYPE TMC2130
opt_enable TMC_USE_SW_SPI MONITOR_DRIVER_STATUS STEALTHCHOP_XY STEALTHCHOP_Z HYBRID_THRESHOLD TMC_DEBUG \
SENSORLESS_PROBING X_STALL_SENSITIVITY Y_STALL_SENSITIVITY Z_STALL_SENSITIVITY
exec_test $1 $2 "Delta Config (generic) + BOARD_COHESION3D_REMIX + UBL + EEPROM_SETTINGS + SENSORLESS_PROBING"
exec_test $1 $2 "Cohesion3D Remix DELTA + ABL Bilinear + EEPROM + SENSORLESS_PROBING"
# clean up
restore_configs

View file

@ -10,7 +10,7 @@ set -e
# Build with the default configurations
#
restore_configs
opt_set MOTHERBOARD BOARD_STM32F1R
opt_set MOTHERBOARD BOARD_STM32F103R
opt_set EXTRUDERS 2
opt_set SERIAL_PORT -1
opt_enable EEPROM_SETTINGS EEPROM_CHITCHAT REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT \

View file

@ -9,8 +9,16 @@ set -e
#
# Build with the default configurations
#
#restore_configs
#exec_test $1 $2 "Default Configuration"
#
# Test MESH_BED_LEVELING feature, with LCD
#
restore_configs
exec_test $1 $2 "Default Configuration"
opt_enable SPINDLE_FEATURE MESH_BED_LEVELING G26_MESH_EDITING MESH_G28_REST_ORIGIN LCD_BED_LEVELING MESH_EDIT_MENU ULTIMAKERCONTROLLER
exec_test $1 $2 "Spindle, MESH_BED_LEVELING, and LCD"
# clean up
restore_configs

View file

@ -9,14 +9,15 @@ set -e
#
# Build with the default configurations
#
restore_configs
exec_test $1 $2 "Default Configuration"
#restore_configs
#exec_test $1 $2 "Default Configuration"
#
# Test 2 extruders (one MAX6675) and heated bed on basic RAMPS 1.4
# Test a "Fix Mounted" Probe with Safe Homing, some arc options,
# linear bed leveling, M48, leveling debug, and firmware retraction.
#
restore_configs
opt_set MOTHERBOARD BOARD_RAMPS_14_EEB
opt_set EXTRUDERS 2
opt_set TEMP_SENSOR_0 -2
@ -81,13 +82,6 @@ opt_set NUM_SERVOS 1
opt_enable NO_VOLUMETRICS EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES AUTOTEMP G38_PROBE_TARGET
exec_test $1 $2 "RAMPS with ZONESTAR_LCD, Servo Probe, 3-Point ABL, DEBUG_LEVELING_FEATURE, EEPROM, G38, and more"
#
# Test MESH_BED_LEVELING feature, with LCD
#
restore_configs
opt_enable SPINDLE_FEATURE MESH_BED_LEVELING G26_MESH_EDITING MESH_G28_REST_ORIGIN LCD_BED_LEVELING MESH_EDIT_MENU ULTIMAKERCONTROLLER
exec_test $1 $2 "Spindle, MESH_BED_LEVELING, and LCD"
#
# Test MINIRAMBO with PWM_MOTOR_CURRENT and many features
#

View file

@ -129,7 +129,7 @@
// Choose the name from boards.h that matches your setup
#ifndef MOTHERBOARD
#define MOTHERBOARD BOARD_STM32F1R
#define MOTHERBOARD BOARD_STM32F103R
#endif
// Name displayed in the LCD "Ready" message and Info menu

View file

@ -129,7 +129,7 @@
// Choose the name from boards.h that matches your setup
#ifndef MOTHERBOARD
#define MOTHERBOARD BOARD_STM32F1R
#define MOTHERBOARD BOARD_STM32F103R
#endif
// Name displayed in the LCD "Ready" message and Info menu

View file

@ -257,11 +257,11 @@ monitor_speed = 250000
#
# STM32F103RE
#
[env:STM32F1]
[env:STM32F103R]
platform = ststm32
framework = arduino
board = genericSTM32F103RE
build_flags = !python Marlin/src/HAL/HAL_STM32F1/STM32F1_flag_script.py
build_flags = !python Marlin/src/HAL/HAL_STM32F1/build_flags.py
${common.build_flags} -std=gnu++14
-DDEBUG_LEVEL=0
build_unflags = -std=gnu++11
@ -271,16 +271,16 @@ src_filter = ${common.default_src_filter} +<src/HAL/HAL_STM32F1>
monitor_speed = 250000
#
# fysetc_STM32F1
# STM32F103R_fysetc
#
[env:fysetc_STM32F1]
[env:STM32F103R_fysetc]
platform = ststm32
framework = arduino
board = genericSTM32F103RC
#board_build.core = maple
platform_packages = tool-stm32duino
extra_scripts = buildroot/share/PlatformIO/scripts/fysetc_STM32F1.py
build_flags = !python Marlin/src/HAL/HAL_STM32F1/STM32F1_flag_script.py
extra_scripts = buildroot/share/PlatformIO/scripts/STM32F103R_fysetc.py
build_flags = !python Marlin/src/HAL/HAL_STM32F1/build_flags.py
${common.build_flags} -std=gnu++14
-DDEBUG_LEVEL=0 -DHAVE_SW_SERIAL
build_unflags = -std=gnu++11
@ -296,13 +296,13 @@ upload_protocol = serial
#
# BigTree SKR Mini V1.1 / SKR mini E3 / SKR E3 DIP (STM32F103RCT6 ARM Cortex-M3)
#
[env:BIGTREE_SKR_MINI]
[env:STM32F103R_bigtree]
platform = ststm32
framework = arduino
board = genericSTM32F103RC
platform_packages = tool-stm32duino
extra_scripts = buildroot/share/PlatformIO/scripts/STM32F1_SKR_MINI.py
build_flags = !python Marlin/src/HAL/HAL_STM32F1/STM32F1_flag_script.py
build_flags = !python Marlin/src/HAL/HAL_STM32F1/build_flags.py
${common.build_flags} -std=gnu++14
-DDEBUG_LEVEL=0
build_unflags = -std=gnu++11
@ -355,13 +355,13 @@ monitor_speed = 250000
#
# Longer 3D board in Alfawise U20 (STM32F103VET6)
#
[env:alfawise_U20]
[env:STM32F103V_longer]
platform = ststm32
framework = arduino
board = genericSTM32F103VE
monitor_speed = 250000
extra_scripts = buildroot/share/PlatformIO/scripts/alfawise_Ux0.py
build_flags = !python Marlin/src/HAL/HAL_STM32F1/STM32F1_flag_script.py
extra_scripts = buildroot/share/PlatformIO/scripts/longer_STM32.py
build_flags = !python Marlin/src/HAL/HAL_STM32F1/build_flags.py
${common.build_flags} -std=gnu++14
-DSTM32F1xx -DU20 -DTS_V12
build_unflags = -std=gnu++11 -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG=1 -DERROR_LED_PORT=GPIOE -DERROR_LED_PIN=6
@ -377,7 +377,7 @@ platform = ststm32
framework = arduino
board = genericSTM32F103ZE
extra_scripts = buildroot/share/PlatformIO/scripts/mks_robin.py
build_flags = !python Marlin/src/HAL/HAL_STM32F1/STM32F1_flag_script.py
build_flags = !python Marlin/src/HAL/HAL_STM32F1/build_flags.py
${common.build_flags} -std=gnu++14
build_unflags = -std=gnu++11
src_filter = ${common.default_src_filter} +<src/HAL/HAL_STM32F1>
@ -392,7 +392,7 @@ platform = ststm32
framework = arduino
board = genericSTM32F103RC
extra_scripts = buildroot/share/PlatformIO/scripts/mks_robin_lite.py
build_flags = !python Marlin/src/HAL/HAL_STM32F1/STM32F1_flag_script.py
build_flags = !python Marlin/src/HAL/HAL_STM32F1/build_flags.py
${common.build_flags} -std=gnu++14
build_unflags = -std=gnu++11
src_filter = ${common.default_src_filter} +<src/HAL/HAL_STM32F1>
@ -407,7 +407,7 @@ platform = ststm32
framework = arduino
board = genericSTM32F103VE
extra_scripts = buildroot/share/PlatformIO/scripts/mks_robin_mini.py
build_flags = !python Marlin/src/HAL/HAL_STM32F1/STM32F1_flag_script.py
build_flags = !python Marlin/src/HAL/HAL_STM32F1/build_flags.py
${common.build_flags} -std=gnu++14
build_unflags = -std=gnu++11
src_filter = ${common.default_src_filter} +<src/HAL/HAL_STM32F1>
@ -422,7 +422,7 @@ platform = ststm32
framework = arduino
board = genericSTM32F103VE
extra_scripts = buildroot/share/PlatformIO/scripts/mks_robin_nano.py
build_flags = !python Marlin/src/HAL/HAL_STM32F1/STM32F1_flag_script.py
build_flags = !python Marlin/src/HAL/HAL_STM32F1/build_flags.py
${common.build_flags} -std=gnu++14
build_unflags = -std=gnu++11
src_filter = ${common.default_src_filter} +<src/HAL/HAL_STM32F1>
@ -437,7 +437,7 @@ platform = ststm32
framework = arduino
board = genericSTM32F103ZE
extra_scripts = buildroot/share/PlatformIO/scripts/jgaurora_a5s_a1_with_bootloader.py
build_flags = !python Marlin/src/HAL/HAL_STM32F1/STM32F1_flag_script.py
build_flags = !python Marlin/src/HAL/HAL_STM32F1/build_flags.py
${common.build_flags} -DSTM32F1xx -std=gnu++14
build_unflags = -std=gnu++11
src_filter = ${common.default_src_filter} +<src/HAL/HAL_STM32F1>
@ -450,7 +450,7 @@ monitor_speed = 250000
# 'Black' STM32F407VET6 board - http://wiki.stm32duino.com/index.php?title=STM32F407
# Shield - https://github.com/jmz52/Hardware
#
[env:black_stm32f407ve]
[env:STM32F407VE_black]
platform = ststm32@5.4.3
framework = arduino
board = blackSTM32F407VET6
@ -533,7 +533,7 @@ monitor_speed = 250000
platform = ststm32
framework = arduino
board = malyanM200
build_flags = !python Marlin/src/HAL/HAL_STM32F1/STM32F1_flag_script.py -DMCU_STM32F103CB -D __STM32F1__=1 -std=c++1y -D MOTHERBOARD="BOARD_MALYAN_M200" -DSERIAL_USB -ffunction-sections -fdata-sections -Wl,--gc-sections
build_flags = !python Marlin/src/HAL/HAL_STM32F1/build_flags.py -DMCU_STM32F103CB -D __STM32F1__=1 -std=c++1y -D MOTHERBOARD="BOARD_MALYAN_M200" -DSERIAL_USB -ffunction-sections -fdata-sections -Wl,--gc-sections
-DDEBUG_LEVEL=0
src_filter = ${common.default_src_filter} +<src/HAL/HAL_STM32F1>
#-<frameworks>
@ -586,7 +586,7 @@ src_filter = ${common.default_src_filter} +<src/HAL/HAL_LINUX>
#
# Adafruit Grand Central M4 (Atmel SAMD51P20A ARM Cortex-M4)
#
[env:adafruit_grandcentral_m4]
[env:SAMD51_grandcentral_m4]
platform = atmelsam
board = adafruit_grandcentral_m4
framework = arduino