MKS Robin Nano V3 and STM32F4x0Vx Variant (#20430)
This commit is contained in:
parent
fae3c860a1
commit
b167cd2427
|
@ -367,6 +367,7 @@
|
||||||
#define BOARD_FLYF407ZG 4217 // FLYF407ZG board (STM32F407ZG)
|
#define BOARD_FLYF407ZG 4217 // FLYF407ZG board (STM32F407ZG)
|
||||||
#define BOARD_MKS_ROBIN2 4218 // MKS_ROBIN2 (STM32F407ZE)
|
#define BOARD_MKS_ROBIN2 4218 // MKS_ROBIN2 (STM32F407ZE)
|
||||||
#define BOARD_MKS_ROBIN_PRO_V2 4219 // MKS Robin Pro V2 (STM32F407VE)
|
#define BOARD_MKS_ROBIN_PRO_V2 4219 // MKS Robin Pro V2 (STM32F407VE)
|
||||||
|
#define BOARD_MKS_ROBIN_NANO_V3 4220 // MKS Robin Nano V3 (STM32F407VG)
|
||||||
|
|
||||||
//
|
//
|
||||||
// ARM Cortex M7
|
// ARM Cortex M7
|
||||||
|
|
|
@ -592,6 +592,8 @@
|
||||||
#include "stm32f4/pins_MKS_ROBIN2.h" // STM32F4 env:MKS_ROBIN2
|
#include "stm32f4/pins_MKS_ROBIN2.h" // STM32F4 env:MKS_ROBIN2
|
||||||
#elif MB(MKS_ROBIN_PRO_V2)
|
#elif MB(MKS_ROBIN_PRO_V2)
|
||||||
#include "stm32f4/pins_MKS_ROBIN_PRO_V2.h" // STM32F4 env:mks_robin_pro2
|
#include "stm32f4/pins_MKS_ROBIN_PRO_V2.h" // STM32F4 env:mks_robin_pro2
|
||||||
|
#elif MB(MKS_ROBIN_NANO_V3)
|
||||||
|
#include "stm32f4/pins_MKS_ROBIN_NANO_V3.h" // STM32F4 env:mks_robin_nano_v3
|
||||||
|
|
||||||
//
|
//
|
||||||
// ARM Cortex M7
|
// ARM Cortex M7
|
||||||
|
|
367
Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h
Normal file
367
Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h
Normal file
|
@ -0,0 +1,367 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* 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
|
||||||
|
|
||||||
|
#if NOT_TARGET(STM32F4, STM32F4xx)
|
||||||
|
#error "Oops! Select an STM32F4 board in 'Tools > Board.'"
|
||||||
|
#elif HOTENDS > 2 || E_STEPPERS > 2
|
||||||
|
#error "MKS Robin Nano V3 supports up to 2 hotends / E-steppers."
|
||||||
|
#elif HAS_FSMC_TFT
|
||||||
|
#error "MKS Robin Nano V3 doesn't support FSMC-based TFT displays."
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define BOARD_INFO_NAME "MKS Robin Nano V3"
|
||||||
|
|
||||||
|
// Use one of these or SDCard-based Emulation will be used
|
||||||
|
//#define SRAM_EEPROM_EMULATION // Use BackSRAM-based EEPROM emulation
|
||||||
|
//#define FLASH_EEPROM_EMULATION // Use Flash-based EEPROM emulation
|
||||||
|
#define I2C_EEPROM
|
||||||
|
|
||||||
|
//
|
||||||
|
// Release PB4 (Z_DIR_PIN) from JTAG NRST role
|
||||||
|
//
|
||||||
|
|
||||||
|
//
|
||||||
|
// Limit Switches
|
||||||
|
//
|
||||||
|
#define X_DIAG_PIN PD15
|
||||||
|
#define Y_DIAG_PIN PD2
|
||||||
|
#define Z_DIAG_PIN PC8
|
||||||
|
#define E0_DIAG_PIN PC4
|
||||||
|
#define E1_DIAG_PIN PE7
|
||||||
|
|
||||||
|
//
|
||||||
|
#define X_STOP_PIN PA15
|
||||||
|
#define Y_STOP_PIN PD2
|
||||||
|
#define Z_MIN_PIN PC8
|
||||||
|
#define Z_MAX_PIN PC4
|
||||||
|
|
||||||
|
//
|
||||||
|
// Steppers
|
||||||
|
//
|
||||||
|
#define X_ENABLE_PIN PE4
|
||||||
|
#define X_STEP_PIN PE3
|
||||||
|
#define X_DIR_PIN PE2
|
||||||
|
#ifndef X_CS_PIN
|
||||||
|
#define X_CS_PIN PD5
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define Y_ENABLE_PIN PE1
|
||||||
|
#define Y_STEP_PIN PE0
|
||||||
|
#define Y_DIR_PIN PB9
|
||||||
|
#ifndef Y_CS_PIN
|
||||||
|
#define Y_CS_PIN PD7
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define Z_ENABLE_PIN PB8
|
||||||
|
#define Z_STEP_PIN PB5
|
||||||
|
#define Z_DIR_PIN PB4
|
||||||
|
#ifndef Z_CS_PIN
|
||||||
|
#define Z_CS_PIN PD4
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define E0_ENABLE_PIN PB3
|
||||||
|
#define E0_STEP_PIN PD6
|
||||||
|
#define E0_DIR_PIN PD3
|
||||||
|
#ifndef E0_CS_PIN
|
||||||
|
#define E0_CS_PIN PD9
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define E1_ENABLE_PIN PA3
|
||||||
|
#define E1_STEP_PIN PD15
|
||||||
|
#define E1_DIR_PIN PA1
|
||||||
|
#ifndef E1_CS_PIN
|
||||||
|
#define E1_CS_PIN PD8
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//
|
||||||
|
// Software SPI pins for TMC2130 stepper drivers
|
||||||
|
//
|
||||||
|
// This board only support SW SPI for stepper drivers
|
||||||
|
#if HAS_TMC_SPI
|
||||||
|
#define TMC_USE_SW_SPI
|
||||||
|
#endif
|
||||||
|
#if ENABLED(TMC_USE_SW_SPI)
|
||||||
|
#if !defined(TMC_SW_MOSI) || TMC_SW_MOSI == -1
|
||||||
|
#define TMC_SW_MOSI PD14
|
||||||
|
#endif
|
||||||
|
#if !defined(TMC_SW_MISO) || TMC_SW_MISO == -1
|
||||||
|
#define TMC_SW_MISO PD1
|
||||||
|
#endif
|
||||||
|
#if !defined(TMC_SW_SCK) || TMC_SW_SCK == -1
|
||||||
|
#define TMC_SW_SCK PD0
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if HAS_TMC_UART
|
||||||
|
//
|
||||||
|
// Software serial
|
||||||
|
// No Hardware serial for steppers
|
||||||
|
//
|
||||||
|
#define X_SERIAL_TX_PIN PD5
|
||||||
|
#define X_SERIAL_RX_PIN PD5
|
||||||
|
|
||||||
|
#define Y_SERIAL_TX_PIN PD7
|
||||||
|
#define Y_SERIAL_RX_PIN PD7
|
||||||
|
|
||||||
|
#define Z_SERIAL_TX_PIN PD4
|
||||||
|
#define Z_SERIAL_RX_PIN PD4
|
||||||
|
|
||||||
|
#define E0_SERIAL_TX_PIN PD9
|
||||||
|
#define E0_SERIAL_RX_PIN PD9
|
||||||
|
|
||||||
|
#define E1_SERIAL_TX_PIN PD8
|
||||||
|
#define E1_SERIAL_RX_PIN PD8
|
||||||
|
|
||||||
|
// Reduce baud rate to improve software serial reliability
|
||||||
|
#define TMC_BAUD_RATE 19200
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//
|
||||||
|
// Temperature Sensors
|
||||||
|
//
|
||||||
|
#define TEMP_0_PIN PC1 // TH1
|
||||||
|
#define TEMP_1_PIN PA2 // TH2
|
||||||
|
#define TEMP_BED_PIN PC0 // TB1
|
||||||
|
|
||||||
|
//
|
||||||
|
// Heaters / Fans
|
||||||
|
//
|
||||||
|
#define HEATER_0_PIN PE5 // HEATER1
|
||||||
|
#define HEATER_1_PIN PB0 // HEATER2
|
||||||
|
#define HEATER_BED_PIN PA0 // HOT BED
|
||||||
|
|
||||||
|
#define FAN_PIN PB1 // FAN
|
||||||
|
#define FAN1_PIN PC14 // FAN1
|
||||||
|
|
||||||
|
//
|
||||||
|
// Thermocouples
|
||||||
|
//
|
||||||
|
//#define MAX6675_SS_PIN HEATER_0_PIN // TC1 - CS1
|
||||||
|
//#define MAX6675_SS_PIN HEATER_1_PIN // TC2 - CS2
|
||||||
|
|
||||||
|
//
|
||||||
|
// Misc. Functions
|
||||||
|
//
|
||||||
|
#define MT_DET_1 PA4
|
||||||
|
#define MT_DET_2 PE6
|
||||||
|
#define PW_DET PA13
|
||||||
|
#define PW_OFF PB2
|
||||||
|
|
||||||
|
#ifndef FIL_RUNOUT_PIN
|
||||||
|
#define FIL_RUNOUT_PIN MT_DET_1
|
||||||
|
#endif
|
||||||
|
#ifndef FIL_RUNOUT2_PIN
|
||||||
|
#define FIL_RUNOUT2_PIN MT_DET_2
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define POWER_LOSS_PIN PW_DET
|
||||||
|
#define PS_ON_PIN PW_OFF
|
||||||
|
//
|
||||||
|
// Enable MKSPWC support
|
||||||
|
//
|
||||||
|
//#define SUICIDE_PIN PB2
|
||||||
|
//#define KILL_PIN PA2
|
||||||
|
//#define KILL_PIN_INVERTING true
|
||||||
|
|
||||||
|
#define SERVO0_PIN PA8 // Enable BLTOUCH support
|
||||||
|
//#define LED_PIN PB2
|
||||||
|
|
||||||
|
// Random Info
|
||||||
|
#define USB_SERIAL -1 //Usb Serial
|
||||||
|
#define WIFI_SERIAL 3 //USART3
|
||||||
|
#define MKS_WIFI_MODULE_SERIAL 1 //USART1
|
||||||
|
#define MKS_WIFI_MODULE_SPI 2 //SPI2
|
||||||
|
|
||||||
|
#ifndef SDCARD_CONNECTION
|
||||||
|
#define SDCARD_CONNECTION ONBOARD
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//
|
||||||
|
// Onboard SD card
|
||||||
|
//
|
||||||
|
// detect pin dont work when ONBOARD and NO_SD_HOST_DRIVE disabled
|
||||||
|
#if SD_CONNECTION_IS(ONBOARD)
|
||||||
|
#define CUSTOM_SPI_PINS // TODO: needed because is the only way to set SPI3 for SD on STM32 (by now)
|
||||||
|
#if ENABLED(CUSTOM_SPI_PINS)
|
||||||
|
#define ENABLE_SPI3
|
||||||
|
#define SS_PIN -1
|
||||||
|
#define SDSS PC9
|
||||||
|
#define SCK_PIN PC10
|
||||||
|
#define MISO_PIN PC11
|
||||||
|
#define MOSI_PIN PC12
|
||||||
|
#define SD_DETECT_PIN PD12
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//
|
||||||
|
// LCD SD
|
||||||
|
//
|
||||||
|
#if SD_CONNECTION_IS(LCD)
|
||||||
|
#define CUSTOM_SPI_PINS
|
||||||
|
#if ENABLED(CUSTOM_SPI_PINS)
|
||||||
|
#define ENABLE_SPI1
|
||||||
|
#define SDSS PE10
|
||||||
|
#define SCK_PIN PA5
|
||||||
|
#define MISO_PIN PA6
|
||||||
|
#define MOSI_PIN PA7
|
||||||
|
#define SD_DETECT_PIN PE12
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//
|
||||||
|
// LCD / Controller
|
||||||
|
#define SPI_FLASH
|
||||||
|
#define HAS_SPI_FLASH 1
|
||||||
|
#define SPI_DEVICE 2
|
||||||
|
#define SPI_FLASH_SIZE 0x1000000
|
||||||
|
#if ENABLED(SPI_FLASH)
|
||||||
|
#define W25QXX_CS_PIN PB12
|
||||||
|
#define W25QXX_MOSI_PIN PC3
|
||||||
|
#define W25QXX_MISO_PIN PC2
|
||||||
|
#define W25QXX_SCK_PIN PB13
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* _____ _____
|
||||||
|
* (BEEPER)PC5 | · · | PE13(BTN_ENC) (SPI1 MISO) PA6 | · · | PA5 (SPI1 SCK)
|
||||||
|
* (LCD_EN)PD13 | · · | PC6(LCD_RS) (BTN_EN1) PE8 | · · | PE10 (SPI1 CS)
|
||||||
|
* (LCD_D4)PE14 | · · PE15(LCD_D5) (BTN_EN2) PE11 | · · PA7 (SPI1 MOSI)
|
||||||
|
* (LCD_D6)PD11 | · · | PD10(LCD_D7) (SPI1_RS) PE12 | · · | RESET
|
||||||
|
* GND | · · | 5V GND | · · | 3.3V
|
||||||
|
*  ̄ ̄ ̄  ̄ ̄ ̄
|
||||||
|
* EXP1 EXP2
|
||||||
|
*/
|
||||||
|
|
||||||
|
#if EITHER(TFT_480x320_SPI, TFT_LVGL_UI_SPI)
|
||||||
|
#ifndef TOUCH_CALIBRATION_X
|
||||||
|
#define TOUCH_CALIBRATION_X -17253
|
||||||
|
#endif
|
||||||
|
#ifndef TOUCH_CALIBRATION_Y
|
||||||
|
#define TOUCH_CALIBRATION_Y 11579
|
||||||
|
#endif
|
||||||
|
#ifndef TOUCH_OFFSET_X
|
||||||
|
#define TOUCH_OFFSET_X 514
|
||||||
|
#endif
|
||||||
|
#ifndef TOUCH_OFFSET_Y
|
||||||
|
#define TOUCH_OFFSET_Y -24
|
||||||
|
#endif
|
||||||
|
#ifndef TOUCH_ORIENTATION
|
||||||
|
#define TOUCH_ORIENTATION TOUCH_LANDSCAPE
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define TFT_CS_PIN PD11
|
||||||
|
#define TFT_SCK_PIN PA5
|
||||||
|
#define TFT_MISO_PIN PA6
|
||||||
|
#define TFT_MOSI_PIN PA7
|
||||||
|
#define TFT_DC_PIN PD10
|
||||||
|
#define TFT_RST_PIN PC6
|
||||||
|
#define TFT_A0_PIN TFT_DC_PIN
|
||||||
|
|
||||||
|
#define TFT_RESET_PIN PC6
|
||||||
|
#define TFT_BACKLIGHT_PIN PD13
|
||||||
|
|
||||||
|
#define TOUCH_BUTTONS_HW_SPI
|
||||||
|
#define TOUCH_BUTTONS_HW_SPI_DEVICE 1
|
||||||
|
|
||||||
|
#define LCD_BACKLIGHT_PIN PD13
|
||||||
|
#ifndef TFT_WIDTH
|
||||||
|
#define TFT_WIDTH 480
|
||||||
|
#endif
|
||||||
|
#ifndef TFT_HEIGHT
|
||||||
|
#define TFT_HEIGHT 320
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define TOUCH_CS_PIN PE14 // SPI1_NSS
|
||||||
|
#define TOUCH_SCK_PIN PA5 // SPI1_SCK
|
||||||
|
#define TOUCH_MISO_PIN PA6 // SPI1_MISO
|
||||||
|
#define TOUCH_MOSI_PIN PA7 // SPI1_MOSI
|
||||||
|
|
||||||
|
#define BTN_EN1 PE8
|
||||||
|
#define BTN_EN2 PE11
|
||||||
|
#define BEEPER_PIN PC5
|
||||||
|
#define BTN_ENC PE13
|
||||||
|
|
||||||
|
#define LCD_READ_ID 0xD3
|
||||||
|
#define LCD_USE_DMA_SPI
|
||||||
|
|
||||||
|
#define TFT_BUFFER_SIZE 14400
|
||||||
|
|
||||||
|
#elif HAS_SPI_LCD
|
||||||
|
#define BEEPER_PIN PC5
|
||||||
|
#define BTN_ENC PE13
|
||||||
|
#define LCD_PINS_ENABLE PD13
|
||||||
|
#define LCD_PINS_RS PC6
|
||||||
|
#define BTN_EN1 PE8
|
||||||
|
#define BTN_EN2 PE11
|
||||||
|
#define LCD_BACKLIGHT_PIN -1
|
||||||
|
|
||||||
|
// MKS MINI12864 and MKS LCD12864B; If using MKS LCD12864A (Need to remove RPK2 resistor)
|
||||||
|
#if ENABLED(MKS_MINI_12864)
|
||||||
|
//#define LCD_BACKLIGHT_PIN -1
|
||||||
|
//#define LCD_RESET_PIN -1
|
||||||
|
#define DOGLCD_A0 PD11
|
||||||
|
#define DOGLCD_CS PE15
|
||||||
|
//#define DOGLCD_SCK PA5
|
||||||
|
//#define DOGLCD_MOSI PA7
|
||||||
|
|
||||||
|
// Required for MKS_MINI_12864 with this board
|
||||||
|
//#define MKS_LCD12864B
|
||||||
|
//#undef SHOW_BOOTSCREEN
|
||||||
|
|
||||||
|
#else // !MKS_MINI_12864
|
||||||
|
|
||||||
|
#define LCD_PINS_D4 PE14
|
||||||
|
#if ENABLED(ULTIPANEL)
|
||||||
|
#define LCD_PINS_D5 PE15
|
||||||
|
#define LCD_PINS_D6 PD11
|
||||||
|
#define LCD_PINS_D7 PD10
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define BOARD_ST7920_DELAY_1 DELAY_NS(96)
|
||||||
|
#define BOARD_ST7920_DELAY_2 DELAY_NS(48)
|
||||||
|
#define BOARD_ST7920_DELAY_3 DELAY_NS(600)
|
||||||
|
|
||||||
|
#endif // !MKS_MINI_12864
|
||||||
|
|
||||||
|
#elif ENABLED(SPI_GRAPHICAL_TFT)
|
||||||
|
#define SPI_TFT_CS_PIN PD11
|
||||||
|
#define SPI_TFT_SCK_PIN PA5
|
||||||
|
#define SPI_TFT_MISO_PIN PA6
|
||||||
|
#define SPI_TFT_MOSI_PIN PA7
|
||||||
|
#define SPI_TFT_DC_PIN PD10
|
||||||
|
#define SPI_TFT_RST_PIN PC6
|
||||||
|
|
||||||
|
#define LCD_BACKLIGHT_PIN PD13
|
||||||
|
|
||||||
|
#define TOUCH_CS_PIN PE14 // SPI1_NSS
|
||||||
|
#define TOUCH_SCK_PIN PA5 // SPI1_SCK
|
||||||
|
#define TOUCH_MISO_PIN PA6 // SPI1_MISO
|
||||||
|
#define TOUCH_MOSI_PIN PA7 // SPI1_MOSI
|
||||||
|
|
||||||
|
#define BTN_EN1 PE8
|
||||||
|
#define BTN_EN2 PE11
|
||||||
|
#define BEEPER_PIN PC5
|
||||||
|
#define BTN_ENC PE13
|
||||||
|
#endif // HAS_SPI_LCD
|
||||||
|
|
||||||
|
#define HAS_OTG_USB_HOST_SUPPORT
|
56
buildroot/share/PlatformIO/boards/genericSTM32F407VGT6.json
Normal file
56
buildroot/share/PlatformIO/boards/genericSTM32F407VGT6.json
Normal file
|
@ -0,0 +1,56 @@
|
||||||
|
{
|
||||||
|
"build": {
|
||||||
|
"core": "stm32",
|
||||||
|
"cpu": "cortex-m4",
|
||||||
|
"extra_flags": "-DSTM32F407xx -DSTM32F4",
|
||||||
|
"f_cpu": "168000000L",
|
||||||
|
"hwids": [
|
||||||
|
[
|
||||||
|
"0x1EAF",
|
||||||
|
"0x0003"
|
||||||
|
],
|
||||||
|
[
|
||||||
|
"0x0483",
|
||||||
|
"0x3748"
|
||||||
|
]
|
||||||
|
],
|
||||||
|
"mcu": "stm32f407vgt6",
|
||||||
|
"product_line": "STM32F407xx",
|
||||||
|
"variant": "Generic_F4x7Vx"
|
||||||
|
},
|
||||||
|
"debug": {
|
||||||
|
"default_tools": [
|
||||||
|
"stlink"
|
||||||
|
],
|
||||||
|
"jlink_device": "STM32F407VG",
|
||||||
|
"openocd_extra_args": [
|
||||||
|
"-c",
|
||||||
|
"reset_config none"
|
||||||
|
],
|
||||||
|
"openocd_target": "stm32f4x",
|
||||||
|
"svd_path": "STM32F40x.svd"
|
||||||
|
},
|
||||||
|
"frameworks": [
|
||||||
|
"arduino",
|
||||||
|
"cmsis",
|
||||||
|
"stm32cube",
|
||||||
|
"libopencm3"
|
||||||
|
],
|
||||||
|
"name": "STM32F407VG (128k RAM, 64k CCM RAM, 1024k Flash",
|
||||||
|
"upload": {
|
||||||
|
"disable_flushing": false,
|
||||||
|
"maximum_ram_size": 131072,
|
||||||
|
"maximum_size": 1048576,
|
||||||
|
"protocol": "stlink",
|
||||||
|
"protocols": [
|
||||||
|
"stlink",
|
||||||
|
"dfu",
|
||||||
|
"jlink"
|
||||||
|
],
|
||||||
|
"require_upload_port": true,
|
||||||
|
"use_1200bps_touch": false,
|
||||||
|
"wait_for_upload_port": false
|
||||||
|
},
|
||||||
|
"url": "https://www.st.com/content/st_com/en/products/microcontrollers/stm32-32-bit-arm-cortex-mcus/stm32-high-performance-mcus/stm32f4-series/stm32f407-417/stm32f407vg.html",
|
||||||
|
"vendor": "Generic"
|
||||||
|
}
|
|
@ -0,0 +1,408 @@
|
||||||
|
/*
|
||||||
|
*******************************************************************************
|
||||||
|
* Copyright (c) 2019, STMicroelectronics
|
||||||
|
* All rights reserved.
|
||||||
|
*
|
||||||
|
* This software component is licensed by ST under BSD 3-Clause license,
|
||||||
|
* the "License"; You may not use this file except in compliance with the
|
||||||
|
* License. You may obtain a copy of the License at:
|
||||||
|
* opensource.org/licenses/BSD-3-Clause
|
||||||
|
*
|
||||||
|
*******************************************************************************
|
||||||
|
* Automatically generated from STM32F407V(E-G)Tx.xml
|
||||||
|
*/
|
||||||
|
#include "Arduino.h"
|
||||||
|
#include "PeripheralPins.h"
|
||||||
|
|
||||||
|
/* =====
|
||||||
|
* Note: Commented lines are alternative possibilities which are not used per default.
|
||||||
|
* If you change them, you will have to know what you do
|
||||||
|
* =====
|
||||||
|
*/
|
||||||
|
|
||||||
|
//*** ADC ***
|
||||||
|
|
||||||
|
#ifdef HAL_ADC_MODULE_ENABLED
|
||||||
|
WEAK const PinMap PinMap_ADC[] = {
|
||||||
|
{PA_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC1_IN0
|
||||||
|
// {PA_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC2_IN0
|
||||||
|
// {PA_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC3_IN0
|
||||||
|
{PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1
|
||||||
|
// {PA_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC2_IN1
|
||||||
|
// {PA_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC3_IN1
|
||||||
|
{PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2
|
||||||
|
// {PA_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC2_IN2
|
||||||
|
// {PA_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC3_IN2
|
||||||
|
{PA_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3
|
||||||
|
// {PA_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC2_IN3
|
||||||
|
// {PA_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC3_IN3
|
||||||
|
{PA_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4
|
||||||
|
// {PA_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC2_IN4
|
||||||
|
{PA_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_IN5
|
||||||
|
// {PA_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC2_IN5
|
||||||
|
{PA_6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6
|
||||||
|
// {PA_6, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC2_IN6
|
||||||
|
{PA_7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7
|
||||||
|
// {PA_7, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC2_IN7
|
||||||
|
{PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8
|
||||||
|
// {PB_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC2_IN8
|
||||||
|
{PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9
|
||||||
|
// {PB_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC2_IN9
|
||||||
|
{PC_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10
|
||||||
|
// {PC_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC2_IN10
|
||||||
|
// {PC_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC3_IN10
|
||||||
|
{PC_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC1_IN11
|
||||||
|
// {PC_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC2_IN11
|
||||||
|
// {PC_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC3_IN11
|
||||||
|
{PC_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC1_IN12
|
||||||
|
// {PC_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC2_IN12
|
||||||
|
// {PC_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC3_IN12
|
||||||
|
{PC_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC1_IN13
|
||||||
|
// {PC_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC2_IN13
|
||||||
|
// {PC_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC3_IN13
|
||||||
|
{PC_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_IN14
|
||||||
|
// {PC_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC2_IN14
|
||||||
|
{PC_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15
|
||||||
|
// {PC_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC2_IN15
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//*** DAC ***
|
||||||
|
|
||||||
|
#ifdef HAL_DAC_MODULE_ENABLED
|
||||||
|
WEAK const PinMap PinMap_DAC[] = {
|
||||||
|
{PA_4, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // DAC_OUT1
|
||||||
|
{PA_5, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // DAC_OUT2
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//*** I2C ***
|
||||||
|
|
||||||
|
#ifdef HAL_I2C_MODULE_ENABLED
|
||||||
|
WEAK const PinMap PinMap_I2C_SDA[] = {
|
||||||
|
{PB_7, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
|
||||||
|
{PB_9, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
|
||||||
|
{PB_11, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)},
|
||||||
|
{PC_9, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)},
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef HAL_I2C_MODULE_ENABLED
|
||||||
|
WEAK const PinMap PinMap_I2C_SCL[] = {
|
||||||
|
{PA_8, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)},
|
||||||
|
{PB_6, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
|
||||||
|
{PB_8, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
|
||||||
|
{PB_10, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)},
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//*** PWM ***
|
||||||
|
|
||||||
|
#ifdef HAL_TIM_MODULE_ENABLED
|
||||||
|
// Some pins can perform PWM from more than one timer. These were selected to utilize as many channels as
|
||||||
|
// possible from timers which were already dedicated to PWM output.
|
||||||
|
|
||||||
|
// TIM1 = Pins are using for OTG FS
|
||||||
|
// TIM2 = [HEATER_BED], TIM2 is used OTG HS SOF
|
||||||
|
// TIM6 = Tone
|
||||||
|
// TIM8 = [FAN0, HEATER_1] OTG HS
|
||||||
|
// TIM7 = Servo
|
||||||
|
// TIM9 = [HEATER_0, ]
|
||||||
|
// TIM1, TIM8, TIM12 = Pins are using for OTG HS
|
||||||
|
// No timer = [FAN1 ]
|
||||||
|
|
||||||
|
WEAK const PinMap PinMap_PWM[] = {
|
||||||
|
{PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1
|
||||||
|
// {PA_0, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1
|
||||||
|
// {PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2
|
||||||
|
{PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2
|
||||||
|
// {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3
|
||||||
|
{PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3
|
||||||
|
// {PA_2, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1
|
||||||
|
// {PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4
|
||||||
|
{PA_3, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 4, 0)}, // TIM5_CH4
|
||||||
|
// {PA_3, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2
|
||||||
|
{PA_5, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1
|
||||||
|
// {PA_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N
|
||||||
|
// {PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1
|
||||||
|
{PA_6, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1
|
||||||
|
// {PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N
|
||||||
|
// {PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2
|
||||||
|
// {PA_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N
|
||||||
|
{PA_7, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1
|
||||||
|
{PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1
|
||||||
|
{PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2
|
||||||
|
{PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3
|
||||||
|
// {PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4
|
||||||
|
{PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1
|
||||||
|
// {PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N
|
||||||
|
// {PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3
|
||||||
|
{PB_0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N
|
||||||
|
// {PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N
|
||||||
|
// {PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4
|
||||||
|
{PB_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N
|
||||||
|
{PB_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4
|
||||||
|
{PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2
|
||||||
|
{PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1
|
||||||
|
{PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2
|
||||||
|
{PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1
|
||||||
|
{PB_7, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2
|
||||||
|
{PB_8, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3
|
||||||
|
// {PB_8, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1
|
||||||
|
// {PB_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4
|
||||||
|
{PB_9, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1
|
||||||
|
{PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3
|
||||||
|
{PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4
|
||||||
|
{PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N
|
||||||
|
// {PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N
|
||||||
|
// {PB_14, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N
|
||||||
|
// {PB_14, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 1, 0)}, // TIM12_CH1
|
||||||
|
// {PB_15, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N
|
||||||
|
// {PB_15, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N
|
||||||
|
// {PB_15, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 2, 0)}, // TIM12_CH2
|
||||||
|
{PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1
|
||||||
|
// {PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1
|
||||||
|
// {PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2
|
||||||
|
{PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2
|
||||||
|
{PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3
|
||||||
|
// {PC_8, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 0)}, // TIM8_CH3
|
||||||
|
// {PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4
|
||||||
|
{PC_9, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 4, 0)}, // TIM8_CH4
|
||||||
|
{PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1
|
||||||
|
{PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2
|
||||||
|
{PD_14, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3
|
||||||
|
{PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4
|
||||||
|
{PE_5, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1
|
||||||
|
{PE_6, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2
|
||||||
|
{PE_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N
|
||||||
|
{PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1
|
||||||
|
{PE_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N
|
||||||
|
{PE_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2
|
||||||
|
{PE_12, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N
|
||||||
|
{PE_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3
|
||||||
|
{PE_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//*** SERIAL ***
|
||||||
|
|
||||||
|
#ifdef HAL_UART_MODULE_ENABLED
|
||||||
|
WEAK const PinMap PinMap_UART_TX[] = {
|
||||||
|
{PA_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
|
||||||
|
{PA_2, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
|
||||||
|
{PA_9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
|
||||||
|
{PB_6, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
|
||||||
|
{PB_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
|
||||||
|
{PC_6, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)},
|
||||||
|
{PC_10, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
|
||||||
|
{PC_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
|
||||||
|
{PC_12, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)},
|
||||||
|
{PD_5, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
|
||||||
|
{PD_8, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef HAL_UART_MODULE_ENABLED
|
||||||
|
WEAK const PinMap PinMap_UART_RX[] = {
|
||||||
|
{PA_1, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
|
||||||
|
{PA_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
|
||||||
|
{PA_10, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
|
||||||
|
{PB_7, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
|
||||||
|
{PB_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
|
||||||
|
{PC_7, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)},
|
||||||
|
// {PC_11, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
|
||||||
|
{PC_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
|
||||||
|
{PD_2, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)},
|
||||||
|
{PD_6, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
|
||||||
|
{PD_9, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef HAL_UART_MODULE_ENABLED
|
||||||
|
WEAK const PinMap PinMap_UART_RTS[] = {
|
||||||
|
{PA_1, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
|
||||||
|
// {PA_12, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
|
||||||
|
// {PB_14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
|
||||||
|
{PD_4, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
|
||||||
|
{PD_12, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef HAL_UART_MODULE_ENABLED
|
||||||
|
WEAK const PinMap PinMap_UART_CTS[] = {
|
||||||
|
{PA_0, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
|
||||||
|
// {PA_11, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
|
||||||
|
{PB_13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
|
||||||
|
{PD_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
|
||||||
|
{PD_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//*** SPI ***
|
||||||
|
|
||||||
|
#ifdef HAL_SPI_MODULE_ENABLED
|
||||||
|
WEAK const PinMap PinMap_SPI_MOSI[] = {
|
||||||
|
{PA_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
|
||||||
|
// {PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
|
||||||
|
{PB_5, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
|
||||||
|
// {PB_15, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
|
||||||
|
{PC_3, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
|
||||||
|
{PC_12, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef HAL_SPI_MODULE_ENABLED
|
||||||
|
WEAK const PinMap PinMap_SPI_MISO[] = {
|
||||||
|
{PA_6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
|
||||||
|
// {PB_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
|
||||||
|
{PB_4, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
|
||||||
|
// {PB_14, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
|
||||||
|
{PC_2, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
|
||||||
|
{PC_11, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef HAL_SPI_MODULE_ENABLED
|
||||||
|
WEAK const PinMap PinMap_SPI_SCLK[] = {
|
||||||
|
{PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
|
||||||
|
// {PB_3, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
|
||||||
|
{PB_3, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
|
||||||
|
{PB_10, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
|
||||||
|
{PB_13, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
|
||||||
|
{PC_10, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef HAL_SPI_MODULE_ENABLED
|
||||||
|
WEAK const PinMap PinMap_SPI_SSEL[] = {
|
||||||
|
{PA_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
|
||||||
|
// {PA_4, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
|
||||||
|
// {PA_15, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
|
||||||
|
{PA_15, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
|
||||||
|
{PB_9, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
|
||||||
|
{PB_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//*** CAN ***
|
||||||
|
|
||||||
|
#ifdef HAL_CAN_MODULE_ENABLED
|
||||||
|
WEAK const PinMap PinMap_CAN_RD[] = {
|
||||||
|
{PA_11, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)},
|
||||||
|
{PB_5, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)},
|
||||||
|
{PB_8, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)},
|
||||||
|
{PB_12, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)},
|
||||||
|
{PD_0, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)},
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef HAL_CAN_MODULE_ENABLED
|
||||||
|
WEAK const PinMap PinMap_CAN_TD[] = {
|
||||||
|
{PA_12, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)},
|
||||||
|
{PB_6, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)},
|
||||||
|
{PB_9, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)},
|
||||||
|
{PB_13, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)},
|
||||||
|
{PD_1, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)},
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//*** ETHERNET ***
|
||||||
|
|
||||||
|
#ifdef HAL_ETH_MODULE_ENABLED
|
||||||
|
WEAK const PinMap PinMap_Ethernet[] = {
|
||||||
|
{PA_0, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_CRS
|
||||||
|
{PA_1, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_REF_CLK|ETH_RX_CLK
|
||||||
|
{PA_2, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_MDIO
|
||||||
|
{PA_3, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_COL
|
||||||
|
{PA_7, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_CRS_DV|ETH_RX_DV
|
||||||
|
{PB_0, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD2
|
||||||
|
{PB_1, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD3
|
||||||
|
{PB_5, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_PPS_OUT
|
||||||
|
{PB_8, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD3
|
||||||
|
{PB_10, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RX_ER
|
||||||
|
{PB_11, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TX_EN
|
||||||
|
{PB_12, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD0
|
||||||
|
{PB_13, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD1
|
||||||
|
{PC_1, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_MDC
|
||||||
|
{PC_2, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD2
|
||||||
|
{PC_3, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TX_CLK
|
||||||
|
{PC_4, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD0
|
||||||
|
{PC_5, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD1
|
||||||
|
{PE_2, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD3
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//*** No QUADSPI ***
|
||||||
|
|
||||||
|
//*** USB ***
|
||||||
|
|
||||||
|
#ifdef HAL_PCD_MODULE_ENABLED
|
||||||
|
WEAK const PinMap PinMap_USB_OTG_FS[] = {
|
||||||
|
// {PA_8, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_SOF
|
||||||
|
// {PA_9, USB_OTG_FS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_FS_VBUS
|
||||||
|
// {PA_10, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_ID
|
||||||
|
{PA_11, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DM
|
||||||
|
{PA_12, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DP
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef HAL_PCD_MODULE_ENABLED
|
||||||
|
WEAK const PinMap PinMap_USB_OTG_HS[] = {
|
||||||
|
#ifdef USE_USB_HS_IN_FS
|
||||||
|
// {PA_4, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_SOF
|
||||||
|
// {PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_ID
|
||||||
|
// {PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_HS_VBUS
|
||||||
|
{PB_14, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DM
|
||||||
|
{PB_15, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DP
|
||||||
|
#else
|
||||||
|
{PA_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D0
|
||||||
|
{PA_5, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_CK
|
||||||
|
{PB_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D1
|
||||||
|
{PB_1, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D2
|
||||||
|
{PB_5, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D7
|
||||||
|
{PB_10, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D3
|
||||||
|
{PB_11, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D4
|
||||||
|
{PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D5
|
||||||
|
{PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D6
|
||||||
|
{PC_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_STP
|
||||||
|
{PC_2, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_DIR
|
||||||
|
{PC_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_NXT
|
||||||
|
#endif /* USE_USB_HS_IN_FS */
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//*** SD ***
|
||||||
|
|
||||||
|
#ifdef HAL_SD_MODULE_ENABLED
|
||||||
|
WEAK const PinMap PinMap_SD[] = {
|
||||||
|
{PB_8, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D4
|
||||||
|
{PB_9, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D5
|
||||||
|
{PC_6, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D6
|
||||||
|
{PC_7, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D7
|
||||||
|
{PC_8, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D0
|
||||||
|
{PC_9, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D1
|
||||||
|
{PC_10, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D2
|
||||||
|
{PC_11, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D3
|
||||||
|
{PC_12, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF12_SDIO)}, // SDIO_CK
|
||||||
|
{PD_2, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF12_SDIO)}, // SDIO_CMD
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
#endif
|
|
@ -0,0 +1,50 @@
|
||||||
|
/* SYS_WKUP */
|
||||||
|
#ifdef PWR_WAKEUP_PIN1
|
||||||
|
SYS_WKUP1 = PA_0,
|
||||||
|
#endif
|
||||||
|
#ifdef PWR_WAKEUP_PIN2
|
||||||
|
SYS_WKUP2 = NC,
|
||||||
|
#endif
|
||||||
|
#ifdef PWR_WAKEUP_PIN3
|
||||||
|
SYS_WKUP3 = NC,
|
||||||
|
#endif
|
||||||
|
#ifdef PWR_WAKEUP_PIN4
|
||||||
|
SYS_WKUP4 = NC,
|
||||||
|
#endif
|
||||||
|
#ifdef PWR_WAKEUP_PIN5
|
||||||
|
SYS_WKUP5 = NC,
|
||||||
|
#endif
|
||||||
|
#ifdef PWR_WAKEUP_PIN6
|
||||||
|
SYS_WKUP6 = NC,
|
||||||
|
#endif
|
||||||
|
#ifdef PWR_WAKEUP_PIN7
|
||||||
|
SYS_WKUP7 = NC,
|
||||||
|
#endif
|
||||||
|
#ifdef PWR_WAKEUP_PIN8
|
||||||
|
SYS_WKUP8 = NC,
|
||||||
|
#endif
|
||||||
|
/* USB */
|
||||||
|
#ifdef USBCON
|
||||||
|
USB_OTG_FS_SOF = PA_8,
|
||||||
|
USB_OTG_FS_VBUS = PA_9,
|
||||||
|
USB_OTG_FS_ID = PA_10,
|
||||||
|
USB_OTG_FS_DM = PA_11,
|
||||||
|
USB_OTG_FS_DP = PA_12,
|
||||||
|
USB_OTG_HS_ULPI_D0 = PA_3,
|
||||||
|
USB_OTG_HS_SOF = PA_4,
|
||||||
|
USB_OTG_HS_ULPI_CK = PA_5,
|
||||||
|
USB_OTG_HS_ULPI_D1 = PB_0,
|
||||||
|
USB_OTG_HS_ULPI_D2 = PB_1,
|
||||||
|
USB_OTG_HS_ULPI_D7 = PB_5,
|
||||||
|
USB_OTG_HS_ULPI_D3 = PB_10,
|
||||||
|
USB_OTG_HS_ULPI_D4 = PB_11,
|
||||||
|
USB_OTG_HS_ID = PB_12,
|
||||||
|
USB_OTG_HS_ULPI_D5 = PB_12,
|
||||||
|
USB_OTG_HS_ULPI_D6 = PB_13,
|
||||||
|
USB_OTG_HS_VBUS = PB_13,
|
||||||
|
USB_OTG_HS_DM = PB_14,
|
||||||
|
USB_OTG_HS_DP = PB_15,
|
||||||
|
USB_OTG_HS_ULPI_STP = PC_0,
|
||||||
|
USB_OTG_HS_ULPI_DIR = PC_2,
|
||||||
|
USB_OTG_HS_ULPI_NXT = PC_3,
|
||||||
|
#endif
|
|
@ -0,0 +1,495 @@
|
||||||
|
/**
|
||||||
|
******************************************************************************
|
||||||
|
* @file stm32f4xx_hal_conf_template.h
|
||||||
|
* @author MCD Application Team
|
||||||
|
* @brief HAL configuration template file.
|
||||||
|
* This file should be copied to the application folder and renamed
|
||||||
|
* to stm32f4xx_hal_conf.h.
|
||||||
|
******************************************************************************
|
||||||
|
* @attention
|
||||||
|
*
|
||||||
|
* <h2><center>© Copyright (c) 2017 STMicroelectronics.
|
||||||
|
* All rights reserved.</center></h2>
|
||||||
|
*
|
||||||
|
* This software component is licensed by ST under BSD 3-Clause license,
|
||||||
|
* the "License"; You may not use this file except in compliance with the
|
||||||
|
* License. You may obtain a copy of the License at:
|
||||||
|
* opensource.org/licenses/BSD-3-Clause
|
||||||
|
*
|
||||||
|
******************************************************************************
|
||||||
|
*/
|
||||||
|
|
||||||
|
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||||
|
#ifndef __STM32F4xx_HAL_CONF_H
|
||||||
|
#define __STM32F4xx_HAL_CONF_H
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* Exported types ------------------------------------------------------------*/
|
||||||
|
/* Exported constants --------------------------------------------------------*/
|
||||||
|
|
||||||
|
/* ########################## Module Selection ############################## */
|
||||||
|
/**
|
||||||
|
* @brief This is the list of modules to be used in the HAL driver
|
||||||
|
*/
|
||||||
|
#define HAL_MODULE_ENABLED
|
||||||
|
#define HAL_ADC_MODULE_ENABLED
|
||||||
|
// #define HAL_CAN_MODULE_ENABLED
|
||||||
|
/* #define HAL_CAN_LEGACY_MODULE_ENABLED */
|
||||||
|
#define HAL_CRC_MODULE_ENABLED
|
||||||
|
// #define HAL_CEC_MODULE_ENABLED
|
||||||
|
// #define HAL_CRYP_MODULE_ENABLED
|
||||||
|
#define HAL_DAC_MODULE_ENABLED
|
||||||
|
// #define HAL_DCMI_MODULE_ENABLED
|
||||||
|
#define HAL_DMA_MODULE_ENABLED
|
||||||
|
// #define HAL_DMA2D_MODULE_ENABLED
|
||||||
|
// #define HAL_ETH_MODULE_ENABLED
|
||||||
|
// #define HAL_FLASH_MODULE_ENABLED
|
||||||
|
// #define HAL_NAND_MODULE_ENABLED
|
||||||
|
// #define HAL_NOR_MODULE_ENABLED
|
||||||
|
// #define HAL_PCCARD_MODULE_ENABLED
|
||||||
|
// #define HAL_SRAM_MODULE_ENABLED
|
||||||
|
// #define HAL_SDRAM_MODULE_ENABLED
|
||||||
|
// #define HAL_HASH_MODULE_ENABLED
|
||||||
|
#define HAL_GPIO_MODULE_ENABLED
|
||||||
|
// #define HAL_EXTI_MODULE_ENABLED
|
||||||
|
#define HAL_I2C_MODULE_ENABLED
|
||||||
|
// #define HAL_SMBUS_MODULE_ENABLED
|
||||||
|
// #define HAL_I2S_MODULE_ENABLED
|
||||||
|
// #define HAL_IWDG_MODULE_ENABLED
|
||||||
|
// #define HAL_LTDC_MODULE_ENABLED
|
||||||
|
// #define HAL_DSI_MODULE_ENABLED
|
||||||
|
#define HAL_PWR_MODULE_ENABLED
|
||||||
|
// #define HAL_QSPI_MODULE_ENABLED
|
||||||
|
#define HAL_RCC_MODULE_ENABLED
|
||||||
|
// #define HAL_RNG_MODULE_ENABLED
|
||||||
|
// #define HAL_RTC_MODULE_ENABLED
|
||||||
|
// #define HAL_SAI_MODULE_ENABLED
|
||||||
|
// #define HAL_SD_MODULE_ENABLED
|
||||||
|
#define HAL_SPI_MODULE_ENABLED
|
||||||
|
#define HAL_TIM_MODULE_ENABLED
|
||||||
|
// #define HAL_UART_MODULE_ENABLED
|
||||||
|
#define HAL_USART_MODULE_ENABLED
|
||||||
|
// #define HAL_IRDA_MODULE_ENABLED
|
||||||
|
// #define HAL_SMARTCARD_MODULE_ENABLED
|
||||||
|
// #define HAL_WWDG_MODULE_ENABLED
|
||||||
|
#define HAL_CORTEX_MODULE_ENABLED
|
||||||
|
// #define HAL_PCD_MODULE_ENABLED
|
||||||
|
// #define HAL_HCD_MODULE_ENABLED
|
||||||
|
// #define HAL_FMPI2C_MODULE_ENABLED
|
||||||
|
// #define HAL_SPDIFRX_MODULE_ENABLED
|
||||||
|
// #define HAL_DFSDM_MODULE_ENABLED
|
||||||
|
// #define HAL_LPTIM_MODULE_ENABLED
|
||||||
|
// #define HAL_MMC_MODULE_ENABLED
|
||||||
|
|
||||||
|
/* ########################## HSE/HSI Values adaptation ##################### */
|
||||||
|
/**
|
||||||
|
* @brief Adjust the value of External High Speed oscillator (HSE) used in your application.
|
||||||
|
* This value is used by the RCC HAL module to compute the system frequency
|
||||||
|
* (when HSE is used as system clock source, directly or through the PLL).
|
||||||
|
*/
|
||||||
|
#if !defined (HSE_VALUE)
|
||||||
|
#define HSE_VALUE 25000000U /*!< Value of the External oscillator in Hz */
|
||||||
|
#endif /* HSE_VALUE */
|
||||||
|
|
||||||
|
#if !defined (HSE_STARTUP_TIMEOUT)
|
||||||
|
#define HSE_STARTUP_TIMEOUT 100U /*!< Time out for HSE start up, in ms */
|
||||||
|
#endif /* HSE_STARTUP_TIMEOUT */
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Internal High Speed oscillator (HSI) value.
|
||||||
|
* This value is used by the RCC HAL module to compute the system frequency
|
||||||
|
* (when HSI is used as system clock source, directly or through the PLL).
|
||||||
|
*/
|
||||||
|
#if !defined (HSI_VALUE)
|
||||||
|
#define HSI_VALUE 16000000U /*!< Value of the Internal oscillator in Hz */
|
||||||
|
#endif /* HSI_VALUE */
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Internal Low Speed oscillator (LSI) value.
|
||||||
|
*/
|
||||||
|
#if !defined (LSI_VALUE)
|
||||||
|
#define LSI_VALUE 32000U /*!< LSI Typical Value in Hz */
|
||||||
|
#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz
|
||||||
|
The real value may vary depending on the variations
|
||||||
|
in voltage and temperature. */
|
||||||
|
/**
|
||||||
|
* @brief External Low Speed oscillator (LSE) value.
|
||||||
|
*/
|
||||||
|
#if !defined (LSE_VALUE)
|
||||||
|
#define LSE_VALUE 32768U /*!< Value of the External Low Speed oscillator in Hz */
|
||||||
|
#endif /* LSE_VALUE */
|
||||||
|
|
||||||
|
#if !defined (LSE_STARTUP_TIMEOUT)
|
||||||
|
#define LSE_STARTUP_TIMEOUT 5000U /*!< Time out for LSE start up, in ms */
|
||||||
|
#endif /* LSE_STARTUP_TIMEOUT */
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief External clock source for I2S peripheral
|
||||||
|
* This value is used by the I2S HAL module to compute the I2S clock source
|
||||||
|
* frequency, this source is inserted directly through I2S_CKIN pad.
|
||||||
|
*/
|
||||||
|
#if !defined (EXTERNAL_CLOCK_VALUE)
|
||||||
|
#define EXTERNAL_CLOCK_VALUE 12288000U /*!< Value of the External oscillator in Hz*/
|
||||||
|
#endif /* EXTERNAL_CLOCK_VALUE */
|
||||||
|
|
||||||
|
/* Tip: To avoid modifying this file each time you need to use different HSE,
|
||||||
|
=== you can define the HSE value in your toolchain compiler preprocessor. */
|
||||||
|
|
||||||
|
/* ########################### System Configuration ######################### */
|
||||||
|
/**
|
||||||
|
* @brief This is the HAL system configuration section
|
||||||
|
*/
|
||||||
|
#define VDD_VALUE 3300U /*!< Value of VDD in mv */
|
||||||
|
#define TICK_INT_PRIORITY 0x0FU /*!< tick interrupt priority */
|
||||||
|
#define USE_RTOS 0U
|
||||||
|
#define PREFETCH_ENABLE 1U
|
||||||
|
#define INSTRUCTION_CACHE_ENABLE 1U
|
||||||
|
#define DATA_CACHE_ENABLE 1U
|
||||||
|
|
||||||
|
#define USE_HAL_ADC_REGISTER_CALLBACKS 0U /* ADC register callback disabled */
|
||||||
|
#define USE_HAL_CAN_REGISTER_CALLBACKS 0U /* CAN register callback disabled */
|
||||||
|
#define USE_HAL_CEC_REGISTER_CALLBACKS 0U /* CEC register callback disabled */
|
||||||
|
#define USE_HAL_CRYP_REGISTER_CALLBACKS 0U /* CRYP register callback disabled */
|
||||||
|
#define USE_HAL_DAC_REGISTER_CALLBACKS 0U /* DAC register callback disabled */
|
||||||
|
#define USE_HAL_DCMI_REGISTER_CALLBACKS 0U /* DCMI register callback disabled */
|
||||||
|
#define USE_HAL_DFSDM_REGISTER_CALLBACKS 0U /* DFSDM register callback disabled */
|
||||||
|
#define USE_HAL_DMA2D_REGISTER_CALLBACKS 0U /* DMA2D register callback disabled */
|
||||||
|
#define USE_HAL_DSI_REGISTER_CALLBACKS 0U /* DSI register callback disabled */
|
||||||
|
#define USE_HAL_ETH_REGISTER_CALLBACKS 0U /* ETH register callback disabled */
|
||||||
|
#define USE_HAL_HASH_REGISTER_CALLBACKS 0U /* HASH register callback disabled */
|
||||||
|
#define USE_HAL_HCD_REGISTER_CALLBACKS 0U /* HCD register callback disabled */
|
||||||
|
#define USE_HAL_I2C_REGISTER_CALLBACKS 0U /* I2C register callback disabled */
|
||||||
|
#define USE_HAL_FMPI2C_REGISTER_CALLBACKS 0U /* FMPI2C register callback disabled */
|
||||||
|
#define USE_HAL_I2S_REGISTER_CALLBACKS 0U /* I2S register callback disabled */
|
||||||
|
#define USE_HAL_IRDA_REGISTER_CALLBACKS 0U /* IRDA register callback disabled */
|
||||||
|
#define USE_HAL_LPTIM_REGISTER_CALLBACKS 0U /* LPTIM register callback disabled */
|
||||||
|
#define USE_HAL_LTDC_REGISTER_CALLBACKS 0U /* LTDC register callback disabled */
|
||||||
|
#define USE_HAL_MMC_REGISTER_CALLBACKS 0U /* MMC register callback disabled */
|
||||||
|
#define USE_HAL_NAND_REGISTER_CALLBACKS 0U /* NAND register callback disabled */
|
||||||
|
#define USE_HAL_NOR_REGISTER_CALLBACKS 0U /* NOR register callback disabled */
|
||||||
|
#define USE_HAL_PCCARD_REGISTER_CALLBACKS 0U /* PCCARD register callback disabled */
|
||||||
|
#define USE_HAL_PCD_REGISTER_CALLBACKS 0U /* PCD register callback disabled */
|
||||||
|
#define USE_HAL_QSPI_REGISTER_CALLBACKS 0U /* QSPI register callback disabled */
|
||||||
|
#define USE_HAL_RNG_REGISTER_CALLBACKS 0U /* RNG register callback disabled */
|
||||||
|
#define USE_HAL_RTC_REGISTER_CALLBACKS 0U /* RTC register callback disabled */
|
||||||
|
#define USE_HAL_SAI_REGISTER_CALLBACKS 0U /* SAI register callback disabled */
|
||||||
|
#define USE_HAL_SD_REGISTER_CALLBACKS 0U /* SD register callback disabled */
|
||||||
|
#define USE_HAL_SMARTCARD_REGISTER_CALLBACKS 0U /* SMARTCARD register callback disabled */
|
||||||
|
#define USE_HAL_SDRAM_REGISTER_CALLBACKS 0U /* SDRAM register callback disabled */
|
||||||
|
#define USE_HAL_SRAM_REGISTER_CALLBACKS 0U /* SRAM register callback disabled */
|
||||||
|
#define USE_HAL_SPDIFRX_REGISTER_CALLBACKS 0U /* SPDIFRX register callback disabled */
|
||||||
|
#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0U /* SMBUS register callback disabled */
|
||||||
|
#define USE_HAL_SPI_REGISTER_CALLBACKS 0U /* SPI register callback disabled */
|
||||||
|
#define USE_HAL_TIM_REGISTER_CALLBACKS 0U /* TIM register callback disabled */
|
||||||
|
#define USE_HAL_UART_REGISTER_CALLBACKS 0U /* UART register callback disabled */
|
||||||
|
#define USE_HAL_USART_REGISTER_CALLBACKS 0U /* USART register callback disabled */
|
||||||
|
#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U /* WWDG register callback disabled */
|
||||||
|
|
||||||
|
/* ########################## Assert Selection ############################## */
|
||||||
|
/**
|
||||||
|
* @brief Uncomment the line below to expanse the "assert_param" macro in the
|
||||||
|
* HAL drivers code
|
||||||
|
*/
|
||||||
|
// #define USE_FULL_ASSERT 1U
|
||||||
|
|
||||||
|
/* ################## Ethernet peripheral configuration ##################### */
|
||||||
|
|
||||||
|
/* Section 1 : Ethernet peripheral configuration */
|
||||||
|
|
||||||
|
/* MAC ADDRESS: MAC_ADDR0:MAC_ADDR1:MAC_ADDR2:MAC_ADDR3:MAC_ADDR4:MAC_ADDR5 */
|
||||||
|
#define MAC_ADDR0 2U
|
||||||
|
#define MAC_ADDR1 0U
|
||||||
|
#define MAC_ADDR2 0U
|
||||||
|
#define MAC_ADDR3 0U
|
||||||
|
#define MAC_ADDR4 0U
|
||||||
|
#define MAC_ADDR5 0U
|
||||||
|
|
||||||
|
/* Definition of the Ethernet driver buffers size and count */
|
||||||
|
#define ETH_RX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for receive */
|
||||||
|
#define ETH_TX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for transmit */
|
||||||
|
#define ETH_RXBUFNB 4U /* 4 Rx buffers of size ETH_RX_BUF_SIZE */
|
||||||
|
#define ETH_TXBUFNB 4U /* 4 Tx buffers of size ETH_TX_BUF_SIZE */
|
||||||
|
|
||||||
|
/* Section 2: PHY configuration section */
|
||||||
|
|
||||||
|
/* DP83848 PHY Address*/
|
||||||
|
#define DP83848_PHY_ADDRESS 0x01U
|
||||||
|
/* PHY Reset delay these values are based on a 1 ms Systick interrupt*/
|
||||||
|
#define PHY_RESET_DELAY 0x000000FFU
|
||||||
|
/* PHY Configuration delay */
|
||||||
|
#define PHY_CONFIG_DELAY 0x00000FFFU
|
||||||
|
|
||||||
|
#define PHY_READ_TO 0x0000FFFFU
|
||||||
|
#define PHY_WRITE_TO 0x0000FFFFU
|
||||||
|
|
||||||
|
/* Section 3: Common PHY Registers */
|
||||||
|
|
||||||
|
#define PHY_BCR ((uint16_t)0x0000) /*!< Transceiver Basic Control Register */
|
||||||
|
#define PHY_BSR ((uint16_t)0x0001) /*!< Transceiver Basic Status Register */
|
||||||
|
|
||||||
|
#define PHY_RESET ((uint16_t)0x8000) /*!< PHY Reset */
|
||||||
|
#define PHY_LOOPBACK ((uint16_t)0x4000) /*!< Select loop-back mode */
|
||||||
|
#define PHY_FULLDUPLEX_100M ((uint16_t)0x2100) /*!< Set the full-duplex mode at 100 Mb/s */
|
||||||
|
#define PHY_HALFDUPLEX_100M ((uint16_t)0x2000) /*!< Set the half-duplex mode at 100 Mb/s */
|
||||||
|
#define PHY_FULLDUPLEX_10M ((uint16_t)0x0100) /*!< Set the full-duplex mode at 10 Mb/s */
|
||||||
|
#define PHY_HALFDUPLEX_10M ((uint16_t)0x0000) /*!< Set the half-duplex mode at 10 Mb/s */
|
||||||
|
#define PHY_AUTONEGOTIATION ((uint16_t)0x1000) /*!< Enable auto-negotiation function */
|
||||||
|
#define PHY_RESTART_AUTONEGOTIATION ((uint16_t)0x0200) /*!< Restart auto-negotiation function */
|
||||||
|
#define PHY_POWERDOWN ((uint16_t)0x0800) /*!< Select the power down mode */
|
||||||
|
#define PHY_ISOLATE ((uint16_t)0x0400) /*!< Isolate PHY from MII */
|
||||||
|
|
||||||
|
#define PHY_AUTONEGO_COMPLETE ((uint16_t)0x0020) /*!< Auto-Negotiation process completed */
|
||||||
|
#define PHY_LINKED_STATUS ((uint16_t)0x0004) /*!< Valid link established */
|
||||||
|
#define PHY_JABBER_DETECTION ((uint16_t)0x0002) /*!< Jabber condition detected */
|
||||||
|
|
||||||
|
/* Section 4: Extended PHY Registers */
|
||||||
|
|
||||||
|
#define PHY_SR ((uint16_t)0x0010) /*!< PHY status register Offset */
|
||||||
|
#define PHY_MICR ((uint16_t)0x0011) /*!< MII Interrupt Control Register */
|
||||||
|
#define PHY_MISR ((uint16_t)0x0012) /*!< MII Interrupt Status and Misc. Control Register */
|
||||||
|
|
||||||
|
#define PHY_LINK_STATUS ((uint16_t)0x0001) /*!< PHY Link mask */
|
||||||
|
#define PHY_SPEED_STATUS ((uint16_t)0x0002) /*!< PHY Speed mask */
|
||||||
|
#define PHY_DUPLEX_STATUS ((uint16_t)0x0004) /*!< PHY Duplex mask */
|
||||||
|
|
||||||
|
#define PHY_MICR_INT_EN ((uint16_t)0x0002) /*!< PHY Enable interrupts */
|
||||||
|
#define PHY_MICR_INT_OE ((uint16_t)0x0001) /*!< PHY Enable output interrupt events */
|
||||||
|
|
||||||
|
#define PHY_MISR_LINK_INT_EN ((uint16_t)0x0020) /*!< Enable Interrupt on change of link status */
|
||||||
|
#define PHY_LINK_INTERRUPT ((uint16_t)0x2000) /*!< PHY link status interrupt mask */
|
||||||
|
|
||||||
|
/* ################## SPI peripheral configuration ########################## */
|
||||||
|
|
||||||
|
/* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver
|
||||||
|
* Activated: CRC code is present inside driver
|
||||||
|
* Deactivated: CRC code cleaned from driver
|
||||||
|
*/
|
||||||
|
|
||||||
|
#define USE_SPI_CRC 0U
|
||||||
|
|
||||||
|
/* Includes ------------------------------------------------------------------*/
|
||||||
|
/**
|
||||||
|
* @brief Include module's header file
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifdef HAL_RCC_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_rcc.h"
|
||||||
|
#endif /* HAL_RCC_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_GPIO_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_gpio.h"
|
||||||
|
#endif /* HAL_GPIO_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_EXTI_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_exti.h"
|
||||||
|
#endif /* HAL_EXTI_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_DMA_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_dma.h"
|
||||||
|
#endif /* HAL_DMA_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_CORTEX_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_cortex.h"
|
||||||
|
#endif /* HAL_CORTEX_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_ADC_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_adc.h"
|
||||||
|
#endif /* HAL_ADC_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_CAN_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_can.h"
|
||||||
|
#endif /* HAL_CAN_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_CAN_LEGACY_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_can_legacy.h"
|
||||||
|
#endif /* HAL_CAN_LEGACY_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_CRC_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_crc.h"
|
||||||
|
#endif /* HAL_CRC_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_CRYP_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_cryp.h"
|
||||||
|
#endif /* HAL_CRYP_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_DMA2D_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_dma2d.h"
|
||||||
|
#endif /* HAL_DMA2D_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_DAC_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_dac.h"
|
||||||
|
#endif /* HAL_DAC_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_DCMI_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_dcmi.h"
|
||||||
|
#endif /* HAL_DCMI_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_ETH_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_eth.h"
|
||||||
|
#endif /* HAL_ETH_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_FLASH_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_flash.h"
|
||||||
|
#endif /* HAL_FLASH_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_SRAM_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_sram.h"
|
||||||
|
#endif /* HAL_SRAM_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_NOR_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_nor.h"
|
||||||
|
#endif /* HAL_NOR_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_NAND_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_nand.h"
|
||||||
|
#endif /* HAL_NAND_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_PCCARD_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_pccard.h"
|
||||||
|
#endif /* HAL_PCCARD_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_SDRAM_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_sdram.h"
|
||||||
|
#endif /* HAL_SDRAM_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_HASH_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_hash.h"
|
||||||
|
#endif /* HAL_HASH_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_I2C_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_i2c.h"
|
||||||
|
#endif /* HAL_I2C_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_SMBUS_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_smbus.h"
|
||||||
|
#endif /* HAL_SMBUS_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_I2S_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_i2s.h"
|
||||||
|
#endif /* HAL_I2S_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_IWDG_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_iwdg.h"
|
||||||
|
#endif /* HAL_IWDG_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_LTDC_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_ltdc.h"
|
||||||
|
#endif /* HAL_LTDC_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_PWR_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_pwr.h"
|
||||||
|
#endif /* HAL_PWR_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_RNG_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_rng.h"
|
||||||
|
#endif /* HAL_RNG_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_RTC_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_rtc.h"
|
||||||
|
#endif /* HAL_RTC_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_SAI_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_sai.h"
|
||||||
|
#endif /* HAL_SAI_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_SD_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_sd.h"
|
||||||
|
#endif /* HAL_SD_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_SPI_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_spi.h"
|
||||||
|
#endif /* HAL_SPI_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_TIM_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_tim.h"
|
||||||
|
#endif /* HAL_TIM_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_UART_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_uart.h"
|
||||||
|
#endif /* HAL_UART_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_USART_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_usart.h"
|
||||||
|
#endif /* HAL_USART_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_IRDA_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_irda.h"
|
||||||
|
#endif /* HAL_IRDA_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_SMARTCARD_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_smartcard.h"
|
||||||
|
#endif /* HAL_SMARTCARD_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_WWDG_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_wwdg.h"
|
||||||
|
#endif /* HAL_WWDG_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_PCD_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_pcd.h"
|
||||||
|
#endif /* HAL_PCD_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_HCD_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_hcd.h"
|
||||||
|
#endif /* HAL_HCD_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_DSI_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_dsi.h"
|
||||||
|
#endif /* HAL_DSI_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_QSPI_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_qspi.h"
|
||||||
|
#endif /* HAL_QSPI_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_CEC_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_cec.h"
|
||||||
|
#endif /* HAL_CEC_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_FMPI2C_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_fmpi2c.h"
|
||||||
|
#endif /* HAL_FMPI2C_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_SPDIFRX_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_spdifrx.h"
|
||||||
|
#endif /* HAL_SPDIFRX_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_DFSDM_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_dfsdm.h"
|
||||||
|
#endif /* HAL_DFSDM_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_LPTIM_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_lptim.h"
|
||||||
|
#endif /* HAL_LPTIM_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_MMC_MODULE_ENABLED
|
||||||
|
#include "stm32f4xx_hal_mmc.h"
|
||||||
|
#endif /* HAL_MMC_MODULE_ENABLED */
|
||||||
|
|
||||||
|
/* Exported macro ------------------------------------------------------------*/
|
||||||
|
#ifdef USE_FULL_ASSERT
|
||||||
|
/**
|
||||||
|
* @brief The assert_param macro is used for function's parameters check.
|
||||||
|
* @param expr If expr is false, it calls assert_failed function
|
||||||
|
* which reports the name of the source file and the source
|
||||||
|
* line number of the call that failed.
|
||||||
|
* If expr is true, it returns no value.
|
||||||
|
* @retval None
|
||||||
|
*/
|
||||||
|
#define assert_param(expr) ((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__))
|
||||||
|
/* Exported functions ------------------------------------------------------- */
|
||||||
|
void assert_failed(uint8_t* file, uint32_t line);
|
||||||
|
#else
|
||||||
|
#define assert_param(expr) ((void)0U)
|
||||||
|
#endif /* USE_FULL_ASSERT */
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif /* __STM32F4xx_HAL_CONF_H */
|
||||||
|
|
||||||
|
|
||||||
|
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
203
buildroot/share/PlatformIO/variants/MARLIN_F4x7Vx/ldscript.ld
Normal file
203
buildroot/share/PlatformIO/variants/MARLIN_F4x7Vx/ldscript.ld
Normal file
|
@ -0,0 +1,203 @@
|
||||||
|
/*
|
||||||
|
******************************************************************************
|
||||||
|
**
|
||||||
|
** File : LinkerScript.ld
|
||||||
|
**
|
||||||
|
** Abstract : Linker script for STM32F4x7Vx Device with
|
||||||
|
** 512/1024KByte FLASH, 192KByte RAM
|
||||||
|
**
|
||||||
|
** Set heap size, stack size and stack location according
|
||||||
|
** to application requirements.
|
||||||
|
**
|
||||||
|
** Set memory bank area and size if external memory is used.
|
||||||
|
**
|
||||||
|
** Target : STMicroelectronics STM32
|
||||||
|
**
|
||||||
|
** Distribution: The file is distributed “as is,” without any warranty
|
||||||
|
** of any kind.
|
||||||
|
**
|
||||||
|
*****************************************************************************
|
||||||
|
** @attention
|
||||||
|
**
|
||||||
|
** <h2><center>© COPYRIGHT(c) 2019 STMicroelectronics</center></h2>
|
||||||
|
**
|
||||||
|
** Redistribution and use in source and binary forms, with or without modification,
|
||||||
|
** are permitted provided that the following conditions are met:
|
||||||
|
** 1. Redistributions of source code must retain the above copyright notice,
|
||||||
|
** this list of conditions and the following disclaimer.
|
||||||
|
** 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||||
|
** this list of conditions and the following disclaimer in the documentation
|
||||||
|
** and/or other materials provided with the distribution.
|
||||||
|
** 3. Neither the name of STMicroelectronics nor the names of its contributors
|
||||||
|
** may be used to endorse or promote products derived from this software
|
||||||
|
** without specific prior written permission.
|
||||||
|
**
|
||||||
|
** THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
|
||||||
|
** AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
||||||
|
** IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
|
||||||
|
** DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
|
||||||
|
** FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||||
|
** DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
|
||||||
|
** SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||||
|
** CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
|
||||||
|
** OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
|
||||||
|
** OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
**
|
||||||
|
*****************************************************************************
|
||||||
|
*/
|
||||||
|
|
||||||
|
/* Entry Point */
|
||||||
|
ENTRY(Reset_Handler)
|
||||||
|
|
||||||
|
/* Highest address of the user mode stack */
|
||||||
|
_estack = 0x20000000 + LD_MAX_DATA_SIZE; /* end of RAM */
|
||||||
|
/* Generate a link error if heap and stack don't fit into RAM */
|
||||||
|
_Min_Heap_Size = 0x200; /* required amount of heap */
|
||||||
|
_Min_Stack_Size = 0x400; /* required amount of stack */
|
||||||
|
|
||||||
|
/* Specify the memory areas */
|
||||||
|
MEMORY
|
||||||
|
{
|
||||||
|
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = LD_MAX_DATA_SIZE
|
||||||
|
CCMRAM (rw) : ORIGIN = 0x10000000, LENGTH = 64K
|
||||||
|
FLASH (rx) : ORIGIN = 0x8000000 + LD_FLASH_OFFSET, LENGTH = LD_MAX_SIZE - LD_FLASH_OFFSET
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Define output sections */
|
||||||
|
SECTIONS
|
||||||
|
{
|
||||||
|
/* The startup code goes first into FLASH */
|
||||||
|
.isr_vector :
|
||||||
|
{
|
||||||
|
. = ALIGN(4);
|
||||||
|
KEEP(*(.isr_vector)) /* Startup code */
|
||||||
|
. = ALIGN(4);
|
||||||
|
} >FLASH
|
||||||
|
|
||||||
|
/* The program code and other data goes into FLASH */
|
||||||
|
.text :
|
||||||
|
{
|
||||||
|
. = ALIGN(4);
|
||||||
|
*(.text) /* .text sections (code) */
|
||||||
|
*(.text*) /* .text* sections (code) */
|
||||||
|
*(.glue_7) /* glue arm to thumb code */
|
||||||
|
*(.glue_7t) /* glue thumb to arm code */
|
||||||
|
*(.eh_frame)
|
||||||
|
|
||||||
|
KEEP (*(.init))
|
||||||
|
KEEP (*(.fini))
|
||||||
|
|
||||||
|
. = ALIGN(4);
|
||||||
|
_etext = .; /* define a global symbols at end of code */
|
||||||
|
} >FLASH
|
||||||
|
|
||||||
|
/* Constant data goes into FLASH */
|
||||||
|
.rodata :
|
||||||
|
{
|
||||||
|
. = ALIGN(4);
|
||||||
|
*(.rodata) /* .rodata sections (constants, strings, etc.) */
|
||||||
|
*(.rodata*) /* .rodata* sections (constants, strings, etc.) */
|
||||||
|
. = ALIGN(4);
|
||||||
|
} >FLASH
|
||||||
|
|
||||||
|
.ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
|
||||||
|
.ARM : {
|
||||||
|
__exidx_start = .;
|
||||||
|
*(.ARM.exidx*)
|
||||||
|
__exidx_end = .;
|
||||||
|
} >FLASH
|
||||||
|
|
||||||
|
.preinit_array :
|
||||||
|
{
|
||||||
|
PROVIDE_HIDDEN (__preinit_array_start = .);
|
||||||
|
KEEP (*(.preinit_array*))
|
||||||
|
PROVIDE_HIDDEN (__preinit_array_end = .);
|
||||||
|
} >FLASH
|
||||||
|
.init_array :
|
||||||
|
{
|
||||||
|
PROVIDE_HIDDEN (__init_array_start = .);
|
||||||
|
KEEP (*(SORT(.init_array.*)))
|
||||||
|
KEEP (*(.init_array*))
|
||||||
|
PROVIDE_HIDDEN (__init_array_end = .);
|
||||||
|
} >FLASH
|
||||||
|
.fini_array :
|
||||||
|
{
|
||||||
|
PROVIDE_HIDDEN (__fini_array_start = .);
|
||||||
|
KEEP (*(SORT(.fini_array.*)))
|
||||||
|
KEEP (*(.fini_array*))
|
||||||
|
PROVIDE_HIDDEN (__fini_array_end = .);
|
||||||
|
} >FLASH
|
||||||
|
|
||||||
|
/* used by the startup to initialize data */
|
||||||
|
_sidata = LOADADDR(.data);
|
||||||
|
|
||||||
|
/* Initialized data sections goes into RAM, load LMA copy after code */
|
||||||
|
.data :
|
||||||
|
{
|
||||||
|
. = ALIGN(4);
|
||||||
|
_sdata = .; /* create a global symbol at data start */
|
||||||
|
*(.data) /* .data sections */
|
||||||
|
*(.data*) /* .data* sections */
|
||||||
|
|
||||||
|
. = ALIGN(4);
|
||||||
|
_edata = .; /* define a global symbol at data end */
|
||||||
|
} >RAM AT> FLASH
|
||||||
|
|
||||||
|
_siccmram = LOADADDR(.ccmram);
|
||||||
|
|
||||||
|
/* CCM-RAM section
|
||||||
|
*
|
||||||
|
* IMPORTANT NOTE!
|
||||||
|
* If initialized variables will be placed in this section,
|
||||||
|
* the startup code needs to be modified to copy the init-values.
|
||||||
|
*/
|
||||||
|
.ccmram :
|
||||||
|
{
|
||||||
|
. = ALIGN(4);
|
||||||
|
_sccmram = .; /* create a global symbol at ccmram start */
|
||||||
|
*(.ccmram)
|
||||||
|
*(.ccmram*)
|
||||||
|
|
||||||
|
. = ALIGN(4);
|
||||||
|
_eccmram = .; /* create a global symbol at ccmram end */
|
||||||
|
} >CCMRAM AT> FLASH
|
||||||
|
|
||||||
|
|
||||||
|
/* Uninitialized data section */
|
||||||
|
. = ALIGN(4);
|
||||||
|
.bss :
|
||||||
|
{
|
||||||
|
/* This is used by the startup in order to initialize the .bss secion */
|
||||||
|
_sbss = .; /* define a global symbol at bss start */
|
||||||
|
__bss_start__ = _sbss;
|
||||||
|
*(.bss)
|
||||||
|
*(.bss*)
|
||||||
|
*(COMMON)
|
||||||
|
|
||||||
|
. = ALIGN(4);
|
||||||
|
_ebss = .; /* define a global symbol at bss end */
|
||||||
|
__bss_end__ = _ebss;
|
||||||
|
} >RAM
|
||||||
|
|
||||||
|
/* User_heap_stack section, used to check that there is enough RAM left */
|
||||||
|
._user_heap_stack :
|
||||||
|
{
|
||||||
|
. = ALIGN(8);
|
||||||
|
PROVIDE ( end = . );
|
||||||
|
PROVIDE ( _end = . );
|
||||||
|
. = . + _Min_Heap_Size;
|
||||||
|
. = . + _Min_Stack_Size;
|
||||||
|
. = ALIGN(8);
|
||||||
|
} >RAM
|
||||||
|
|
||||||
|
|
||||||
|
/* Remove information from the standard libraries */
|
||||||
|
/DISCARD/ :
|
||||||
|
{
|
||||||
|
libc.a ( * )
|
||||||
|
libm.a ( * )
|
||||||
|
libgcc.a ( * )
|
||||||
|
}
|
||||||
|
|
||||||
|
.ARM.attributes 0 : { *(.ARM.attributes) }
|
||||||
|
}
|
275
buildroot/share/PlatformIO/variants/MARLIN_F4x7Vx/variant.cpp
Normal file
275
buildroot/share/PlatformIO/variants/MARLIN_F4x7Vx/variant.cpp
Normal file
|
@ -0,0 +1,275 @@
|
||||||
|
/*
|
||||||
|
Copyright (c) 2011 Arduino. All right reserved.
|
||||||
|
|
||||||
|
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
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "pins_arduino.h"
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Digital PinName array
|
||||||
|
const PinName digitalPin[] = {
|
||||||
|
PA_0, // Digital pin 0
|
||||||
|
PA_1, // Digital pin 1
|
||||||
|
PA_2, // Digital pin 2
|
||||||
|
PA_3, // Digital pin 3
|
||||||
|
PA_4, // Digital pin 4
|
||||||
|
PA_5, // Digital pin 5
|
||||||
|
PA_6, // Digital pin 6
|
||||||
|
PA_7, // Digital pin 7
|
||||||
|
PA_8, // Digital pin 8
|
||||||
|
PA_9, // Digital pin 9
|
||||||
|
PA_10, // Digital pin 10
|
||||||
|
PA_11, // Digital pin 11
|
||||||
|
PA_12, // Digital pin 12
|
||||||
|
PA_13, // Digital pin 13
|
||||||
|
PA_14, // Digital pin 14
|
||||||
|
PA_15, // Digital pin 15
|
||||||
|
|
||||||
|
PB_0, // Digital pin 16
|
||||||
|
PB_1, // Digital pin 17
|
||||||
|
PB_2, // Digital pin 18
|
||||||
|
PB_3, // Digital pin 19
|
||||||
|
PB_4, // Digital pin 20
|
||||||
|
PB_5, // Digital pin 21
|
||||||
|
PB_6, // Digital pin 22
|
||||||
|
PB_7, // Digital pin 23
|
||||||
|
PB_8, // Digital pin 24
|
||||||
|
PB_9, // Digital pin 25
|
||||||
|
PB_10, // Digital pin 26
|
||||||
|
PB_11, // Digital pin 27
|
||||||
|
PB_12, // Digital pin 28
|
||||||
|
PB_13, // Digital pin 29
|
||||||
|
PB_14, // Digital pin 30
|
||||||
|
PB_15, // Digital pin 31
|
||||||
|
|
||||||
|
PC_0, // Digital pin 32
|
||||||
|
PC_1, // Digital pin 33
|
||||||
|
PC_2, // Digital pin 34
|
||||||
|
PC_3, // Digital pin 35
|
||||||
|
PC_4, // Digital pin 36
|
||||||
|
PC_5, // Digital pin 37
|
||||||
|
PC_6, // Digital pin 38
|
||||||
|
PC_7, // Digital pin 39
|
||||||
|
PC_8, // Digital pin 40
|
||||||
|
PC_9, // Digital pin 41
|
||||||
|
PC_10, // Digital pin 42
|
||||||
|
PC_11, // Digital pin 43
|
||||||
|
PC_12, // Digital pin 44
|
||||||
|
PC_13, // Digital pin 45
|
||||||
|
PC_14, // Digital pin 46
|
||||||
|
PC_15, // Digital pin 47
|
||||||
|
|
||||||
|
PD_0, // Digital pin 48
|
||||||
|
PD_1, // Digital pin 49
|
||||||
|
PD_2, // Digital pin 50
|
||||||
|
PD_3, // Digital pin 51
|
||||||
|
PD_4, // Digital pin 52
|
||||||
|
PD_5, // Digital pin 53
|
||||||
|
PD_6, // Digital pin 54
|
||||||
|
PD_7, // Digital pin 55
|
||||||
|
PD_8, // Digital pin 56
|
||||||
|
PD_9, // Digital pin 57
|
||||||
|
PD_10, // Digital pin 58
|
||||||
|
PD_11, // Digital pin 59
|
||||||
|
PD_12, // Digital pin 60
|
||||||
|
PD_13, // Digital pin 61
|
||||||
|
PD_14, // Digital pin 62
|
||||||
|
PD_15, // Digital pin 63
|
||||||
|
|
||||||
|
PE_0, // Digital pin 64
|
||||||
|
PE_1, // Digital pin 65
|
||||||
|
PE_2, // Digital pin 66
|
||||||
|
PE_3, // Digital pin 67
|
||||||
|
PE_4, // Digital pin 68
|
||||||
|
PE_5, // Digital pin 69
|
||||||
|
PE_6, // Digital pin 70
|
||||||
|
PE_7, // Digital pin 71
|
||||||
|
PE_8, // Digital pin 72
|
||||||
|
PE_9, // Digital pin 73
|
||||||
|
PE_10, // Digital pin 74
|
||||||
|
PE_11, // Digital pin 75
|
||||||
|
PE_12, // Digital pin 76
|
||||||
|
PE_13, // Digital pin 77
|
||||||
|
PE_14, // Digital pin 78
|
||||||
|
PE_15, // Digital pin 79
|
||||||
|
|
||||||
|
PH_0, // Digital pin 80, used by the external oscillator
|
||||||
|
PH_1 // Digital pin 81, used by the external oscillator
|
||||||
|
};
|
||||||
|
|
||||||
|
// Analog (Ax) pin number array
|
||||||
|
const uint32_t analogInputPin[] = {
|
||||||
|
0, // A0, PA0
|
||||||
|
1, // A1, PA1
|
||||||
|
2, // A2, PA2
|
||||||
|
3, // A3, PA3
|
||||||
|
4, // A4, PA4
|
||||||
|
5, // A5, PA5
|
||||||
|
6, // A6, PA6
|
||||||
|
7, // A7, PA7
|
||||||
|
16, // A8, PB0
|
||||||
|
17, // A9, PB1
|
||||||
|
32, // A10, PC0
|
||||||
|
33, // A11, PC1
|
||||||
|
34, // A12, PC2
|
||||||
|
35, // A13, PC3
|
||||||
|
36, // A14, PC4
|
||||||
|
37 // A15, PC5
|
||||||
|
};
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// ----------------------------------------------------------------------------
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/*
|
||||||
|
* @brief Configures the System clock source, PLL Multiplier and Divider factors,
|
||||||
|
* AHB/APBx prescalers and Flash settings
|
||||||
|
* @note This function should be called only once the RCC clock configuration
|
||||||
|
* is reset to the default reset state (done in SystemInit() function).
|
||||||
|
* @param None
|
||||||
|
* @retval None
|
||||||
|
*/
|
||||||
|
|
||||||
|
/******************************************************************************/
|
||||||
|
/* PLL (clocked by HSE) used as System clock source */
|
||||||
|
/******************************************************************************/
|
||||||
|
static uint8_t SetSysClock_PLL_HSE(uint8_t bypass)
|
||||||
|
{
|
||||||
|
RCC_OscInitTypeDef RCC_OscInitStruct;
|
||||||
|
RCC_ClkInitTypeDef RCC_ClkInitStruct;
|
||||||
|
|
||||||
|
/* The voltage scaling allows optimizing the power consumption when the device is
|
||||||
|
clocked below the maximum system frequency, to update the voltage scaling value
|
||||||
|
regarding system frequency refer to product datasheet. */
|
||||||
|
__HAL_RCC_PWR_CLK_ENABLE();
|
||||||
|
__HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);
|
||||||
|
|
||||||
|
// Enable HSE oscillator and activate PLL with HSE as source
|
||||||
|
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
|
||||||
|
if (bypass == 0) {
|
||||||
|
RCC_OscInitStruct.HSEState = RCC_HSE_ON; // External 8 MHz xtal on OSC_IN/OSC_OUT
|
||||||
|
} else {
|
||||||
|
RCC_OscInitStruct.HSEState = RCC_HSE_BYPASS; // External 8 MHz clock on OSC_IN
|
||||||
|
}
|
||||||
|
|
||||||
|
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
|
||||||
|
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
|
||||||
|
RCC_OscInitStruct.PLL.PLLM = HSE_VALUE / 1000000L; // Expects an 8 MHz external clock by default. Redefine HSE_VALUE if not
|
||||||
|
RCC_OscInitStruct.PLL.PLLN = 336; // VCO output clock = 336 MHz (1 MHz * 336)
|
||||||
|
RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; // PLLCLK = 168 MHz (336 MHz / 2)
|
||||||
|
RCC_OscInitStruct.PLL.PLLQ = 7;
|
||||||
|
if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) {
|
||||||
|
return 0; // FAIL
|
||||||
|
}
|
||||||
|
|
||||||
|
// Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 clocks dividers
|
||||||
|
RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2;
|
||||||
|
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
|
||||||
|
RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; // 168 MHz
|
||||||
|
RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; // 42 MHz
|
||||||
|
RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; // 84 MHz
|
||||||
|
if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5) != HAL_OK) {
|
||||||
|
return 0; // FAIL
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Output clock on MCO1 pin(PA8) for debugging purpose */
|
||||||
|
/*
|
||||||
|
if (bypass == 0)
|
||||||
|
HAL_RCC_MCOConfig(RCC_MCO1, RCC_MCO1SOURCE_HSE, RCC_MCODIV_2); // 4 MHz
|
||||||
|
else
|
||||||
|
HAL_RCC_MCOConfig(RCC_MCO1, RCC_MCO1SOURCE_HSE, RCC_MCODIV_1); // 8 MHz
|
||||||
|
*/
|
||||||
|
|
||||||
|
return 1; // OK
|
||||||
|
}
|
||||||
|
|
||||||
|
/******************************************************************************/
|
||||||
|
/* PLL (clocked by HSI) used as System clock source */
|
||||||
|
/******************************************************************************/
|
||||||
|
uint8_t SetSysClock_PLL_HSI(void)
|
||||||
|
{
|
||||||
|
RCC_OscInitTypeDef RCC_OscInitStruct;
|
||||||
|
RCC_ClkInitTypeDef RCC_ClkInitStruct;
|
||||||
|
|
||||||
|
/* The voltage scaling allows optimizing the power consumption when the device is
|
||||||
|
clocked below the maximum system frequency, to update the voltage scaling value
|
||||||
|
regarding system frequency refer to product datasheet. */
|
||||||
|
__HAL_RCC_PWR_CLK_ENABLE();
|
||||||
|
__HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);
|
||||||
|
|
||||||
|
// Enable HSI oscillator and activate PLL with HSI as source
|
||||||
|
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI | RCC_OSCILLATORTYPE_HSE;
|
||||||
|
RCC_OscInitStruct.HSIState = RCC_HSI_ON;
|
||||||
|
RCC_OscInitStruct.HSEState = RCC_HSE_OFF;
|
||||||
|
RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT;
|
||||||
|
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
|
||||||
|
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI;
|
||||||
|
RCC_OscInitStruct.PLL.PLLM = 16; // VCO input clock = 1 MHz (16 MHz / 16)
|
||||||
|
RCC_OscInitStruct.PLL.PLLN = 336; // VCO output clock = 336 MHz (1 MHz * 336)
|
||||||
|
RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; // PLLCLK = 168 MHz (336 MHz / 2)
|
||||||
|
RCC_OscInitStruct.PLL.PLLQ = 7;
|
||||||
|
if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) {
|
||||||
|
return 0; // FAIL
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 clocks dividers */
|
||||||
|
RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2);
|
||||||
|
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
|
||||||
|
RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; // 168 MHz
|
||||||
|
RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; // 42 MHz
|
||||||
|
RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; // 84 MHz
|
||||||
|
if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5) != HAL_OK) {
|
||||||
|
return 0; // FAIL
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Output clock on MCO1 pin(PA8) for debugging purpose */
|
||||||
|
//HAL_RCC_MCOConfig(RCC_MCO1, RCC_MCO1SOURCE_HSI, RCC_MCODIV_1); // 16 MHz
|
||||||
|
|
||||||
|
return 1; // OK
|
||||||
|
}
|
||||||
|
|
||||||
|
WEAK void SystemClock_Config(void)
|
||||||
|
{
|
||||||
|
/* 1- If fail try to start with HSE and external xtal */
|
||||||
|
if (SetSysClock_PLL_HSE(0) == 0) {
|
||||||
|
/* 2- Try to start with HSE and external clock */
|
||||||
|
if (SetSysClock_PLL_HSE(1) == 0) {
|
||||||
|
/* 3- If fail start with HSI clock */
|
||||||
|
if (SetSysClock_PLL_HSI() == 0) {
|
||||||
|
Error_Handler();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Ensure CCM RAM clock is enabled */
|
||||||
|
__HAL_RCC_CCMDATARAMEN_CLK_ENABLE();
|
||||||
|
|
||||||
|
/* Output clock on MCO2 pin(PC9) for debugging purpose */
|
||||||
|
//HAL_RCC_MCOConfig(RCC_MCO2, RCC_MCO2SOURCE_SYSCLK, RCC_MCODIV_4);
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
199
buildroot/share/PlatformIO/variants/MARLIN_F4x7Vx/variant.h
Normal file
199
buildroot/share/PlatformIO/variants/MARLIN_F4x7Vx/variant.h
Normal file
|
@ -0,0 +1,199 @@
|
||||||
|
/*
|
||||||
|
Copyright (c) 2011 Arduino. All right reserved.
|
||||||
|
|
||||||
|
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
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef _VARIANT_ARDUINO_STM32_
|
||||||
|
#define _VARIANT_ARDUINO_STM32_
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif // __cplusplus
|
||||||
|
|
||||||
|
/*----------------------------------------------------------------------------
|
||||||
|
* Pins
|
||||||
|
*----------------------------------------------------------------------------*/
|
||||||
|
|
||||||
|
// | DIGITAL | ANALOG IN | ANALOG OUT | UART/USART | TWI | SPI | SPECIAL |
|
||||||
|
// |---------|------------|------------|-----------------------|----------------------|-----------------------------------|-----------|
|
||||||
|
#define PA0 PIN_A0 // | 0 | A0 (ADC1) | | UART4_TX | | | |
|
||||||
|
#define PA1 PIN_A1 // | 1 | A1 (ADC1) | | UART4_RX | | | |
|
||||||
|
#define PA2 PIN_A2 // | 2 | A2 (ADC1) | | USART2_TX | | | |
|
||||||
|
#define PA3 PIN_A3 // | 3 | A3 (ADC1) | | USART2_RX | | | |
|
||||||
|
#define PA4 PIN_A4 // | 4 | A4 (ADC1) | DAC_OUT1 | | | SPI1_SS, (SPI3_SS) | |
|
||||||
|
#define PA5 PIN_A5 // | 5 | A5 (ADC1) | DAC_OUT2 | | | SPI1_SCK | |
|
||||||
|
#define PA6 PIN_A6 // | 6 | A6 (ADC1) | | | | SPI1_MISO | |
|
||||||
|
#define PA7 PIN_A7 // | 7 | A7 (ADC1) | | | | SPI1_MOSI | |
|
||||||
|
#define PA8 8 // | 8 | | | | TWI3_SCL | | |
|
||||||
|
#define PA9 9 // | 9 | | | USART1_TX | | | |
|
||||||
|
#define PA10 10 // | 10 | | | USART1_RX | | | |
|
||||||
|
#define PA11 11 // | 11 | | | | | | |
|
||||||
|
#define PA12 12 // | 12 | | | | | | |
|
||||||
|
#define PA13 13 // | 13 | | | | | | SWD_SWDIO |
|
||||||
|
#define PA14 14 // | 14 | | | | | | SWD_SWCLK |
|
||||||
|
#define PA15 15 // | 15 | | | | | SPI3_SS, (SPI1_SS) | |
|
||||||
|
// |---------|------------|------------|-----------------------|----------------------|-----------------------------------|-----------|
|
||||||
|
#define PB0 PIN_A8 // | 16 | A8 (ADC1) | | | | | |
|
||||||
|
#define PB1 PIN_A9 // | 17 | A9 (ADC1) | | | | | |
|
||||||
|
#define PB2 18 // | 18 | | | | | | BOOT1 |
|
||||||
|
#define PB3 19 // | 19 | | | | | SPI3_SCK, (SPI1_SCK) | |
|
||||||
|
#define PB4 20 // | 20 | | | | | SPI3_MISO, (SPI1_MISO) | |
|
||||||
|
#define PB5 21 // | 21 | | | | | SPI3_MOSI, (SPI1_MOSI) | |
|
||||||
|
#define PB6 22 // | 22 | | | USART1_TX | TWI1_SCL | | |
|
||||||
|
#define PB7 23 // | 23 | | | USART1_RX | TWI1_SDA | | |
|
||||||
|
#define PB8 24 // | 24 | | | | TWI1_SCL | | |
|
||||||
|
#define PB9 25 // | 25 | | | | TWI1_SDA | SPI2_SS | |
|
||||||
|
#define PB10 26 // | 26 | | | USART3_TX, (UART4_TX) | TWI2_SCL | SPI2_SCK | |
|
||||||
|
#define PB11 27 // | 27 | | | USART3_RX | TWI2_SDA | | |
|
||||||
|
#define PB12 28 // | 28 | | | | | SPI2_SS | |
|
||||||
|
#define PB13 29 // | 29 | | | | | SPI2_SCK | |
|
||||||
|
#define PB14 30 // | 30 | | | | | SPI2_MISO | |
|
||||||
|
#define PB15 31 // | 31 | | | | | SPI2_MOSI | |
|
||||||
|
// |---------|------------|------------|-----------------------|----------------------|-----------------------------------|-----------|
|
||||||
|
#define PC0 PIN_A10 // | 32 | A10 (ADC1) | | | | | |
|
||||||
|
#define PC1 PIN_A11 // | 33 | A11 (ADC1) | | | | | |
|
||||||
|
#define PC2 PIN_A12 // | 34 | A12 (ADC1) | | | | SPI2_MISO | |
|
||||||
|
#define PC3 PIN_A13 // | 35 | A13 (ADC1) | | | | SPI2_MOSI | |
|
||||||
|
#define PC4 PIN_A14 // | 36 | A14 (ADC1) | | | | | |
|
||||||
|
#define PC5 PIN_A15 // | 37 | A15 (ADC1) | | USART3_RX | | | |
|
||||||
|
#define PC6 38 // | 38 | | | USART6_TX | | | |
|
||||||
|
#define PC7 39 // | 39 | | | USART6_RX | | | |
|
||||||
|
#define PC8 40 // | 40 | | | | | | |
|
||||||
|
#define PC9 41 // | 41 | | | USART3_TX | TWI3_SDA | | |
|
||||||
|
#define PC10 42 // | 42 | | | | | SPI3_SCK | |
|
||||||
|
#define PC11 43 // | 43 | | | USART3_RX, (UART4_RX) | | SPI3_MISO | |
|
||||||
|
#define PC12 44 // | 44 | | | UART5_TX | | SPI3_MOSI | |
|
||||||
|
#define PC13 45 // | 45 | | | | | | |
|
||||||
|
#define PC14 46 // | 46 | | | | | | OSC32_IN |
|
||||||
|
#define PC15 47 // | 47 | | | | | | OSC32_OUT |
|
||||||
|
// |---------|------------|------------|-----------------------|----------------------|-----------------------------------|-----------|
|
||||||
|
#define PD0 48 // | 48 | | | | | | |
|
||||||
|
#define PD1 49 // | 49 | | | | | | |
|
||||||
|
#define PD2 50 // | 50 | | | UART5_RX | | | |
|
||||||
|
#define PD3 51 // | 51 | | | | | | |
|
||||||
|
#define PD4 52 // | 52 | | | | | | |
|
||||||
|
#define PD5 53 // | 53 | | | USART2_TX | | | |
|
||||||
|
#define PD6 54 // | 54 | | | USART2_RX | | | |
|
||||||
|
#define PD7 55 // | 55 | | | | | | |
|
||||||
|
#define PD8 56 // | 56 | | | USART3_TX | | | |
|
||||||
|
#define PD9 57 // | 57 | | | USART3_RX | | | |
|
||||||
|
#define PD10 58 // | 58 | | | | | | |
|
||||||
|
#define PD11 59 // | 59 | | | | | | |
|
||||||
|
#define PD12 60 // | 60 | | | | | | |
|
||||||
|
#define PD13 61 // | 61 | | | | | | |
|
||||||
|
#define PD14 62 // | 62 | | | | | | |
|
||||||
|
#define PD15 63 // | 63 | | | | | | |
|
||||||
|
// |---------|------------|------------|-----------------------|----------------------|-----------------------------------|-----------|
|
||||||
|
#define PE0 64 // | 64 | | | | | | |
|
||||||
|
#define PE1 65 // | 65 | | | | | | |
|
||||||
|
#define PE2 66 // | 66 | | | | | | |
|
||||||
|
#define PE3 67 // | 67 | | | | | | |
|
||||||
|
#define PE4 68 // | 68 | | | | | | |
|
||||||
|
#define PE5 69 // | 69 | | | | | | |
|
||||||
|
#define PE6 70 // | 70 | | | | | | |
|
||||||
|
#define PE7 71 // | 71 | | | | | | |
|
||||||
|
#define PE8 72 // | 72 | | | | | | |
|
||||||
|
#define PE9 73 // | 73 | | | | | | |
|
||||||
|
#define PE10 74 // | 74 | | | | | | |
|
||||||
|
#define PE11 75 // | 75 | | | | | | |
|
||||||
|
#define PE12 76 // | 76 | | | | | | |
|
||||||
|
#define PE13 77 // | 77 | | | | | | |
|
||||||
|
#define PE14 78 // | 78 | | | | | | |
|
||||||
|
#define PE15 79 // | 79 | | | | | | |
|
||||||
|
// |---------|------------|------------|-----------------------|----------------------|-----------------------------------|-----------|
|
||||||
|
#define PH0 80 // | 80 | | | | | | OSC_IN |
|
||||||
|
#define PH1 81 // | 81 | | | | | | OSC_OUT |
|
||||||
|
// |---------|------------|------------|-----------------------|----------------------|-----------------------------------|-----------|
|
||||||
|
|
||||||
|
/// This must be a literal
|
||||||
|
#define NUM_DIGITAL_PINS 82
|
||||||
|
#define NUM_ANALOG_INPUTS 16
|
||||||
|
|
||||||
|
// On-board LED pin number
|
||||||
|
#ifndef LED_BUILTIN
|
||||||
|
#define LED_BUILTIN PA5
|
||||||
|
#endif
|
||||||
|
#define LED_GREEN LED_BUILTIN
|
||||||
|
|
||||||
|
// On-board user button
|
||||||
|
#ifndef USER_BTN
|
||||||
|
#define USER_BTN PC13
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// SPI definitions
|
||||||
|
#define PIN_SPI_SS PA4
|
||||||
|
#define PIN_SPI_SS1 PA4
|
||||||
|
#define PIN_SPI_SS2 PB12
|
||||||
|
#define PIN_SPI_SS3 PA15
|
||||||
|
#define PIN_SPI_MOSI PA7
|
||||||
|
#define PIN_SPI_MISO PA6
|
||||||
|
#define PIN_SPI_SCK PA5
|
||||||
|
|
||||||
|
// I2C definitions
|
||||||
|
#define PIN_WIRE_SDA PB9
|
||||||
|
#define PIN_WIRE_SCL PB8
|
||||||
|
|
||||||
|
// Timer Definitions
|
||||||
|
// Use TIM6/TIM7 when possible as servo and tone don't need GPIO output pin
|
||||||
|
#ifndef TIMER_TONE
|
||||||
|
#define TIMER_TONE TIM6
|
||||||
|
#endif
|
||||||
|
#ifndef TIMER_SERVO
|
||||||
|
#define TIMER_SERVO TIM7
|
||||||
|
#endif
|
||||||
|
#ifndef TIMER_SERIAL
|
||||||
|
#define TIMER_SERIAL TIM5
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// UART Definitions
|
||||||
|
#define SERIAL_UART_INSTANCE 2
|
||||||
|
|
||||||
|
// Default pin used for 'Serial' instance
|
||||||
|
// Mandatory for Firmata
|
||||||
|
#define PIN_SERIAL_RX PA3
|
||||||
|
#define PIN_SERIAL_TX PA2
|
||||||
|
|
||||||
|
/* Extra HAL modules */
|
||||||
|
#define HAL_DAC_MODULE_ENABLED
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
} // extern "C"
|
||||||
|
#endif
|
||||||
|
/*----------------------------------------------------------------------------
|
||||||
|
* Arduino objects - C++ only
|
||||||
|
*----------------------------------------------------------------------------*/
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
// These serial port names are intended to allow libraries and architecture-neutral
|
||||||
|
// sketches to automatically default to the correct port name for a particular type
|
||||||
|
// of use. For example, a GPS module would normally connect to SERIAL_PORT_HARDWARE_OPEN,
|
||||||
|
// the first hardware serial port whose RX/TX pins are not dedicated to another use.
|
||||||
|
//
|
||||||
|
// SERIAL_PORT_MONITOR Port which normally prints to the Arduino Serial Monitor
|
||||||
|
//
|
||||||
|
// SERIAL_PORT_USBVIRTUAL Port which is USB virtual serial
|
||||||
|
//
|
||||||
|
// SERIAL_PORT_LINUXBRIDGE Port which connects to a Linux system via Bridge library
|
||||||
|
//
|
||||||
|
// SERIAL_PORT_HARDWARE Hardware serial port, physical RX & TX pins.
|
||||||
|
//
|
||||||
|
// SERIAL_PORT_HARDWARE_OPEN Hardware serial ports which are open for use. Their RX & TX
|
||||||
|
// pins are NOT connected to anything by default.
|
||||||
|
#define SERIAL_PORT_MONITOR Serial
|
||||||
|
#define SERIAL_PORT_HARDWARE Serial1
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif /* _VARIANT_ARDUINO_STM32_ */
|
|
@ -1377,6 +1377,28 @@ extra_scripts = ${common.extra_scripts}
|
||||||
buildroot/share/PlatformIO/scripts/stm32_bootloader.py
|
buildroot/share/PlatformIO/scripts/stm32_bootloader.py
|
||||||
buildroot/share/PlatformIO/scripts/mks_encrypt.py
|
buildroot/share/PlatformIO/scripts/mks_encrypt.py
|
||||||
|
|
||||||
|
#
|
||||||
|
# MKS Robin Nano V3
|
||||||
|
#
|
||||||
|
[env:mks_robin_nano_v3]
|
||||||
|
platform = ${common_stm32.platform}
|
||||||
|
extends = common_stm32
|
||||||
|
build_flags = ${common_stm32.build_flags} -DHAL_PCD_MODULE_ENABLED -DUSBCON -DUSBD_USE_CDC
|
||||||
|
board = genericSTM32F407VGT6
|
||||||
|
board_build.core = stm32
|
||||||
|
board_build.variant = MARLIN_F4x7Vx
|
||||||
|
board_build.ldscript = ldscript.ld
|
||||||
|
board_build.firmware = Robin_nano_v3.bin
|
||||||
|
board_build.offset = 0xC000
|
||||||
|
board_upload.offset_address = 0x0800C000
|
||||||
|
build_unflags = ${common_stm32.build_unflags}
|
||||||
|
debug_tool = jlink
|
||||||
|
upload_protocol = jlink
|
||||||
|
extra_scripts = ${common.extra_scripts}
|
||||||
|
pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py
|
||||||
|
buildroot/share/PlatformIO/scripts/stm32_bootloader.py
|
||||||
|
buildroot/share/PlatformIO/scripts/mks_encrypt.py
|
||||||
|
|
||||||
#################################
|
#################################
|
||||||
# #
|
# #
|
||||||
# Other Architectures #
|
# Other Architectures #
|
||||||
|
|
Loading…
Reference in a new issue