Shorter paths to HAL, ExtUI (#17156)

This commit is contained in:
Scott Lahteine
2020-03-13 16:29:29 -05:00
committed by GitHub
parent ad980a72f7
commit 6bead0c1b0
600 changed files with 228 additions and 227 deletions

View File

@ -0,0 +1,138 @@
/**
* Marlin 3D Printer Firmware
*
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
* Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
* Copyright (c) 2017 Victor Perez
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
#include "HAL.h"
#include "../../inc/MarlinConfig.h"
#include "../shared/Delay.h"
#if HAS_TMC_SW_SERIAL
#include "SoftwareSerial.h"
#endif
#if ENABLED(SRAM_EEPROM_EMULATION)
#if STM32F7xx
#include <stm32f7xx_ll_pwr.h>
#elif STM32F4xx
#include <stm32f4xx_ll_pwr.h>
#else
#error "SRAM_EEPROM_EMULATION is currently only supported for STM32F4xx and STM32F7xx"
#endif
#endif
// ------------------------
// Public Variables
// ------------------------
uint16_t HAL_adc_result;
// ------------------------
// Public functions
// ------------------------
// Needed for DELAY_NS() / DELAY_US() on CORTEX-M7
#if (defined(__arm__) || defined(__thumb__)) && __CORTEX_M == 7
// HAL pre-initialization task
// Force the preinit function to run between the premain() and main() function
// of the STM32 arduino core
__attribute__((constructor (102)))
void HAL_preinit() {
enableCycleCounter();
}
#endif
// HAL initialization task
void HAL_init() {
FastIO_init();
#if ENABLED(SDSUPPORT)
OUT_WRITE(SDSS, HIGH); // Try to set SDSS inactive before any other SPI users start up
#endif
#if PIN_EXISTS(LED)
OUT_WRITE(LED_PIN, LOW);
#endif
#if ENABLED(SRAM_EEPROM_EMULATION)
// Enable access to backup SRAM
__HAL_RCC_PWR_CLK_ENABLE();
HAL_PWR_EnableBkUpAccess();
__HAL_RCC_BKPSRAM_CLK_ENABLE();
// Enable backup regulator
LL_PWR_EnableBkUpRegulator();
// Wait until backup regulator is initialized
while (!LL_PWR_IsActiveFlag_BRR());
#endif // EEPROM_EMULATED_SRAM
#if HAS_TMC_SW_SERIAL
SoftwareSerial::setInterruptPriority(SWSERIAL_TIMER_IRQ_PRIO, 0);
#endif
}
void HAL_clear_reset_source() { __HAL_RCC_CLEAR_RESET_FLAGS(); }
uint8_t HAL_get_reset_source() {
return
#ifdef RCC_FLAG_IWDGRST // Some sources may not exist...
RESET != __HAL_RCC_GET_FLAG(RCC_FLAG_IWDGRST) ? RST_WATCHDOG :
#endif
#ifdef RCC_FLAG_IWDG1RST
RESET != __HAL_RCC_GET_FLAG(RCC_FLAG_IWDG1RST) ? RST_WATCHDOG :
#endif
#ifdef RCC_FLAG_IWDG2RST
RESET != __HAL_RCC_GET_FLAG(RCC_FLAG_IWDG2RST) ? RST_WATCHDOG :
#endif
#ifdef RCC_FLAG_SFTRST
RESET != __HAL_RCC_GET_FLAG(RCC_FLAG_SFTRST) ? RST_SOFTWARE :
#endif
#ifdef RCC_FLAG_PINRST
RESET != __HAL_RCC_GET_FLAG(RCC_FLAG_PINRST) ? RST_EXTERNAL :
#endif
#ifdef RCC_FLAG_PORRST
RESET != __HAL_RCC_GET_FLAG(RCC_FLAG_PORRST) ? RST_POWER_ON :
#endif
0
;
}
void _delay_ms(const int delay_ms) { delay(delay_ms); }
extern "C" {
extern unsigned int _ebss; // end of bss section
}
// ------------------------
// ADC
// ------------------------
// TODO: Make sure this doesn't cause any delay
void HAL_adc_start_conversion(const uint8_t adc_pin) { HAL_adc_result = analogRead(adc_pin); }
uint16_t HAL_adc_get_result() { return HAL_adc_result; }
void flashFirmware(int16_t) { NVIC_SystemReset(); }
#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC

226
Marlin/src/HAL/STM32/HAL.h Normal file
View File

@ -0,0 +1,226 @@
/**
* Marlin 3D Printer Firmware
*
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
* Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
* Copyright (c) 2017 Victor Perez
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
#define CPU_32_BIT
#include "../../core/macros.h"
#include "../shared/Marduino.h"
#include "../shared/math_32bit.h"
#include "../shared/HAL_SPI.h"
#include "fastio.h"
#include "watchdog.h"
#include "../../inc/MarlinConfigPre.h"
#include <stdint.h>
#ifdef USBCON
#include <USBSerial.h>
#endif
// ------------------------
// Defines
// ------------------------
#if SERIAL_PORT == 0
#error "SERIAL_PORT cannot be 0. (Port 0 does not exist.) Please update your configuration."
#elif SERIAL_PORT == -1
#define MYSERIAL0 SerialUSB
#elif SERIAL_PORT == 1
#define MYSERIAL0 Serial1
#elif SERIAL_PORT == 2
#define MYSERIAL0 Serial2
#elif SERIAL_PORT == 3
#define MYSERIAL0 Serial3
#elif SERIAL_PORT == 4
#define MYSERIAL0 Serial4
#elif SERIAL_PORT == 5
#define MYSERIAL0 Serial5
#elif SERIAL_PORT == 6
#define MYSERIAL0 Serial6
#else
#error "SERIAL_PORT must be from -1 to 6. Please update your configuration."
#endif
#ifdef SERIAL_PORT_2
#define NUM_SERIAL 2
#if SERIAL_PORT_2 == 0
#error "SERIAL_PORT_2 cannot be 0. (Port 0 does not exist.) Please update your configuration."
#elif SERIAL_PORT_2 == SERIAL_PORT
#error "SERIAL_PORT_2 must be different than SERIAL_PORT. Please update your configuration."
#elif SERIAL_PORT_2 == -1
#define MYSERIAL1 SerialUSB
#elif SERIAL_PORT_2 == 1
#define MYSERIAL1 Serial1
#elif SERIAL_PORT_2 == 2
#define MYSERIAL1 Serial2
#elif SERIAL_PORT_2 == 3
#define MYSERIAL1 Serial3
#elif SERIAL_PORT_2 == 4
#define MYSERIAL1 Serial4
#elif SERIAL_PORT_2 == 5
#define MYSERIAL1 Serial5
#elif SERIAL_PORT_2 == 6
#define MYSERIAL1 Serial6
#else
#error "SERIAL_PORT_2 must be from -1 to 6. Please update your configuration."
#endif
#else
#define NUM_SERIAL 1
#endif
#if HAS_DGUS_LCD
#if DGUS_SERIAL_PORT == 0
#error "DGUS_SERIAL_PORT cannot be 0. (Port 0 does not exist.) Please update your configuration."
#elif DGUS_SERIAL_PORT == SERIAL_PORT
#error "DGUS_SERIAL_PORT must be different than SERIAL_PORT. Please update your configuration."
#elif defined(SERIAL_PORT_2) && DGUS_SERIAL_PORT == SERIAL_PORT_2
#error "DGUS_SERIAL_PORT must be different than SERIAL_PORT_2. Please update your configuration."
#elif DGUS_SERIAL_PORT == -1
#define DGUS_SERIAL SerialUSB
#elif DGUS_SERIAL_PORT == 1
#define DGUS_SERIAL Serial1
#elif DGUS_SERIAL_PORT == 2
#define DGUS_SERIAL Serial2
#elif DGUS_SERIAL_PORT == 3
#define DGUS_SERIAL Serial3
#elif DGUS_SERIAL_PORT == 4
#define DGUS_SERIAL Serial4
#elif DGUS_SERIAL_PORT == 5
#define DGUS_SERIAL Serial5
#elif DGUS_SERIAL_PORT == 6
#define DGUS_SERIAL Serial6
#else
#error "DGUS_SERIAL_PORT must be from -1 to 6. Please update your configuration."
#endif
#define DGUS_SERIAL_GET_TX_BUFFER_FREE DGUS_SERIAL.availableForWrite
#endif
#include "timers.h"
/**
* TODO: review this to return 1 for pins that are not analog input
*/
#ifndef analogInputToDigitalPin
#define analogInputToDigitalPin(p) (p)
#endif
#define CRITICAL_SECTION_START() uint32_t primask = __get_PRIMASK(); __disable_irq()
#define CRITICAL_SECTION_END() if (!primask) __enable_irq()
#define ISRS_ENABLED() (!__get_PRIMASK())
#define ENABLE_ISRS() __enable_irq()
#define DISABLE_ISRS() __disable_irq()
#define cli() __disable_irq()
#define sei() __enable_irq()
// On AVR this is in math.h?
#define square(x) ((x)*(x))
#ifndef strncpy_P
#define strncpy_P(dest, src, num) strncpy((dest), (src), (num))
#endif
// Fix bug in pgm_read_ptr
#undef pgm_read_ptr
#define pgm_read_ptr(addr) (*(addr))
// ------------------------
// Types
// ------------------------
typedef int16_t pin_t;
#define HAL_SERVO_LIB libServo
// ------------------------
// Public Variables
// ------------------------
// result of last ADC conversion
extern uint16_t HAL_adc_result;
// ------------------------
// Public functions
// ------------------------
// Memory related
#define __bss_end __bss_end__
// Enable hooks into setup for HAL
void HAL_init();
// Clear reset reason
void HAL_clear_reset_source();
// Reset reason
uint8_t HAL_get_reset_source();
void _delay_ms(const int delay);
extern "C" char* _sbrk(int incr);
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-function"
static inline int freeMemory() {
volatile char top;
return &top - reinterpret_cast<char*>(_sbrk(0));
}
#pragma GCC diagnostic pop
//
// EEPROM
//
// Wire library should work for i2c EEPROMs
void eeprom_write_byte(uint8_t *pos, unsigned char value);
uint8_t eeprom_read_byte(uint8_t *pos);
void eeprom_read_block(void *__dst, const void *__src, size_t __n);
void eeprom_update_block(const void *__src, void *__dst, size_t __n);
//
// ADC
//
#define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT)
inline void HAL_adc_init() {}
#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
#define HAL_ADC_RESOLUTION 10
#define HAL_READ_ADC() HAL_adc_result
#define HAL_ADC_READY() true
void HAL_adc_start_conversion(const uint8_t adc_pin);
uint16_t HAL_adc_get_result();
#define GET_PIN_MAP_PIN(index) index
#define GET_PIN_MAP_INDEX(pin) pin
#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
#define PLATFORM_M997_SUPPORT
void flashFirmware(int16_t value);

View File

@ -0,0 +1,230 @@
/**
* 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
* Copyright (c) 2017 Victor Perez
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
#include "../../inc/MarlinConfig.h"
#include <SPI.h>
// ------------------------
// Public Variables
// ------------------------
static SPISettings spiConfig;
// ------------------------
// Public functions
// ------------------------
#if ENABLED(SOFTWARE_SPI)
// ------------------------
// Software SPI
// ------------------------
#include "../shared/Delay.h"
void spiBegin(void) {
OUT_WRITE(SS_PIN, HIGH);
OUT_WRITE(SCK_PIN, HIGH);
SET_INPUT(MISO_PIN);
OUT_WRITE(MOSI_PIN, HIGH);
}
static uint16_t delay_STM32_soft_spi;
void spiInit(uint8_t spiRate) {
// Use datarates Marlin uses
switch (spiRate) {
case SPI_FULL_SPEED: delay_STM32_soft_spi = 125; break; // desired: 8,000,000 actual: ~1.1M
case SPI_HALF_SPEED: delay_STM32_soft_spi = 125; break; // desired: 4,000,000 actual: ~1.1M
case SPI_QUARTER_SPEED:delay_STM32_soft_spi = 250; break; // desired: 2,000,000 actual: ~890K
case SPI_EIGHTH_SPEED: delay_STM32_soft_spi = 500; break; // desired: 1,000,000 actual: ~590K
case SPI_SPEED_5: delay_STM32_soft_spi = 1000; break; // desired: 500,000 actual: ~360K
case SPI_SPEED_6: delay_STM32_soft_spi = 2000; break; // desired: 250,000 actual: ~210K
default: delay_STM32_soft_spi = 4000; break; // desired: 125,000 actual: ~123K
}
SPI.begin();
}
// Begin SPI transaction, set clock, bit order, data mode
void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { /* do nothing */ }
uint8_t HAL_SPI_STM32_SpiTransfer_Mode_3(uint8_t b) { // using Mode 3
for (uint8_t bits = 8; bits--;) {
WRITE(SCK_PIN, LOW);
WRITE(MOSI_PIN, b & 0x80);
DELAY_NS(delay_STM32_soft_spi);
WRITE(SCK_PIN, HIGH);
DELAY_NS(delay_STM32_soft_spi);
b <<= 1; // little setup time
b |= (READ(MISO_PIN) != 0);
}
DELAY_NS(125);
return b;
}
// Soft SPI receive byte
uint8_t spiRec() {
DISABLE_ISRS(); // No interrupts during byte receive
const uint8_t data = HAL_SPI_STM32_SpiTransfer_Mode_3(0xFF);
ENABLE_ISRS(); // Enable interrupts
return data;
}
// Soft SPI read data
void spiRead(uint8_t *buf, uint16_t nbyte) {
for (uint16_t i = 0; i < nbyte; i++)
buf[i] = spiRec();
}
// Soft SPI send byte
void spiSend(uint8_t data) {
DISABLE_ISRS(); // No interrupts during byte send
HAL_SPI_STM32_SpiTransfer_Mode_3(data); // Don't care what is received
ENABLE_ISRS(); // Enable interrupts
}
// Soft SPI send block
void spiSendBlock(uint8_t token, const uint8_t *buf) {
spiSend(token);
for (uint16_t i = 0; i < 512; i++)
spiSend(buf[i]);
}
#else
// ------------------------
// Hardware SPI
// ------------------------
/**
* VGPV SPI speed start and PCLK2/2, by default 108/2 = 54Mhz
*/
/**
* @brief Begin SPI port setup
*
* @return Nothing
*
* @details Only configures SS pin since stm32duino creates and initialize the SPI object
*/
void spiBegin() {
#if !PIN_EXISTS(SS)
#error "SS_PIN not defined!"
#endif
OUT_WRITE(SS_PIN, HIGH);
}
// Configure SPI for specified SPI speed
void spiInit(uint8_t spiRate) {
// Use datarates Marlin uses
uint32_t clock;
switch (spiRate) {
case SPI_FULL_SPEED: clock = 20000000; break; // 13.9mhz=20000000 6.75mhz=10000000 3.38mhz=5000000 .833mhz=1000000
case SPI_HALF_SPEED: clock = 5000000; break;
case SPI_QUARTER_SPEED: clock = 2500000; break;
case SPI_EIGHTH_SPEED: clock = 1250000; break;
case SPI_SPEED_5: clock = 625000; break;
case SPI_SPEED_6: clock = 300000; break;
default:
clock = 4000000; // Default from the SPI library
}
spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0);
#if ENABLED(CUSTOM_SPI_PINS)
SPI.setMISO(MISO_PIN);
SPI.setMOSI(MOSI_PIN);
SPI.setSCLK(SCK_PIN);
SPI.setSSEL(SS_PIN);
#endif
SPI.begin();
}
/**
* @brief Receives a single byte from the SPI port.
*
* @return Byte received
*
* @details
*/
uint8_t spiRec() {
SPI.beginTransaction(spiConfig);
uint8_t returnByte = SPI.transfer(0xFF);
SPI.endTransaction();
return returnByte;
}
/**
* @brief Receive a number of bytes from the SPI port to a buffer
*
* @param buf Pointer to starting address of buffer to write to.
* @param nbyte Number of bytes to receive.
* @return Nothing
*
* @details Uses DMA
*/
void spiRead(uint8_t* buf, uint16_t nbyte) {
if (nbyte == 0) return;
memset(buf, 0xFF, nbyte);
SPI.beginTransaction(spiConfig);
SPI.transfer(buf, nbyte);
SPI.endTransaction();
}
/**
* @brief Send a single byte on SPI port
*
* @param b Byte to send
*
* @details
*/
void spiSend(uint8_t b) {
SPI.beginTransaction(spiConfig);
SPI.transfer(b);
SPI.endTransaction();
}
/**
* @brief Write token and then write from 512 byte buffer to SPI (for SD card)
*
* @param buf Pointer with buffer start address
* @return Nothing
*
* @details Use DMA
*/
void spiSendBlock(uint8_t token, const uint8_t* buf) {
uint8_t rxBuf[512];
SPI.beginTransaction(spiConfig);
SPI.transfer(token);
SPI.transfer((uint8_t*)buf, &rxBuf, 512);
SPI.endTransaction();
}
#endif // SOFTWARE_SPI
#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC

View File

@ -0,0 +1,11 @@
# Generic STM32 HAL based on the stm32duino core
This HAL is intended to act as the generic STM32 HAL for all STM32 chips (The whole F, H and L family).
Currently it supports:
* STM32F0xx
* STM32F1xx
* STM32F4xx
* STM32F7xx
Targeting the official [Arduino STM32 Core](https://github.com/stm32duino/Arduino_Core_STM32).

View File

@ -0,0 +1,274 @@
/**
* 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/>.
*
*/
#include "../../inc/MarlinConfig.h"
#if ENABLED(SDIO_SUPPORT) && !defined(STM32GENERIC)
#include <stdint.h>
#include <stdbool.h>
//#include "SdMscDriver.h"
//#include "usbd_msc_bot.h"
//#include "usbd_msc_scsi.h"
//#include "usbd_msc_composite.h"
//#include "usbd_msc_cdc_composite.h"
//#include "usbd_msc_data.h"
#if defined(STM32F103xE) || defined(STM32F103xG)
#include <stm32f1xx_hal_rcc_ex.h>
#include <stm32f1xx_hal_sd.h>
#elif defined(STM32F4xx)
#include <stm32f4xx_hal_rcc.h>
#include <stm32f4xx_hal_dma.h>
#include <stm32f4xx_hal_gpio.h>
#include <stm32f4xx_hal_sd.h>
#elif defined(STM32F7xx)
#include <stm32f7xx_hal_rcc.h>
#include <stm32f7xx_hal_dma.h>
#include <stm32f7xx_hal_gpio.h>
#include <stm32f7xx_hal_sd.h>
#else
#error "ERROR - Only STM32F103xE, STM32F103xG, STM32F4xx or STM32F7xx CPUs supported"
#endif
SD_HandleTypeDef hsd; // create SDIO structure
#define TRANSFER_CLOCK_DIV ((uint8_t)SDIO_INIT_CLK_DIV/40)
#ifndef USBD_OK
#define USBD_OK 0
#endif
void go_to_transfer_speed() {
SD_InitTypeDef Init;
/* Default SDIO peripheral configuration for SD card initialization */
Init.ClockEdge = hsd.Init.ClockEdge;
Init.ClockBypass = hsd.Init.ClockBypass;
Init.ClockPowerSave = hsd.Init.ClockPowerSave;
Init.BusWide = hsd.Init.BusWide;
Init.HardwareFlowControl = hsd.Init.HardwareFlowControl;
Init.ClockDiv = TRANSFER_CLOCK_DIV;
/* Initialize SDIO peripheral interface with default configuration */
SDIO_Init(hsd.Instance, Init);
}
void SD_LowLevel_Init(void) {
uint32_t tempreg;
GPIO_InitTypeDef GPIO_InitStruct;
__HAL_RCC_GPIOC_CLK_ENABLE(); //enable GPIO clocks
__HAL_RCC_GPIOD_CLK_ENABLE(); //enable GPIO clocks
GPIO_InitStruct.Pin = GPIO_PIN_8 | GPIO_PIN_12; // D0 & SCK
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = 1; //GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF12_SDIO;
HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
#if defined(SDIO_D1_PIN) && defined(SDIO_D2_PIN) && defined(SDIO_D3_PIN) // define D1-D3 only if have a four bit wide SDIO bus
GPIO_InitStruct.Pin = GPIO_PIN_9 | GPIO_PIN_10 | GPIO_PIN_11; // D1-D3
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = 1; //GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF12_SDIO;
HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
#endif
// Configure PD.02 CMD line
GPIO_InitStruct.Pin = GPIO_PIN_2;
HAL_GPIO_Init(GPIOD, &GPIO_InitStruct);
RCC->APB2RSTR &= ~RCC_APB2RSTR_SDIORST_Msk; // take SDIO out of reset
RCC->APB2ENR |= RCC_APB2RSTR_SDIORST_Msk; // enable SDIO clock
// Enable the DMA2 Clock
//Initialize the SDIO (with initial <400Khz Clock)
tempreg = 0; //Reset value
tempreg |= SDIO_CLKCR_CLKEN; //Clock is enabled
tempreg |= (uint32_t)0x76; //Clock Divider. Clock = 48000/(118+2) = 400Khz
//Keep the rest at 0 => HW_Flow Disabled, Rising Clock Edge, Disable CLK ByPass, Bus Width = 0, Power save Disable
SDIO->CLKCR = tempreg;
//Power up the SDIO
SDIO->POWER = 0x03;
}
void HAL_SD_MspInit(SD_HandleTypeDef *hsd) { // application specific init
UNUSED(hsd); /* Prevent unused argument(s) compilation warning */
__HAL_RCC_SDIO_CLK_ENABLE(); // turn on SDIO clock
}
constexpr uint8_t SD_RETRY_COUNT = (1
#if ENABLED(SD_CHECK_AND_RETRY)
+ 2
#endif
);
bool SDIO_Init() {
//init SDIO and get SD card info
uint8_t retryCnt = SD_RETRY_COUNT;
bool status;
hsd.Instance = SDIO;
hsd.State = (HAL_SD_StateTypeDef) 0; // HAL_SD_STATE_RESET
SD_LowLevel_Init();
uint8_t retry_Cnt = retryCnt;
for (;;) {
status = (bool) HAL_SD_Init(&hsd);
if (!status) break;
if (!--retry_Cnt) return false; // return failing status if retries are exhausted
}
go_to_transfer_speed();
#if defined(SDIO_D1_PIN) && defined(SDIO_D2_PIN) && defined(SDIO_D3_PIN) // go to 4 bit wide mode if pins are defined
retry_Cnt = retryCnt;
for (;;) {
if (!HAL_SD_ConfigWideBusOperation(&hsd, SDIO_BUS_WIDE_4B)) break; // some cards are only 1 bit wide so a pass here is not required
if (!--retry_Cnt) break;
}
if (!retry_Cnt) { // wide bus failed, go back to one bit wide mode
hsd.State = (HAL_SD_StateTypeDef) 0; // HAL_SD_STATE_RESET
SD_LowLevel_Init();
retry_Cnt = retryCnt;
for (;;) {
status = (bool) HAL_SD_Init(&hsd);
if (!status) break;
if (!--retry_Cnt) return false; // return failing status if retries are exhausted
}
}
#endif
return true;
}
void init_SDIO_pins(void) {
GPIO_InitTypeDef GPIO_InitStruct = {0};
/**SDIO GPIO Configuration
PC8 ------> SDIO_D0
PC12 ------> SDIO_CK
PD2 ------> SDIO_CMD
*/
GPIO_InitStruct.Pin = GPIO_PIN_8;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF12_SDIO;
HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
GPIO_InitStruct.Pin = GPIO_PIN_12;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF12_SDIO;
HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
GPIO_InitStruct.Pin = GPIO_PIN_2;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF12_SDIO;
HAL_GPIO_Init(GPIOD, &GPIO_InitStruct);
}
//bool SDIO_init() { return (bool) (SD_SDIO_Init() ? 1 : 0);}
//bool SDIO_Init_C() { return (bool) (SD_SDIO_Init() ? 1 : 0);}
bool SDIO_ReadBlock(uint32_t block, uint8_t *dst) {
bool status;
hsd.Instance = SDIO;
uint8_t retryCnt = SD_RETRY_COUNT;
for (;;) {
bool status = (bool) HAL_SD_ReadBlocks(&hsd, (uint8_t*)dst, block, 1, 1000); // read one 512 byte block with 500mS timeout
status |= (bool) HAL_SD_GetCardState(&hsd); // make sure all is OK
if (!status) return false; // return passing status
if (!--retryCnt) return true; // return failing status if retries are exhausted
}
/*
return (bool) ((status_read | status_card) ? 1 : 0);
if (SDIO_GetCardState() != SDIO_CARD_TRANSFER) return false;
if (blockAddress >= SdCard.LogBlockNbr) return false;
if ((0x03 & (uint32_t)data)) return false; // misaligned data
if (SdCard.CardType != CARD_SDHC_SDXC) { blockAddress *= 512U; }
if (!SDIO_CmdReadSingleBlock(blockAddress)) {
SDIO_CLEAR_FLAG(SDIO_ICR_CMD_FLAGS);
dma_disable(SDIO_DMA_DEV, SDIO_DMA_CHANNEL);
return false;
}
while (!SDIO_GET_FLAG(SDIO_STA_DATAEND | SDIO_STA_TRX_ERROR_FLAGS)) {}
dma_disable(SDIO_DMA_DEV, SDIO_DMA_CHANNEL);
if (SDIO->STA & SDIO_STA_RXDAVL) {
while (SDIO->STA & SDIO_STA_RXDAVL) (void)SDIO->FIFO;
SDIO_CLEAR_FLAG(SDIO_ICR_CMD_FLAGS | SDIO_ICR_DATA_FLAGS);
return false;
}
if (SDIO_GET_FLAG(SDIO_STA_TRX_ERROR_FLAGS)) {
SDIO_CLEAR_FLAG(SDIO_ICR_CMD_FLAGS | SDIO_ICR_DATA_FLAGS);
return false;
}
SDIO_CLEAR_FLAG(SDIO_ICR_CMD_FLAGS | SDIO_ICR_DATA_FLAGS);
*/
return true;
}
bool SDIO_WriteBlock(uint32_t block, const uint8_t *src) {
bool status;
hsd.Instance = SDIO;
uint8_t retryCnt = SD_RETRY_COUNT;
for (;;) {
status = (bool) HAL_SD_WriteBlocks(&hsd, (uint8_t*)src, block, 1, 500); // write one 512 byte block with 500mS timeout
status |= (bool) HAL_SD_GetCardState(&hsd); // make sure all is OK
if (!status) return (bool) status; // return passing status
if (!--retryCnt) return (bool) status; // return failing status if retries are exhausted
}
}
#endif // SDIO_SUPPORT

View File

@ -0,0 +1,62 @@
/**
* 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
* Copyright (c) 2017 Victor Perez
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
#include "../../inc/MarlinConfig.h"
#if HAS_SERVOS
#include "Servo.h"
static uint_fast8_t servoCount = 0;
constexpr millis_t servoDelay[] = SERVO_DELAY;
static_assert(COUNT(servoDelay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long.");
libServo::libServo()
: delay(servoDelay[servoCount++])
{}
int8_t libServo::attach(const int pin) {
if (servoCount >= MAX_SERVOS) return -1;
if (pin > 0) servo_pin = pin;
return super::attach(servo_pin);
}
int8_t libServo::attach(const int pin, const int min, const int max) {
if (servoCount >= MAX_SERVOS) return -1;
if (pin > 0) servo_pin = pin;
return super::attach(servo_pin, min, max);
}
void libServo::move(const int value) {
if (attach(0) >= 0) {
write(value);
safe_delay(delay);
#if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE)
detach();
#endif
}
}
#endif // HAS_SERVOS
#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC

View File

@ -0,0 +1,41 @@
/**
* 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
* Copyright (c) 2017 Victor Perez
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
#include <Servo.h>
#include "../../core/millis_t.h"
// Inherit and expand on the official library
class libServo : public Servo {
public:
libServo();
int8_t attach(const int pin);
int8_t attach(const int pin, const int min, const int max);
void move(const int value);
private:
typedef Servo super;
int servo_pin = 0;
millis_t delay = 0;
};

View File

@ -0,0 +1,395 @@
/*
* SoftwareSerial.cpp (formerly NewSoftSerial.cpp)
*
* Multi-instance software serial library for Arduino/Wiring
* -- Interrupt-driven receive and other improvements by ladyada
* (http://ladyada.net)
* -- Tuning, circular buffer, derivation from class Print/Stream,
* multi-instance support, porting to 8MHz processors,
* various optimizations, PROGMEM delay tables, inverse logic and
* direct port writing by Mikal Hart (http://www.arduiniana.org)
* -- Pin change interrupt macros by Paul Stoffregen (http://www.pjrc.com)
* -- 20MHz processor support by Garrett Mace (http://www.macetech.com)
* -- ATmega1280/2560 support by Brett Hagman (http://www.roguerobotics.com/)
* -- STM32 support by Armin van der Togt
*
* This library is free software; you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public
* License as published by the Free Software Foundation; either
* version 2.1 of the License, or (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public
* License along with this library; if not, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* The latest version of this library can always be found at
* http://arduiniana.org.
*/
//
// Includes
//
#if defined(PLATFORMIO) && defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
#include "SoftwareSerial.h"
#include "timers.h"
#define OVERSAMPLE 3 // in RX, Timer will generate interruption OVERSAMPLE time during a bit. Thus OVERSAMPLE ticks in a bit. (interrupt not synchonized with edge).
// defined in bit-periods
#define HALFDUPLEX_SWITCH_DELAY 5
// It's best to define TIMER_SERIAL in variant.h. If not defined, we choose one here
// The order is based on (lack of) features and compare channels, we choose the simplest available
// because we only need an update interrupt
#if !defined(TIMER_SERIAL)
#if defined (TIM18_BASE)
#define TIMER_SERIAL TIM18
#elif defined (TIM7_BASE)
#define TIMER_SERIAL TIM7
#elif defined (TIM6_BASE)
#define TIMER_SERIAL TIM6
#elif defined (TIM22_BASE)
#define TIMER_SERIAL TIM22
#elif defined (TIM21_BASE)
#define TIMER_SERIAL TIM21
#elif defined (TIM17_BASE)
#define TIMER_SERIAL TIM17
#elif defined (TIM16_BASE)
#define TIMER_SERIAL TIM16
#elif defined (TIM15_BASE)
#define TIMER_SERIAL TIM15
#elif defined (TIM14_BASE)
#define TIMER_SERIAL TIM14
#elif defined (TIM13_BASE)
#define TIMER_SERIAL TIM13
#elif defined (TIM11_BASE)
#define TIMER_SERIAL TIM11
#elif defined (TIM10_BASE)
#define TIMER_SERIAL TIM10
#elif defined (TIM12_BASE)
#define TIMER_SERIAL TIM12
#elif defined (TIM19_BASE)
#define TIMER_SERIAL TIM19
#elif defined (TIM9_BASE)
#define TIMER_SERIAL TIM9
#elif defined (TIM5_BASE)
#define TIMER_SERIAL TIM5
#elif defined (TIM4_BASE)
#define TIMER_SERIAL TIM4
#elif defined (TIM3_BASE)
#define TIMER_SERIAL TIM3
#elif defined (TIM2_BASE)
#define TIMER_SERIAL TIM2
#elif defined (TIM20_BASE)
#define TIMER_SERIAL TIM20
#elif defined (TIM8_BASE)
#define TIMER_SERIAL TIM8
#elif defined (TIM1_BASE)
#define TIMER_SERIAL TIM1
#else
#error No suitable timer found for SoftwareSerial, define TIMER_SERIAL in variant.h
#endif
#endif
//
// Statics
//
HardwareTimer SoftwareSerial::timer(TIMER_SERIAL);
const IRQn_Type SoftwareSerial::timer_interrupt_number = static_cast<IRQn_Type>(getTimerUpIrq(TIMER_SERIAL));
uint32_t SoftwareSerial::timer_interrupt_priority = NVIC_EncodePriority(NVIC_GetPriorityGrouping(), TIM_IRQ_PRIO, TIM_IRQ_SUBPRIO);
SoftwareSerial *SoftwareSerial::active_listener = nullptr;
SoftwareSerial *volatile SoftwareSerial::active_out = nullptr;
SoftwareSerial *volatile SoftwareSerial::active_in = nullptr;
int32_t SoftwareSerial::tx_tick_cnt = 0; // OVERSAMPLE ticks needed for a bit
int32_t volatile SoftwareSerial::rx_tick_cnt = 0; // OVERSAMPLE ticks needed for a bit
uint32_t SoftwareSerial::tx_buffer = 0;
int32_t SoftwareSerial::tx_bit_cnt = 0;
uint32_t SoftwareSerial::rx_buffer = 0;
int32_t SoftwareSerial::rx_bit_cnt = -1; // rx_bit_cnt = -1 : waiting for start bit
uint32_t SoftwareSerial::cur_speed = 0;
void SoftwareSerial::setInterruptPriority(uint32_t preemptPriority, uint32_t subPriority) {
timer_interrupt_priority = NVIC_EncodePriority(NVIC_GetPriorityGrouping(), preemptPriority, subPriority);
}
//
// Private methods
//
void SoftwareSerial::setSpeed(uint32_t speed) {
if (speed != cur_speed) {
timer.pause();
if (speed != 0) {
// Disable the timer
uint32_t clock_rate, cmp_value;
// Get timer clock
clock_rate = timer.getTimerClkFreq();
int pre = 1;
// Calculate prescale an compare value
do {
cmp_value = clock_rate / (speed * OVERSAMPLE);
if (cmp_value >= UINT16_MAX) {
clock_rate /= 2;
pre *= 2;
}
} while (cmp_value >= UINT16_MAX);
timer.setPrescaleFactor(pre);
timer.setOverflow(cmp_value);
timer.setCount(0);
timer.attachInterrupt(&handleInterrupt);
timer.resume();
NVIC_SetPriority(timer_interrupt_number, timer_interrupt_priority);
}
else
timer.detachInterrupt();
cur_speed = speed;
}
}
// This function sets the current object as the "listening"
// one and returns true if it replaces another
bool SoftwareSerial::listen() {
if (active_listener != this) {
// wait for any transmit to complete as we may change speed
while (active_out);
active_listener->stopListening();
rx_tick_cnt = 1; // 1 : next interrupt will decrease rx_tick_cnt to 0 which means RX pin level will be considered.
rx_bit_cnt = -1; // rx_bit_cnt = -1 : waiting for start bit
setSpeed(_speed);
active_listener = this;
if (!_half_duplex) active_in = this;
return true;
}
return false;
}
// Stop listening. Returns true if we were actually listening.
bool SoftwareSerial::stopListening() {
if (active_listener == this) {
// wait for any output to complete
while (active_out);
if (_half_duplex) setRXTX(false);
active_listener = nullptr;
active_in = nullptr;
// turn off ints
setSpeed(0);
return true;
}
return false;
}
inline void SoftwareSerial::setTX() {
if (_inverse_logic)
LL_GPIO_ResetOutputPin(_transmitPinPort, _transmitPinNumber);
else
LL_GPIO_SetOutputPin(_transmitPinPort, _transmitPinNumber);
pinMode(_transmitPin, OUTPUT);
}
inline void SoftwareSerial::setRX() {
pinMode(_receivePin, _inverse_logic ? INPUT_PULLDOWN : INPUT_PULLUP); // pullup for normal logic!
}
inline void SoftwareSerial::setRXTX(bool input) {
if (_half_duplex) {
if (input) {
if (active_in != this) {
setRX();
rx_bit_cnt = -1; // rx_bit_cnt = -1 : waiting for start bit
rx_tick_cnt = 2; // 2 : next interrupt will be discarded. 2 interrupts required to consider RX pin level
active_in = this;
}
}
else {
if (active_in == this) {
setTX();
active_in = nullptr;
}
}
}
}
inline void SoftwareSerial::send() {
if (--tx_tick_cnt <= 0) { // if tx_tick_cnt > 0 interrupt is discarded. Only when tx_tick_cnt reaches 0 is TX pin set.
if (tx_bit_cnt++ < 10) { // tx_bit_cnt < 10 transmission is not finished (10 = 1 start +8 bits + 1 stop)
// Send data (including start and stop bits)
if (tx_buffer & 1)
LL_GPIO_SetOutputPin(_transmitPinPort, _transmitPinNumber);
else
LL_GPIO_ResetOutputPin(_transmitPinPort, _transmitPinNumber);
tx_buffer >>= 1;
tx_tick_cnt = OVERSAMPLE; // Wait OVERSAMPLE ticks to send next bit
}
else { // Transmission finished
tx_tick_cnt = 1;
if (_output_pending) {
active_out = nullptr;
// In half-duplex mode wait HALFDUPLEX_SWITCH_DELAY bit-periods after the byte has
// been transmitted before allowing the switch to RX mode
}
else if (tx_bit_cnt > 10 + OVERSAMPLE * HALFDUPLEX_SWITCH_DELAY) {
if (_half_duplex && active_listener == this) setRXTX(true);
active_out = nullptr;
}
}
}
}
//
// The receive routine called by the interrupt handler
//
inline void SoftwareSerial::recv() {
if (--rx_tick_cnt <= 0) { // if rx_tick_cnt > 0 interrupt is discarded. Only when rx_tick_cnt reaches 0 is RX pin considered
bool inbit = LL_GPIO_IsInputPinSet(_receivePinPort, _receivePinNumber) ^ _inverse_logic;
if (rx_bit_cnt == -1) { // rx_bit_cnt = -1 : waiting for start bit
if (!inbit) {
// got start bit
rx_bit_cnt = 0; // rx_bit_cnt == 0 : start bit received
rx_tick_cnt = OVERSAMPLE + 1; // Wait 1 bit (OVERSAMPLE ticks) + 1 tick in order to sample RX pin in the middle of the edge (and not too close to the edge)
rx_buffer = 0;
}
else
rx_tick_cnt = 1; // Waiting for start bit, but wrong level. Wait for next Interrupt to check RX pin level
}
else if (rx_bit_cnt >= 8) { // rx_bit_cnt >= 8 : waiting for stop bit
if (inbit) {
// Stop-bit read complete. Add to buffer.
uint8_t next = (_receive_buffer_tail + 1) % _SS_MAX_RX_BUFF;
if (next != _receive_buffer_head) {
// save new data in buffer: tail points to byte destination
_receive_buffer[_receive_buffer_tail] = rx_buffer; // save new byte
_receive_buffer_tail = next;
}
else // rx_bit_cnt = x with x = [0..7] correspond to new bit x received
_buffer_overflow = true;
}
// Full trame received. Restart waiting for start bit at next interrupt
rx_tick_cnt = 1;
rx_bit_cnt = -1;
}
else {
// data bits
rx_buffer >>= 1;
if (inbit) rx_buffer |= 0x80;
rx_bit_cnt++; // Prepare for next bit
rx_tick_cnt = OVERSAMPLE; // Wait OVERSAMPLE ticks before sampling next bit
}
}
}
//
// Interrupt handling
//
/* static */
inline void SoftwareSerial::handleInterrupt(HardwareTimer*) {
if (active_in) active_in->recv();
if (active_out) active_out->send();
}
//
// Constructor
//
SoftwareSerial::SoftwareSerial(uint16_t receivePin, uint16_t transmitPin, bool inverse_logic /* = false */) :
_receivePin(receivePin),
_transmitPin(transmitPin),
_receivePinPort(digitalPinToPort(receivePin)),
_receivePinNumber(STM_LL_GPIO_PIN(digitalPinToPinName(receivePin))),
_transmitPinPort(digitalPinToPort(transmitPin)),
_transmitPinNumber(STM_LL_GPIO_PIN(digitalPinToPinName(transmitPin))),
_speed(0),
_buffer_overflow(false),
_inverse_logic(inverse_logic),
_half_duplex(receivePin == transmitPin),
_output_pending(0),
_receive_buffer_tail(0),
_receive_buffer_head(0)
{
if ((receivePin < NUM_DIGITAL_PINS) || (transmitPin < NUM_DIGITAL_PINS)) {
/* Enable GPIO clock for tx and rx pin*/
set_GPIO_Port_Clock(STM_PORT(digitalPinToPinName(transmitPin)));
set_GPIO_Port_Clock(STM_PORT(digitalPinToPinName(receivePin)));
}
else
_Error_Handler("ERROR: invalid pin number\n", -1);
}
//
// Destructor
//
SoftwareSerial::~SoftwareSerial() { end(); }
//
// Public methods
//
void SoftwareSerial::begin(long speed) {
#ifdef FORCE_BAUD_RATE
speed = FORCE_BAUD_RATE;
#endif
_speed = speed;
if (!_half_duplex) {
setTX();
setRX();
listen();
}
else
setTX();
}
void SoftwareSerial::end() {
stopListening();
}
// Read data from buffer
int SoftwareSerial::read() {
// Empty buffer?
if (_receive_buffer_head == _receive_buffer_tail) return -1;
// Read from "head"
uint8_t d = _receive_buffer[_receive_buffer_head]; // grab next byte
_receive_buffer_head = (_receive_buffer_head + 1) % _SS_MAX_RX_BUFF;
return d;
}
int SoftwareSerial::available() {
return (_receive_buffer_tail + _SS_MAX_RX_BUFF - _receive_buffer_head) % _SS_MAX_RX_BUFF;
}
size_t SoftwareSerial::write(uint8_t b) {
// wait for previous transmit to complete
_output_pending = 1;
while (active_out) { /* nada */ }
// add start and stop bits.
tx_buffer = b << 1 | 0x200;
if (_inverse_logic) tx_buffer = ~tx_buffer;
tx_bit_cnt = 0;
tx_tick_cnt = OVERSAMPLE;
setSpeed(_speed);
if (_half_duplex) setRXTX(false);
_output_pending = 0;
// make us active
active_out = this;
return 1;
}
void SoftwareSerial::flush() {
noInterrupts();
_receive_buffer_head = _receive_buffer_tail = 0;
interrupts();
}
int SoftwareSerial::peek() {
// Empty buffer?
if (_receive_buffer_head == _receive_buffer_tail) return -1;
// Read from "head"
return _receive_buffer[_receive_buffer_head];
}
#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC

View File

@ -0,0 +1,119 @@
/**
* SoftwareSerial.h (formerly NewSoftSerial.h)
*
* Multi-instance software serial library for Arduino/Wiring
* -- Interrupt-driven receive and other improvements by ladyada
* (http://ladyada.net)
* -- Tuning, circular buffer, derivation from class Print/Stream,
* multi-instance support, porting to 8MHz processors,
* various optimizations, PROGMEM delay tables, inverse logic and
* direct port writing by Mikal Hart (http://www.arduiniana.org)
* -- Pin change interrupt macros by Paul Stoffregen (http://www.pjrc.com)
* -- 20MHz processor support by Garrett Mace (http://www.macetech.com)
* -- ATmega1280/2560 support by Brett Hagman (http://www.roguerobotics.com/)
*
* This library is free software; you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public
* License as published by the Free Software Foundation; either
* version 2.1 of the License, or (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public
* License along with this library; if not, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* The latest version of this library can always be found at
* http://arduiniana.org.
*/
#ifndef SOFTWARESERIAL_H
#define SOFTWARESERIAL_H
#include <Arduino.h>
/******************************************************************************
* Definitions
******************************************************************************/
#define _SS_MAX_RX_BUFF 64 // RX buffer size
class SoftwareSerial : public Stream {
private:
// per object data
uint16_t _receivePin;
uint16_t _transmitPin;
GPIO_TypeDef *_receivePinPort;
uint32_t _receivePinNumber;
GPIO_TypeDef *_transmitPinPort;
uint32_t _transmitPinNumber;
uint32_t _speed;
uint16_t _buffer_overflow: 1;
uint16_t _inverse_logic: 1;
uint16_t _half_duplex: 1;
uint16_t _output_pending: 1;
unsigned char _receive_buffer[_SS_MAX_RX_BUFF];
volatile uint8_t _receive_buffer_tail;
volatile uint8_t _receive_buffer_head;
uint32_t delta_start = 0;
// static data
static bool initialised;
static HardwareTimer timer;
static const IRQn_Type timer_interrupt_number;
static uint32_t timer_interrupt_priority;
static SoftwareSerial *active_listener;
static SoftwareSerial *volatile active_out;
static SoftwareSerial *volatile active_in;
static int32_t tx_tick_cnt;
static volatile int32_t rx_tick_cnt;
static uint32_t tx_buffer;
static int32_t tx_bit_cnt;
static uint32_t rx_buffer;
static int32_t rx_bit_cnt;
static uint32_t cur_speed;
// private methods
void send();
void recv();
void setTX();
void setRX();
void setSpeed(uint32_t speed);
void setRXTX(bool input);
static void handleInterrupt(HardwareTimer *timer);
public:
// public methods
SoftwareSerial(uint16_t receivePin, uint16_t transmitPin, bool inverse_logic = false);
virtual ~SoftwareSerial();
void begin(long speed);
bool listen();
void end();
bool isListening() { return active_listener == this; }
bool stopListening();
bool overflow() {
bool ret = _buffer_overflow;
if (ret) _buffer_overflow = false;
return ret;
}
int peek();
virtual size_t write(uint8_t byte);
virtual int read();
virtual int available();
virtual void flush();
operator bool() { return true; }
static void setInterruptPriority(uint32_t preemptPriority, uint32_t subPriority);
using Print::write;
};
#endif // SOFTWARESERIAL_H

View File

@ -0,0 +1,70 @@
/**
* 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
* Copyright (c) 2017 Victor Perez
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
#include "../../module/endstops.h"
// One ISR for all EXT-Interrupts
void endstop_ISR() { endstops.update(); }
void setup_endstop_interrupts() {
#if HAS_X_MAX
attachInterrupt(X_MAX_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_X_MIN
attachInterrupt(X_MIN_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_Y_MAX
attachInterrupt(Y_MAX_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_Y_MIN
attachInterrupt(Y_MIN_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_Z_MAX
attachInterrupt(Z_MAX_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_Z_MIN
attachInterrupt(Z_MIN_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_Z2_MAX
attachInterrupt(Z2_MAX_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_Z2_MIN
attachInterrupt(Z2_MIN_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_Z3_MAX
attachInterrupt(Z3_MAX_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_Z3_MIN
attachInterrupt(Z3_MIN_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_Z4_MAX
attachInterrupt(Z4_MAX_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_Z4_MIN
attachInterrupt(Z4_MIN_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_Z_MIN_PROBE_PIN
attachInterrupt(Z_MIN_PROBE_PIN, endstop_ISR, CHANGE);
#endif
}

View File

@ -0,0 +1,34 @@
/**
* 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
* Copyright (c) 2017 Victor Perez
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
#include "../../inc/MarlinConfig.h"
GPIO_TypeDef* FastIOPortMap[LastPort + 1];
void FastIO_init() {
for (uint8_t i = 0; i < NUM_DIGITAL_PINS; i++)
FastIOPortMap[STM_PORT(digitalPin[i])] = get_GPIO_Port(STM_PORT(digitalPin[i]));
}
#endif

View File

@ -0,0 +1,87 @@
/**
* 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
* Copyright (c) 2017 Victor Perez
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Fast I/O interfaces for STM32
* These use GPIO register access for fast port manipulation.
*/
// ------------------------
// Public Variables
// ------------------------
extern GPIO_TypeDef * FastIOPortMap[];
// ------------------------
// Public functions
// ------------------------
void FastIO_init(); // Must be called before using fast io macros
// ------------------------
// Defines
// ------------------------
#define _BV32(b) (1UL << (b))
#ifndef PWM
#define PWM OUTPUT
#endif
#if defined(STM32F0xx) || defined(STM32F1xx) || defined(STM32F3xx) || defined(STM32L0xx) || defined(STM32L4xx)
#define _WRITE(IO, V) do { \
if (V) FastIOPortMap[STM_PORT(digitalPin[IO])]->BSRR = _BV32(STM_PIN(digitalPin[IO])) ; \
else FastIOPortMap[STM_PORT(digitalPin[IO])]->BRR = _BV32(STM_PIN(digitalPin[IO])) ; \
}while(0)
#else
#define _WRITE(IO, V) (FastIOPortMap[STM_PORT(digitalPin[IO])]->BSRR = _BV32(STM_PIN(digitalPin[IO]) + ((V) ? 0 : 16)))
#endif
#define _READ(IO) bool(READ_BIT(FastIOPortMap[STM_PORT(digitalPin[IO])]->IDR, _BV32(STM_PIN(digitalPin[IO]))))
#define _TOGGLE(IO) (FastIOPortMap[STM_PORT(digitalPin[IO])]->ODR ^= _BV32(STM_PIN(digitalPin[IO])))
#define _GET_MODE(IO)
#define _SET_MODE(IO,M) pinMode(IO, M)
#define _SET_OUTPUT(IO) pinMode(IO, OUTPUT) /*!< Output Push Pull Mode & GPIO_NOPULL */
#define WRITE(IO,V) _WRITE(IO,V)
#define READ(IO) _READ(IO)
#define TOGGLE(IO) _TOGGLE(IO)
#define OUT_WRITE(IO,V) do{ _SET_OUTPUT(IO); WRITE(IO,V); }while(0)
#define SET_INPUT(IO) _SET_MODE(IO, INPUT) /*!< Input Floating Mode */
#define SET_INPUT_PULLUP(IO) _SET_MODE(IO, INPUT_PULLUP) /*!< Input with Pull-up activation */
#define SET_INPUT_PULLDOWN(IO) _SET_MODE(IO, INPUT_PULLDOWN) /*!< Input with Pull-down activation */
#define SET_OUTPUT(IO) OUT_WRITE(IO, LOW)
#define SET_PWM(IO) _SET_MODE(IO, PWM)
#define IS_INPUT(IO)
#define IS_OUTPUT(IO)
#define PWM_PIN(P) digitalPinHasPWM(P)
// digitalRead/Write wrappers
#define extDigitalRead(IO) digitalRead(IO)
#define extDigitalWrite(IO,V) digitalWrite(IO,V)

View File

@ -0,0 +1,22 @@
/**
* 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

View File

@ -0,0 +1,22 @@
/**
* 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

View File

@ -0,0 +1,22 @@
/**
* 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

View File

@ -0,0 +1,37 @@
/**
* 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
/**
* Test STM32-specific configuration values for errors at compile-time.
*/
//#if ENABLED(SPINDLE_LASER_PWM) && !(SPINDLE_LASER_PWM_PIN == 4 || SPINDLE_LASER_PWM_PIN == 6 || SPINDLE_LASER_PWM_PIN == 11)
// #error "SPINDLE_LASER_PWM_PIN must use SERVO0, SERVO1 or SERVO3 connector"
//#endif
#if ENABLED(EMERGENCY_PARSER)
#error "EMERGENCY_PARSER is not yet implemented for STM32. Disable EMERGENCY_PARSER to continue."
#endif
#if ENABLED(FAST_PWM_FAN)
#error "FAST_PWM_FAN is not yet implemented for this platform."
#endif

View File

@ -0,0 +1,265 @@
/**
* Marlin 3D Printer Firmware
*
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
* Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
* Copyright (c) 2016 Victor Perez victor_pv@hotmail.com
*
* 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/>.
*
*/
#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
#include "../../inc/MarlinConfig.h"
#if BOTH(EEPROM_SETTINGS, FLASH_EEPROM_EMULATION)
#include "../shared/persistent_store_api.h"
// Only STM32F4 can support wear leveling at this time
#ifndef STM32F4xx
#undef FLASH_EEPROM_LEVELING
#endif
/**
* The STM32 HAL supports chips that deal with "pages" and some with "sectors" and some that
* even have multiple "banks" of flash.
*
* This code is a bit of a mashup of
* framework-arduinoststm32/cores/arduino/stm32/stm32_eeprom.c
* hal/hal_lpc1768/persistent_store_flash.cpp
*
* This has only be written against those that use a single "sector" design.
*
* Those that deal with "pages" could be made to work. Looking at the STM32F07 for example, there are
* 128 "pages", each 2kB in size. If we continued with our EEPROM being 4Kb, we'd always need to operate
* on 2 of these pages. Each write, we'd use 2 different pages from a pool of pages until we are done.
*/
#if ENABLED(FLASH_EEPROM_LEVELING)
#include "stm32_def.h"
#define DEBUG_OUT ENABLED(EEPROM_CHITCHAT)
#include "src/core/debug_out.h"
#ifndef EEPROM_SIZE
#define EEPROM_SIZE 0x1000 // 4kB
#endif
#ifndef FLASH_SECTOR
#define FLASH_SECTOR (FLASH_SECTOR_TOTAL - 1)
#endif
#ifndef FLASH_UNIT_SIZE
#define FLASH_UNIT_SIZE 0x20000 // 128kB
#endif
#define FLASH_ADDRESS_START (FLASH_END - ((FLASH_SECTOR_TOTAL - FLASH_SECTOR) * FLASH_UNIT_SIZE) + 1)
#define FLASH_ADDRESS_END (FLASH_ADDRESS_START + FLASH_UNIT_SIZE - 1)
#define EEPROM_SLOTS (FLASH_UNIT_SIZE/EEPROM_SIZE)
#define SLOT_ADDRESS(slot) (FLASH_ADDRESS_START + (slot * EEPROM_SIZE))
#define UNLOCK_FLASH() if (!flash_unlocked) { \
HAL_FLASH_Unlock(); \
__HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | \
FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR); \
flash_unlocked = true; \
}
#define LOCK_FLASH() if (flash_unlocked) { HAL_FLASH_Lock(); flash_unlocked = false; }
#define EMPTY_UINT32 ((uint32_t)-1)
#define EMPTY_UINT8 ((uint8_t)-1)
static uint8_t ram_eeprom[EEPROM_SIZE] __attribute__((aligned(4))) = {0};
static int current_slot = -1;
static_assert(0 == EEPROM_SIZE % 4, "EEPROM_SIZE must be a multiple of 4"); // Ensure copying as uint32_t is safe
static_assert(0 == FLASH_UNIT_SIZE % EEPROM_SIZE, "EEPROM_SIZE must divide evenly into your FLASH_UNIT_SIZE");
static_assert(FLASH_UNIT_SIZE >= EEPROM_SIZE, "FLASH_UNIT_SIZE must be greater than or equal to your EEPROM_SIZE");
static_assert(IS_FLASH_SECTOR(FLASH_SECTOR), "FLASH_SECTOR is invalid");
static_assert(IS_POWER_OF_2(FLASH_UNIT_SIZE), "FLASH_UNIT_SIZE should be a power of 2, please check your chip's spec sheet");
#endif
static bool eeprom_data_written = false;
bool PersistentStore::access_start() {
#if ENABLED(FLASH_EEPROM_LEVELING)
if (current_slot == -1 || eeprom_data_written) {
// This must be the first time since power on that we have accessed the storage, or someone
// loaded and called write_data and never called access_finish.
// Lets go looking for the slot that holds our configuration.
if (eeprom_data_written) DEBUG_ECHOLN("Dangling EEPROM write_data");
uint32_t address = FLASH_ADDRESS_START;
while (address <= FLASH_ADDRESS_END) {
uint32_t address_value = (*(__IO uint32_t*)address);
if (address_value != EMPTY_UINT32) {
current_slot = (address - FLASH_ADDRESS_START) / EEPROM_SIZE;
break;
}
address += sizeof(uint32_t);
}
if (current_slot == -1) {
// We didn't find anything, so we'll just intialize to empty
for (int i = 0; i < EEPROM_SIZE; i++) ram_eeprom[i] = EMPTY_UINT8;
current_slot = EEPROM_SLOTS;
}
else {
// load current settings
uint8_t *eeprom_data = (uint8_t *)SLOT_ADDRESS(current_slot);
for (int i = 0; i < EEPROM_SIZE; i++) ram_eeprom[i] = eeprom_data[i];
DEBUG_ECHOLNPAIR("EEPROM loaded from slot ", current_slot, ".");
}
eeprom_data_written = false;
}
#else
eeprom_buffer_fill();
#endif
return true;
}
bool PersistentStore::access_finish() {
if (eeprom_data_written) {
#if ENABLED(FLASH_EEPROM_LEVELING)
HAL_StatusTypeDef status = HAL_ERROR;
bool flash_unlocked = false;
if (--current_slot < 0) {
// all slots have been used, erase everything and start again
FLASH_EraseInitTypeDef EraseInitStruct;
uint32_t SectorError = 0;
EraseInitStruct.TypeErase = FLASH_TYPEERASE_SECTORS;
EraseInitStruct.VoltageRange = FLASH_VOLTAGE_RANGE_3;
EraseInitStruct.Sector = FLASH_SECTOR;
EraseInitStruct.NbSectors = 1;
current_slot = EEPROM_SLOTS - 1;
UNLOCK_FLASH();
status = HAL_FLASHEx_Erase(&EraseInitStruct, &SectorError);
if (status != HAL_OK) {
DEBUG_ECHOLNPAIR("HAL_FLASHEx_Erase=", status);
DEBUG_ECHOLNPAIR("GetError=", HAL_FLASH_GetError());
DEBUG_ECHOLNPAIR("SectorError=", SectorError);
LOCK_FLASH();
return false;
}
}
UNLOCK_FLASH();
uint32_t offset = 0;
uint32_t address = SLOT_ADDRESS(current_slot);
uint32_t address_end = address + EEPROM_SIZE;
uint32_t data = 0;
bool success = true;
while (address < address_end) {
memcpy(&data, ram_eeprom + offset, sizeof(uint32_t));
status = HAL_FLASH_Program(FLASH_TYPEPROGRAM_WORD, address, data);
if (status == HAL_OK) {
address += sizeof(uint32_t);
offset += sizeof(uint32_t);
}
else {
DEBUG_ECHOLNPAIR("HAL_FLASH_Program=", status);
DEBUG_ECHOLNPAIR("GetError=", HAL_FLASH_GetError());
DEBUG_ECHOLNPAIR("address=", address);
success = false;
break;
}
}
LOCK_FLASH();
if (success) {
eeprom_data_written = false;
DEBUG_ECHOLNPAIR("EEPROM saved to slot ", current_slot, ".");
}
return success;
#else
eeprom_buffer_flush();
eeprom_data_written = false;
#endif
}
return true;
}
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
while (size--) {
uint8_t v = *value;
#if ENABLED(FLASH_EEPROM_LEVELING)
if (v != ram_eeprom[pos]) {
ram_eeprom[pos] = v;
eeprom_data_written = true;
}
#else
if (v != eeprom_buffered_read_byte(pos)) {
eeprom_buffered_write_byte(pos, v);
eeprom_data_written = true;
}
#endif
crc16(crc, &v, 1);
pos++;
value++;
}
return false;
}
bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
do {
const uint8_t c = (
#if ENABLED(FLASH_EEPROM_LEVELING)
ram_eeprom[pos]
#else
eeprom_buffered_read_byte(pos)
#endif
);
if (writing) *value = c;
crc16(crc, &c, 1);
pos++;
value++;
} while (--size);
return false;
}
size_t PersistentStore::capacity() {
return (
#if ENABLED(FLASH_EEPROM_LEVELING)
EEPROM_SIZE
#else
E2END + 1
#endif
);
}
#endif // EEPROM_SETTINGS && FLASH_EEPROM_EMULATION
#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC

View File

@ -0,0 +1,97 @@
/**
* Marlin 3D Printer Firmware
*
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
* Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
* Copyright (c) 2016 Victor Perez victor_pv@hotmail.com
*
* 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/>.
*
*/
#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
#include "../../inc/MarlinConfig.h"
#if EITHER(USE_REAL_EEPROM, SRAM_EEPROM_EMULATION)
#include "../shared/persistent_store_api.h"
bool PersistentStore::access_start() {
return true;
}
bool PersistentStore::access_finish() {
return true;
}
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
while (size--) {
uint8_t v = *value;
// Save to either external EEPROM, program flash or Backup SRAM
#if USE_REAL_EEPROM
// EEPROM has only ~100,000 write cycles,
// so only write bytes that have changed!
uint8_t * const p = (uint8_t * const)pos;
if (v != eeprom_read_byte(p)) {
eeprom_write_byte(p, v);
if (eeprom_read_byte(p) != v) {
SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE);
return true;
}
}
#else
*(__IO uint8_t *)(BKPSRAM_BASE + (uint8_t * const)pos) = v;
#endif
crc16(crc, &v, 1);
pos++;
value++;
};
return false;
}
bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
do {
// Read from either external EEPROM, program flash or Backup SRAM
const uint8_t c = (
#if USE_REAL_EEPROM
eeprom_read_byte((uint8_t*)pos)
#else
(*(__IO uint8_t *)(BKPSRAM_BASE + ((uint8_t*)pos)))
#endif
);
if (writing) *value = c;
crc16(crc, &c, 1);
pos++;
value++;
} while (--size);
return false;
}
size_t PersistentStore::capacity() {
return (
#if USE_REAL_EEPROM
E2END + 1
#else
4096 // 4kB
#endif
);
}
#endif // USE_REAL_EEPROM || SRAM_EEPROM_EMULATION
#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC

View File

@ -0,0 +1,103 @@
/**
* 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/>.
*
*/
/**
* Implementation of EEPROM settings in SD Card
*/
#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
#include "../../inc/MarlinConfig.h"
#if ENABLED(SDCARD_EEPROM_EMULATION)
#include "../shared/persistent_store_api.h"
#ifndef E2END
#define E2END 0xFFF // 4KB
#endif
#define HAL_EEPROM_SIZE int(E2END + 1)
#define _ALIGN(x) __attribute__ ((aligned(x)))
static char _ALIGN(4) HAL_eeprom_data[HAL_EEPROM_SIZE];
#if ENABLED(SDSUPPORT)
#include "../../sd/cardreader.h"
#define EEPROM_FILENAME "eeprom.dat"
bool PersistentStore::access_start() {
if (!card.isMounted()) return false;
SdFile file, root = card.getroot();
if (!file.open(&root, EEPROM_FILENAME, O_RDONLY))
return true;
int bytes_read = file.read(HAL_eeprom_data, HAL_EEPROM_SIZE);
if (bytes_read < 0) return false;
for (; bytes_read < HAL_EEPROM_SIZE; bytes_read++)
HAL_eeprom_data[bytes_read] = 0xFF;
file.close();
return true;
}
bool PersistentStore::access_finish() {
if (!card.isMounted()) return false;
SdFile file, root = card.getroot();
int bytes_written = 0;
if (file.open(&root, EEPROM_FILENAME, O_CREAT | O_WRITE | O_TRUNC)) {
bytes_written = file.write(HAL_eeprom_data, HAL_EEPROM_SIZE);
file.close();
}
return (bytes_written == HAL_EEPROM_SIZE);
}
#else // !SDSUPPORT
#error "Please define an EEPROM, a SDCARD or disable EEPROM_SETTINGS."
#endif // !SDSUPPORT
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
for (size_t i = 0; i < size; i++)
HAL_eeprom_data[pos + i] = value[i];
crc16(crc, value, size);
pos += size;
return false;
}
bool PersistentStore::read_data(int &pos, uint8_t* value, const size_t size, uint16_t *crc, const bool writing/*=true*/) {
for (size_t i = 0; i < size; i++) {
uint8_t c = HAL_eeprom_data[pos + i];
if (writing) value[i] = c;
crc16(crc, &c, 1);
}
pos += size;
return false;
}
size_t PersistentStore::capacity() { return HAL_EEPROM_SIZE; }
#endif // SDCARD_EEPROM_EMULATION
#endif // STM32 && !STM32GENERIC

View File

@ -0,0 +1,34 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* 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 !(defined(NUM_DIGITAL_PINS) || defined(BOARD_NR_GPIO_PINS))
#error "M43 not supported for this board"
#endif
// Strange - STM32F4 comes to HAL_STM32 rather than HAL_STM32F4 for these files
#ifdef STM32F4
#ifdef NUM_DIGITAL_PINS // Only in ST's Arduino core (STM32duino, STM32Core)
#include "pinsDebug_STM32duino.h"
#elif defined(BOARD_NR_GPIO_PINS) // Only in STM32GENERIC (Maple)
#include "pinsDebug_STM32GENERIC.h"
#else
#error "M43 not supported for this board"
#endif
#endif

View File

@ -0,0 +1,125 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* 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
/**
* Support routines for STM32GENERIC (Maple)
*/
/**
* Translation of routines & variables used by pinsDebug.h
*/
#ifdef BOARD_NR_GPIO_PINS // Only in STM32GENERIC (Maple)
#ifdef __STM32F1__
#include "../STM32F1/fastio.h"
#elif defined(STM32F4) || defined(STM32F7)
#include "../STM32_F4_F7/fastio.h"
#else
#include "fastio.h"
#endif
extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS];
#define NUM_DIGITAL_PINS BOARD_NR_GPIO_PINS
#define NUMBER_PINS_TOTAL BOARD_NR_GPIO_PINS
#define VALID_PIN(pin) (pin >= 0 && pin < BOARD_NR_GPIO_PINS)
#define GET_ARRAY_PIN(p) pin_t(pin_array[p].pin)
#define pwm_status(pin) PWM_PIN(pin)
#define digitalRead_mod(p) extDigitalRead(p)
#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%3hd "), int16_t(p)); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PORT(p) print_port(p)
#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
#define MULTI_NAME_PAD 21 // space needed to be pretty if not first name assigned to a pin
// pins that will cause hang/reset/disconnect in M43 Toggle and Watch utilities
#ifndef M43_NEVER_TOUCH
#define M43_NEVER_TOUCH(Q) (Q >= 9 && Q <= 12) // SERIAL/USB pins PA9(TX) PA10(RX)
#endif
static inline int8_t get_pin_mode(pin_t pin) {
return VALID_PIN(pin) ? _GET_MODE(pin) : -1;
}
static inline pin_t DIGITAL_PIN_TO_ANALOG_PIN(pin_t pin) {
if (!VALID_PIN(pin)) return -1;
int8_t adc_channel = int8_t(PIN_MAP[pin].adc_channel);
#ifdef NUM_ANALOG_INPUTS
if (adc_channel >= NUM_ANALOG_INPUTS) adc_channel = ADCx;
#endif
return pin_t(adc_channel);
}
static inline bool IS_ANALOG(pin_t pin) {
if (!VALID_PIN(pin)) return false;
if (PIN_MAP[pin].adc_channel != ADCx) {
#ifdef NUM_ANALOG_INPUTS
if (PIN_MAP[pin].adc_channel >= NUM_ANALOG_INPUTS) return false;
#endif
return _GET_MODE(pin) == GPIO_INPUT_ANALOG && !M43_NEVER_TOUCH(pin);
}
return false;
}
static inline bool GET_PINMODE(const pin_t pin) {
return VALID_PIN(pin) && !IS_INPUT(pin);
}
static inline bool GET_ARRAY_IS_DIGITAL(const int16_t array_pin) {
const pin_t pin = GET_ARRAY_PIN(array_pin);
return (!IS_ANALOG(pin)
#ifdef NUM_ANALOG_INPUTS
|| PIN_MAP[pin].adc_channel >= NUM_ANALOG_INPUTS
#endif
);
}
#include "../../inc/MarlinConfig.h" // Allow pins/pins.h to set density
static inline void pwm_details(const pin_t pin) {
if (PWM_PIN(pin)) {
timer_dev * const tdev = PIN_MAP[pin].timer_device;
const uint8_t channel = PIN_MAP[pin].timer_channel;
const char num = (
#if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY)
tdev == &timer8 ? '8' :
tdev == &timer5 ? '5' :
#endif
tdev == &timer4 ? '4' :
tdev == &timer3 ? '3' :
tdev == &timer2 ? '2' :
tdev == &timer1 ? '1' : '?'
);
char buffer[10];
sprintf_P(buffer, PSTR(" TIM%c CH%c"), num, ('0' + channel));
SERIAL_ECHO(buffer);
}
}
static inline void print_port(pin_t pin) {
const char port = 'A' + char(pin >> 4); // pin div 16
const int16_t gbit = PIN_MAP[pin].gpio_bit;
char buffer[8];
sprintf_P(buffer, PSTR("P%c%hd "), port, gbit);
if (gbit < 10) SERIAL_CHAR(' ');
SERIAL_ECHO(buffer);
}
#endif // BOARD_NR_GPIO_PINS

View File

@ -0,0 +1,275 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* 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
#include <Arduino.h>
#ifdef NUM_DIGITAL_PINS // Only in ST's Arduino core (STM32duino, STM32Core)
/**
* Life gets complicated if you want an easy to use 'M43 I' output (in port/pin order)
* because the variants in this platform do not always define all the I/O port/pins
* that a CPU has.
*
* VARIABLES:
* Ard_num - Arduino pin number - defined by the platform. It is used by digitalRead and
* digitalWrite commands and by M42.
* - does not contain port/pin info
* - is not in port/pin order
* - typically a variant will only assign Ard_num to port/pins that are actually used
* Index - M43 counter - only used to get Ard_num
* x - a parameter/argument used to search the pin_array to try to find a signal name
* associated with a Ard_num
* Port_pin - port number and pin number for use with CPU registers and printing reports
*
* Since M43 uses digitalRead and digitalWrite commands, only the Port_pins with an Ard_num
* are accessed and/or displayed.
*
* Three arrays are used.
*
* digitalPin[] is provided by the platform. It consists of the Port_pin numbers in
* Arduino pin number order.
*
* pin_array is a structure generated by the pins/pinsDebug.h header file. It is generated by
* the preprocessor. Only the signals associated with enabled options are in this table.
* It contains:
* - name of the signal
* - the Ard_num assigned by the pins_YOUR_BOARD.h file using the platform defines.
* EXAMPLE: "#define KILL_PIN PB1" results in Ard_num of 57. 57 is then used as an
* index into digitalPin[] to get the Port_pin number
* - if it is a digital or analog signal. PWMs are considered digital here.
*
* pin_xref is a structure generated by this header file. It is generated by the
* preprocessor. It is in port/pin order. It contains just the port/pin numbers defined by the
* platform for this variant.
* - Ard_num
* - printable version of Port_pin
*
* Routines with an "x" as a parameter/argument are used to search the pin_array to try to
* find a signal name associated with a port/pin.
*
* NOTE - the Arduino pin number is what is used by the M42 command, NOT the port/pin for that
* signal. The Arduino pin number is listed by the M43 I command.
*/
extern const PinName digitalPin[]; // provided by the platform
////////////////////////////////////////////////////////
//
// make a list of the Arduino pin numbers in the Port/Pin order
//
#define _PIN_ADD_2(NAME_ALPHA, ARDUINO_NUM) { {NAME_ALPHA}, ARDUINO_NUM },
#define _PIN_ADD(NAME_ALPHA, ARDUINO_NUM) { NAME_ALPHA, ARDUINO_NUM },
#define PIN_ADD(NAME) _PIN_ADD(#NAME, NAME)
typedef struct {
char Port_pin_alpha[5];
pin_t Ard_num;
} XrefInfo;
const XrefInfo pin_xref[] PROGMEM = {
#include "pins_Xref.h"
};
////////////////////////////////////////////////////////////
#define MODE_PIN_INPUT 0 // Input mode (reset state)
#define MODE_PIN_OUTPUT 1 // General purpose output mode
#define MODE_PIN_ALT 2 // Alternate function mode
#define MODE_PIN_ANALOG 3 // Analog mode
#define PIN_NUM(P) (P & 0x000F)
#define PIN_NUM_ALPHA_LEFT(P) (((P & 0x000F) < 10) ? ('0' + (P & 0x000F)) : '1')
#define PIN_NUM_ALPHA_RIGHT(P) (((P & 0x000F) > 9) ? ('0' + (P & 0x000F) - 10) : 0 )
#define PORT_NUM(P) ((P >> 4) & 0x0007)
#define PORT_ALPHA(P) ('A' + (P >> 4))
/**
* Translation of routines & variables used by pinsDebug.h
*/
#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS
#define VALID_PIN(ANUM) ((ANUM) >= 0 && (ANUM) < NUMBER_PINS_TOTAL)
#define digitalRead_mod(Ard_num) extDigitalRead(Ard_num) // must use Arduino pin numbers when doing reads
#define PRINT_PIN(Q)
#define PRINT_PORT(ANUM) port_print(ANUM)
#define DIGITAL_PIN_TO_ANALOG_PIN(ANUM) -1 // will report analog pin number in the print port routine
#define GET_PIN_MAP_PIN_M43(Index) pin_xref[Index].Ard_num
// x is a variable used to search pin_array
#define GET_ARRAY_IS_DIGITAL(x) ((bool) pin_array[x].is_digital)
#define GET_ARRAY_PIN(x) ((pin_t) pin_array[x].pin)
#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
#define MULTI_NAME_PAD 33 // space needed to be pretty if not first name assigned to a pin
#ifndef M43_NEVER_TOUCH
#define _M43_NEVER_TOUCH(Index) (Index >= 9 && Index <= 12) // SERIAL/USB pins: PA9(TX) PA10(RX) PA11(USB_DM) PA12(USB_DP)
#ifdef KILL_PIN
#define M43_NEVER_TOUCH(Index) m43_never_touch(Index)
bool m43_never_touch(const pin_t Index) {
static pin_t M43_kill_index = -1;
if (M43_kill_index < 0)
for (M43_kill_index = 0; M43_kill_index < NUMBER_PINS_TOTAL; M43_kill_index++)
if (KILL_PIN == GET_PIN_MAP_PIN_M43(M43_kill_index)) break;
return _M43_NEVER_TOUCH(Index) || Index == M43_kill_index; // KILL_PIN and SERIAL/USB
}
#else
#define M43_NEVER_TOUCH(Index) _M43_NEVER_TOUCH(Index)
#endif
#endif
uint8_t get_pin_mode(const pin_t Ard_num) {
uint32_t mode_all = 0;
const PinName dp = digitalPin[Ard_num];
switch (PORT_ALPHA(dp)) {
case 'A' : mode_all = GPIOA->MODER; break;
case 'B' : mode_all = GPIOB->MODER; break;
case 'C' : mode_all = GPIOC->MODER; break;
case 'D' : mode_all = GPIOD->MODER; break;
#ifdef PE_0
case 'E' : mode_all = GPIOE->MODER; break;
#elif defined(PF_0)
case 'F' : mode_all = GPIOF->MODER; break;
#elif defined(PG_0)
case 'G' : mode_all = GPIOG->MODER; break;
#elif defined(PH_0)
case 'H' : mode_all = GPIOH->MODER; break;
#elif defined(PI_0)
case 'I' : mode_all = GPIOI->MODER; break;
#elif defined(PJ_0)
case 'J' : mode_all = GPIOJ->MODER; break;
#elif defined(PK_0)
case 'K' : mode_all = GPIOK->MODER; break;
#elif defined(PL_0)
case 'L' : mode_all = GPIOL->MODER; break;
#endif
}
return (mode_all >> (2 * uint8_t(PIN_NUM(dp)))) & 0x03;
}
bool GET_PINMODE(const pin_t Ard_num) {
const uint8_t pin_mode = get_pin_mode(Ard_num);
return pin_mode == MODE_PIN_OUTPUT || pin_mode == MODE_PIN_ALT; // assume all alt definitions are PWM
}
int8_t digital_pin_to_analog_pin(pin_t Ard_num) {
Ard_num -= NUM_ANALOG_FIRST;
return (Ard_num >= 0 && Ard_num < NUM_ANALOG_INPUTS) ? Ard_num : -1;
}
bool IS_ANALOG(const pin_t Ard_num) {
return get_pin_mode(Ard_num) == MODE_PIN_ANALOG;
}
bool is_digital(const pin_t x) {
const uint8_t pin_mode = get_pin_mode(pin_array[x].pin);
return pin_mode == MODE_PIN_INPUT || pin_mode == MODE_PIN_OUTPUT;
}
void port_print(const pin_t Ard_num) {
char buffer[16];
pin_t Index;
for (Index = 0; Index < NUMBER_PINS_TOTAL; Index++)
if (Ard_num == GET_PIN_MAP_PIN_M43(Index)) break;
const char * ppa = pin_xref[Index].Port_pin_alpha;
sprintf_P(buffer, PSTR("%s"), ppa);
SERIAL_ECHO(buffer);
if (ppa[3] == '\0') SERIAL_CHAR(' ');
// print analog pin number
const int8_t Port_pin = digital_pin_to_analog_pin(Ard_num);
if (Port_pin >= 0) {
sprintf_P(buffer, PSTR(" (A%d) "), Port_pin);
SERIAL_ECHO(buffer);
if (Port_pin < 10) SERIAL_CHAR(' ');
}
else
SERIAL_ECHO_SP(7);
// Print number to be used with M42
sprintf_P(buffer, PSTR(" M42 P%d "), Ard_num);
SERIAL_ECHO(buffer);
if (Ard_num < 10) SERIAL_CHAR(' ');
if (Ard_num < 100) SERIAL_CHAR(' ');
}
bool pwm_status(const pin_t Ard_num) {
return get_pin_mode(Ard_num) == MODE_PIN_ALT;
}
void pwm_details(const pin_t Ard_num) {
if (pwm_status(Ard_num)) {
uint32_t alt_all = 0;
const PinName dp = digitalPin[Ard_num];
pin_t pin_number = uint8_t(PIN_NUM(dp));
const bool over_7 = pin_number >= 8;
const uint8_t ind = over_7 ? 1 : 0;
switch (PORT_ALPHA(dp)) { // get alt function
case 'A' : alt_all = GPIOA->AFR[ind]; break;
case 'B' : alt_all = GPIOB->AFR[ind]; break;
case 'C' : alt_all = GPIOC->AFR[ind]; break;
case 'D' : alt_all = GPIOD->AFR[ind]; break;
#ifdef PE_0
case 'E' : alt_all = GPIOE->AFR[ind]; break;
#elif defined (PF_0)
case 'F' : alt_all = GPIOF->AFR[ind]; break;
#elif defined (PG_0)
case 'G' : alt_all = GPIOG->AFR[ind]; break;
#elif defined (PH_0)
case 'H' : alt_all = GPIOH->AFR[ind]; break;
#elif defined (PI_0)
case 'I' : alt_all = GPIOI->AFR[ind]; break;
#elif defined (PJ_0)
case 'J' : alt_all = GPIOJ->AFR[ind]; break;
#elif defined (PK_0)
case 'K' : alt_all = GPIOK->AFR[ind]; break;
#elif defined (PL_0)
case 'L' : alt_all = GPIOL->AFR[ind]; break;
#endif
}
if (over_7) pin_number -= 8;
uint8_t alt_func = (alt_all >> (4 * pin_number)) & 0x0F;
SERIAL_ECHOPAIR("Alt Function: ", alt_func);
if (alt_func < 10) SERIAL_CHAR(' ');
SERIAL_ECHOPGM(" - ");
switch (alt_func) {
case 0 : SERIAL_ECHOPGM("system (misc. I/O)"); break;
case 1 : SERIAL_ECHOPGM("TIM1/TIM2 (probably PWM)"); break;
case 2 : SERIAL_ECHOPGM("TIM3..5 (probably PWM)"); break;
case 3 : SERIAL_ECHOPGM("TIM8..11 (probably PWM)"); break;
case 4 : SERIAL_ECHOPGM("I2C1..3"); break;
case 5 : SERIAL_ECHOPGM("SPI1/SPI2"); break;
case 6 : SERIAL_ECHOPGM("SPI3"); break;
case 7 : SERIAL_ECHOPGM("USART1..3"); break;
case 8 : SERIAL_ECHOPGM("USART4..6"); break;
case 9 : SERIAL_ECHOPGM("CAN1/CAN2, TIM12..14 (probably PWM)"); break;
case 10 : SERIAL_ECHOPGM("OTG"); break;
case 11 : SERIAL_ECHOPGM("ETH"); break;
case 12 : SERIAL_ECHOPGM("FSMC, SDIO, OTG"); break;
case 13 : SERIAL_ECHOPGM("DCMI"); break;
case 14 : SERIAL_ECHOPGM("unused (shouldn't see this)"); break;
case 15 : SERIAL_ECHOPGM("EVENTOUT"); break;
}
}
} // pwm_details
#endif // NUM_DIGITAL_PINS

View File

@ -0,0 +1,612 @@
/**
* 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/>.
*
*/
//
// make a list of the Arduino pin numbers in the Port/Pin order
//
#ifdef PA0
PIN_ADD(PA0)
#endif
#ifdef PA1
PIN_ADD(PA1)
#endif
#ifdef PA2
PIN_ADD(PA2)
#endif
#ifdef PA3
PIN_ADD(PA3)
#endif
#ifdef PA4
PIN_ADD(PA4)
#endif
#ifdef PA5
PIN_ADD(PA5)
#endif
#ifdef PA6
PIN_ADD(PA6)
#endif
#ifdef PA7
PIN_ADD(PA7)
#endif
#ifdef PA8
PIN_ADD(PA8)
#endif
#ifdef PA9
PIN_ADD(PA9)
#endif
#ifdef PA10
PIN_ADD(PA10)
#endif
#ifdef PA11
PIN_ADD(PA11)
#endif
#ifdef PA12
PIN_ADD(PA12)
#endif
#ifdef PA13
PIN_ADD(PA13)
#endif
#ifdef PA14
PIN_ADD(PA14)
#endif
#ifdef PA15
PIN_ADD(PA15)
#endif
#ifdef PB0
PIN_ADD(PB0)
#endif
#ifdef PB1
PIN_ADD(PB1)
#endif
#ifdef PB2
PIN_ADD(PB2)
#endif
#ifdef PB3
PIN_ADD(PB3)
#endif
#ifdef PB4
PIN_ADD(PB4)
#endif
#ifdef PB5
PIN_ADD(PB5)
#endif
#ifdef PB6
PIN_ADD(PB6)
#endif
#ifdef PB7
PIN_ADD(PB7)
#endif
#ifdef PB8
PIN_ADD(PB8)
#endif
#ifdef PB9
PIN_ADD(PB9)
#endif
#ifdef PB10
PIN_ADD(PB10)
#endif
#ifdef PB11
PIN_ADD(PB11)
#endif
#ifdef PB12
PIN_ADD(PB12)
#endif
#ifdef PB13
PIN_ADD(PB13)
#endif
#ifdef PB14
PIN_ADD(PB14)
#endif
#ifdef PB15
PIN_ADD(PB15)
#endif
#ifdef PC0
PIN_ADD(PC0)
#endif
#ifdef PC1
PIN_ADD(PC1)
#endif
#ifdef PC2
PIN_ADD(PC2)
#endif
#ifdef PC3
PIN_ADD(PC3)
#endif
#ifdef PC4
PIN_ADD(PC4)
#endif
#ifdef PC5
PIN_ADD(PC5)
#endif
#ifdef PC6
PIN_ADD(PC6)
#endif
#ifdef PC7
PIN_ADD(PC7)
#endif
#ifdef PC8
PIN_ADD(PC8)
#endif
#ifdef PC9
PIN_ADD(PC9)
#endif
#ifdef PC10
PIN_ADD(PC10)
#endif
#ifdef PC11
PIN_ADD(PC11)
#endif
#ifdef PC12
PIN_ADD(PC12)
#endif
#ifdef PC13
PIN_ADD(PC13)
#endif
#ifdef PC14
PIN_ADD(PC14)
#endif
#ifdef PC15
PIN_ADD(PC15)
#endif
#ifdef PD0
PIN_ADD(PD0)
#endif
#ifdef PD1
PIN_ADD(PD1)
#endif
#ifdef PD2
PIN_ADD(PD2)
#endif
#ifdef PD3
PIN_ADD(PD3)
#endif
#ifdef PD4
PIN_ADD(PD4)
#endif
#ifdef PD5
PIN_ADD(PD5)
#endif
#ifdef PD6
PIN_ADD(PD6)
#endif
#ifdef PD7
PIN_ADD(PD7)
#endif
#ifdef PD8
PIN_ADD(PD8)
#endif
#ifdef PD9
PIN_ADD(PD9)
#endif
#ifdef PD10
PIN_ADD(PD10)
#endif
#ifdef PD11
PIN_ADD(PD11)
#endif
#ifdef PD12
PIN_ADD(PD12)
#endif
#ifdef PD13
PIN_ADD(PD13)
#endif
#ifdef PD14
PIN_ADD(PD14)
#endif
#ifdef PD15
PIN_ADD(PD15)
#endif
#ifdef PE0
PIN_ADD(PE0)
#endif
#ifdef PE1
PIN_ADD(PE1)
#endif
#ifdef PE2
PIN_ADD(PE2)
#endif
#ifdef PE3
PIN_ADD(PE3)
#endif
#ifdef PE4
PIN_ADD(PE4)
#endif
#ifdef PE5
PIN_ADD(PE5)
#endif
#ifdef PE6
PIN_ADD(PE6)
#endif
#ifdef PE7
PIN_ADD(PE7)
#endif
#ifdef PE8
PIN_ADD(PE8)
#endif
#ifdef PE9
PIN_ADD(PE9)
#endif
#ifdef PE10
PIN_ADD(PE10)
#endif
#ifdef PE11
PIN_ADD(PE11)
#endif
#ifdef PE12
PIN_ADD(PE12)
#endif
#ifdef PE13
PIN_ADD(PE13)
#endif
#ifdef PE14
PIN_ADD(PE14)
#endif
#ifdef PE15
PIN_ADD(PE15)
#endif
#ifdef PF0
PIN_ADD(PF0)
#endif
#ifdef PF1
PIN_ADD(PF1)
#endif
#ifdef PF2
PIN_ADD(PF2)
#endif
#ifdef PF3
PIN_ADD(PF3)
#endif
#ifdef PF4
PIN_ADD(PF4)
#endif
#ifdef PF5
PIN_ADD(PF5)
#endif
#ifdef PF6
PIN_ADD(PF6)
#endif
#ifdef PF7
PIN_ADD(PF7)
#endif
#ifdef PF8
PIN_ADD(PF8)
#endif
#ifdef PF9
PIN_ADD(PF9)
#endif
#ifdef PF10
PIN_ADD(PF10)
#endif
#ifdef PF11
PIN_ADD(PF11)
#endif
#ifdef PF12
PIN_ADD(PF12)
#endif
#ifdef PF13
PIN_ADD(PF13)
#endif
#ifdef PF14
PIN_ADD(PF14)
#endif
#ifdef PF15
PIN_ADD(PF15)
#endif
#ifdef PG0
PIN_ADD(PG0)
#endif
#ifdef PG1
PIN_ADD(PG1)
#endif
#ifdef PG2
PIN_ADD(PG2)
#endif
#ifdef PG3
PIN_ADD(PG3)
#endif
#ifdef PG4
PIN_ADD(PG4)
#endif
#ifdef PG5
PIN_ADD(PG5)
#endif
#ifdef PG6
PIN_ADD(PG6)
#endif
#ifdef PG7
PIN_ADD(PG7)
#endif
#ifdef PG8
PIN_ADD(PG8)
#endif
#ifdef PG9
PIN_ADD(PG9)
#endif
#ifdef PG10
PIN_ADD(PG10)
#endif
#ifdef PG11
PIN_ADD(PG11)
#endif
#ifdef PG12
PIN_ADD(PG12)
#endif
#ifdef PG13
PIN_ADD(PG13)
#endif
#ifdef PG14
PIN_ADD(PG14)
#endif
#ifdef PG15
PIN_ADD(PG15)
#endif
#ifdef PH0
PIN_ADD(PH0)
#endif
#ifdef PH1
PIN_ADD(PH1)
#endif
#ifdef PH2
PIN_ADD(PH2)
#endif
#ifdef PH3
PIN_ADD(PH3)
#endif
#ifdef PH4
PIN_ADD(PH4)
#endif
#ifdef PH5
PIN_ADD(PH5)
#endif
#ifdef PH6
PIN_ADD(PH6)
#endif
#ifdef PH7
PIN_ADD(PH7)
#endif
#ifdef PH8
PIN_ADD(PH8)
#endif
#ifdef PH9
PIN_ADD(PH9)
#endif
#ifdef PH10
PIN_ADD(PH10)
#endif
#ifdef PH11
PIN_ADD(PH11)
#endif
#ifdef PH12
PIN_ADD(PH12)
#endif
#ifdef PH13
PIN_ADD(PH13)
#endif
#ifdef PH14
PIN_ADD(PH14)
#endif
#ifdef PH15
PIN_ADD(PH15)
#endif
#ifdef PI0
PIN_ADD(PI0)
#endif
#ifdef PI1
PIN_ADD(PI1)
#endif
#ifdef PI2
PIN_ADD(PI2)
#endif
#ifdef PI3
PIN_ADD(PI3)
#endif
#ifdef PI4
PIN_ADD(PI4)
#endif
#ifdef PI5
PIN_ADD(PI5)
#endif
#ifdef PI6
PIN_ADD(PI6)
#endif
#ifdef PI7
PIN_ADD(PI7)
#endif
#ifdef PI8
PIN_ADD(PI8)
#endif
#ifdef PI9
PIN_ADD(PI9)
#endif
#ifdef PI10
PIN_ADD(PI10)
#endif
#ifdef PI11
PIN_ADD(PI11)
#endif
#ifdef PI12
PIN_ADD(PI12)
#endif
#ifdef PI13
PIN_ADD(PI13)
#endif
#ifdef PI14
PIN_ADD(PI14)
#endif
#ifdef PI15
PIN_ADD(PI15)
#endif
#ifdef PJ0
PIN_ADD(PJ0)
#endif
#ifdef PJ1
PIN_ADD(PJ1)
#endif
#ifdef PJ2
PIN_ADD(PJ2)
#endif
#ifdef PJ3
PIN_ADD(PJ3)
#endif
#ifdef PJ4
PIN_ADD(PJ4)
#endif
#ifdef PJ5
PIN_ADD(PJ5)
#endif
#ifdef PJ6
PIN_ADD(PJ6)
#endif
#ifdef PJ7
PIN_ADD(PJ7)
#endif
#ifdef PJ8
PIN_ADD(PJ8)
#endif
#ifdef PJ9
PIN_ADD(PJ9)
#endif
#ifdef PJ10
PIN_ADD(PJ10)
#endif
#ifdef PJ11
PIN_ADD(PJ11)
#endif
#ifdef PJ12
PIN_ADD(PJ12)
#endif
#ifdef PJ13
PIN_ADD(PJ13)
#endif
#ifdef PJ14
PIN_ADD(PJ14)
#endif
#ifdef PJ15
PIN_ADD(PJ15)
#endif
#ifdef PK0
PIN_ADD(PK0)
#endif
#ifdef PK1
PIN_ADD(PK1)
#endif
#ifdef PK2
PIN_ADD(PK2)
#endif
#ifdef PK3
PIN_ADD(PK3)
#endif
#ifdef PK4
PIN_ADD(PK4)
#endif
#ifdef PK5
PIN_ADD(PK5)
#endif
#ifdef PK6
PIN_ADD(PK6)
#endif
#ifdef PK7
PIN_ADD(PK7)
#endif
#ifdef PK8
PIN_ADD(PK8)
#endif
#ifdef PK9
PIN_ADD(PK9)
#endif
#ifdef PK10
PIN_ADD(PK10)
#endif
#ifdef PK11
PIN_ADD(PK11)
#endif
#ifdef PK12
PIN_ADD(PK12)
#endif
#ifdef PK13
PIN_ADD(PK13)
#endif
#ifdef PK14
PIN_ADD(PK14)
#endif
#ifdef PK15
PIN_ADD(PK15)
#endif
#ifdef PL0
PIN_ADD(PL0)
#endif
#ifdef PL1
PIN_ADD(PL1)
#endif
#ifdef PL2
PIN_ADD(PL2)
#endif
#ifdef PL3
PIN_ADD(PL3)
#endif
#ifdef PL4
PIN_ADD(PL4)
#endif
#ifdef PL5
PIN_ADD(PL5)
#endif
#ifdef PL6
PIN_ADD(PL6)
#endif
#ifdef PL7
PIN_ADD(PL7)
#endif
#ifdef PL8
PIN_ADD(PL8)
#endif
#ifdef PL9
PIN_ADD(PL9)
#endif
#ifdef PL10
PIN_ADD(PL10)
#endif
#ifdef PL11
PIN_ADD(PL11)
#endif
#ifdef PL12
PIN_ADD(PL12)
#endif
#ifdef PL13
PIN_ADD(PL13)
#endif
#ifdef PL14
PIN_ADD(PL14)
#endif
#ifdef PL15
PIN_ADD(PL15)
#endif

View File

@ -0,0 +1,35 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* 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
/**
* Define SPI Pins: SCK, MISO, MOSI, SS
*/
#ifndef SCK_PIN
#define SCK_PIN PIN_SPI_SCK
#endif
#ifndef MISO_PIN
#define MISO_PIN PIN_SPI_MISO
#endif
#ifndef MOSI_PIN
#define MOSI_PIN PIN_SPI_MOSI
#endif
#ifndef SS_PIN
#define SS_PIN PIN_SPI_SS
#endif

View File

@ -0,0 +1,139 @@
/**
* Marlin 3D Printer Firmware
*
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
* Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
*
* 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/>.
*
*/
#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
#include "HAL.h"
#include "timers.h"
// ------------------------
// Local defines
// ------------------------
#define NUM_HARDWARE_TIMERS 2
#define __TIMER_DEV(X) TIM##X
#define _TIMER_DEV(X) __TIMER_DEV(X)
#define STEP_TIMER_DEV _TIMER_DEV(STEP_TIMER)
#define TEMP_TIMER_DEV _TIMER_DEV(TEMP_TIMER)
// ------------------------
// Private Variables
// ------------------------
HardwareTimer *timer_instance[NUM_HARDWARE_TIMERS] = { NULL };
bool timer_enabled[NUM_HARDWARE_TIMERS] = { false };
// ------------------------
// Public functions
// ------------------------
// frequency is in Hertz
void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
if (!HAL_timer_initialized(timer_num)) {
switch (timer_num) {
case STEP_TIMER_NUM: // STEPPER TIMER - use a 32bit timer if possible
timer_instance[timer_num] = new HardwareTimer(STEP_TIMER_DEV);
/* Set the prescaler to the final desired value.
* This will change the effective ISR callback frequency but when
* HAL_timer_start(timer_num=0) is called in the core for the first time
* the real frequency isn't important as long as, after boot, the ISR
* gets called with the correct prescaler and count register. So here
* we set the prescaler to the correct, final value and ignore the frequency
* asked. We will call back the ISR in 1 second to start at full speed.
*
* The proper fix, however, would be a correct initialization OR a
* HAL_timer_change(const uint8_t timer_num, const uint32_t frequency)
* which changes the prescaler when an IRQ frequency change is needed
* (for example when steppers are turned on)
*/
timer_instance[timer_num]->setPrescaleFactor(STEPPER_TIMER_PRESCALE); //the -1 is done internally
timer_instance[timer_num]->setOverflow(_MIN(hal_timer_t(HAL_TIMER_TYPE_MAX), (HAL_TIMER_RATE) / (STEPPER_TIMER_PRESCALE) /* /frequency */), TICK_FORMAT);
break;
case TEMP_TIMER_NUM: // TEMP TIMER - any available 16bit timer
timer_instance[timer_num] = new HardwareTimer(TEMP_TIMER_DEV);
// The prescale factor is computed automatically for HERTZ_FORMAT
timer_instance[timer_num]->setOverflow(frequency, HERTZ_FORMAT);
break;
}
HAL_timer_enable_interrupt(timer_num);
/*
* Initializes (and unfortunately starts) the timer.
* This is needed to set correct IRQ priority at the moment but causes
* no harm since every call to HAL_timer_start() is actually followed by
* a call to HAL_timer_enable_interrupt() which means that there isn't
* a case in which you want the timer to run without a callback.
*/
timer_instance[timer_num]->resume(); // First call to resume() MUST follow the attachInterrupt()
// This is fixed in Arduino_Core_STM32 1.8.
// These calls can be removed and replaced with
// timer_instance[timer_num]->setInterruptPriority
switch (timer_num) {
case STEP_TIMER_NUM:
HAL_NVIC_SetPriority(STEP_TIMER_IRQ_NAME, STEP_TIMER_IRQ_PRIO, 0);
break;
case TEMP_TIMER_NUM:
HAL_NVIC_SetPriority(TEMP_TIMER_IRQ_NAME, TEMP_TIMER_IRQ_PRIO, 0);
break;
}
}
}
void HAL_timer_enable_interrupt(const uint8_t timer_num) {
if (HAL_timer_initialized(timer_num) && !timer_enabled[timer_num]) {
timer_enabled[timer_num] = true;
switch (timer_num) {
case STEP_TIMER_NUM:
timer_instance[timer_num]->attachInterrupt(Step_Handler);
break;
case TEMP_TIMER_NUM:
timer_instance[timer_num]->attachInterrupt(Temp_Handler);
break;
}
}
}
void HAL_timer_disable_interrupt(const uint8_t timer_num) {
if (HAL_timer_interrupt_enabled(timer_num)) {
timer_instance[timer_num]->detachInterrupt();
timer_enabled[timer_num] = false;
}
}
bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
return HAL_timer_initialized(timer_num) && timer_enabled[timer_num];
}
// Only for use within the HAL
TIM_TypeDef * HAL_timer_device(const uint8_t timer_num) {
switch (timer_num) {
case STEP_TIMER_NUM: return STEP_TIMER_DEV;
case TEMP_TIMER_NUM: return TEMP_TIMER_DEV;
}
return nullptr;
}
#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC

View File

@ -0,0 +1,181 @@
/**
* Marlin 3D Printer Firmware
*
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
* Copyright (c) 2017 Victor Perez
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
#include <stdint.h>
#include "../../inc/MarlinConfig.h"
// ------------------------
// Defines
// ------------------------
#define FORCE_INLINE __attribute__((always_inline)) inline
#define hal_timer_t uint32_t
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFF // Timers can be 16 or 32 bit
#ifdef STM32F0xx
#define HAL_TIMER_RATE (F_CPU) // frequency of timer peripherals
#ifndef STEP_TIMER
#define STEP_TIMER 16
#endif
#ifndef TEMP_TIMER
#define TEMP_TIMER 17
#endif
#elif defined(STM32F1xx)
#define HAL_TIMER_RATE (F_CPU) // frequency of timer peripherals
#ifndef STEP_TIMER
#define STEP_TIMER 4
#endif
#ifndef TEMP_TIMER
#define TEMP_TIMER 2
#endif
#elif defined(STM32F401xC) || defined(STM32F401xE)
#define HAL_TIMER_RATE (F_CPU / 2) // frequency of timer peripherals
#ifndef STEP_TIMER
#define STEP_TIMER 9
#endif
#ifndef TEMP_TIMER
#define TEMP_TIMER 10
#endif
#elif defined(STM32F4xx)
#define HAL_TIMER_RATE (F_CPU / 2) // frequency of timer peripherals
#ifndef STEP_TIMER
#define STEP_TIMER 6 // STM32F401 has no TIM6, TIM7, or TIM8
#endif
#ifndef TEMP_TIMER
#define TEMP_TIMER 14 // TIM7 is consumed by Software Serial if used.
#endif
#elif defined(STM32F7xx)
#define HAL_TIMER_RATE (F_CPU / 2) // frequency of timer peripherals
#ifndef STEP_TIMER
#define STEP_TIMER 6 // the RIGHT timer!
#endif
#ifndef TEMP_TIMER
#define TEMP_TIMER 14
#endif
#endif
#ifndef SWSERIAL_TIMER_IRQ_PRIO
#define SWSERIAL_TIMER_IRQ_PRIO 1
#endif
#ifndef STEP_TIMER_IRQ_PRIO
#define STEP_TIMER_IRQ_PRIO 2
#endif
#ifndef TEMP_TIMER_IRQ_PRIO
#define TEMP_TIMER_IRQ_PRIO 14 // 14 = after hardware ISRs
#endif
#define STEP_TIMER_NUM 0 // index of timer to use for stepper
#define TEMP_TIMER_NUM 1 // index of timer to use for temperature
#define PULSE_TIMER_NUM STEP_TIMER_NUM
#define TEMP_TIMER_FREQUENCY 1000 // Temperature::isr() is expected to be called at around 1kHz
// TODO: get rid of manual rate/prescale/ticks/cycles taken for procedures in stepper.cpp
#define STEPPER_TIMER_RATE 2000000 // 2 Mhz
#define STEPPER_TIMER_PRESCALE ((HAL_TIMER_RATE)/(STEPPER_TIMER_RATE))
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
#define __TIMER_IRQ_NAME(X) TIM##X##_IRQn
#define _TIMER_IRQ_NAME(X) __TIMER_IRQ_NAME(X)
#define STEP_TIMER_IRQ_NAME _TIMER_IRQ_NAME(STEP_TIMER)
#define TEMP_TIMER_IRQ_NAME _TIMER_IRQ_NAME(TEMP_TIMER)
#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM)
#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(STEP_TIMER_NUM)
#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM)
#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM)
#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM)
extern void Step_Handler(HardwareTimer *htim);
extern void Temp_Handler(HardwareTimer *htim);
#define HAL_STEP_TIMER_ISR() void Step_Handler(HardwareTimer *htim)
#define HAL_TEMP_TIMER_ISR() void Temp_Handler(HardwareTimer *htim)
// ------------------------
// Public Variables
// ------------------------
extern HardwareTimer *timer_instance[];
// ------------------------
// Public functions
// ------------------------
void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency);
void HAL_timer_enable_interrupt(const uint8_t timer_num);
void HAL_timer_disable_interrupt(const uint8_t timer_num);
bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
//TIM_TypeDef* HAL_timer_device(const uint8_t timer_num); no need to be public for now. not public = not used externally
// FORCE_INLINE because these are used in performance-critical situations
FORCE_INLINE bool HAL_timer_initialized(const uint8_t timer_num) {
return timer_instance[timer_num] != NULL;
}
FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) {
return HAL_timer_initialized(timer_num) ? timer_instance[timer_num]->getCount() : 0;
}
// NOTE: Method name may be misleading.
// STM32 has an Auto-Reload Register (ARR) as opposed to a "compare" register
FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t overflow) {
if (HAL_timer_initialized(timer_num)) {
timer_instance[timer_num]->setOverflow(overflow + 1, TICK_FORMAT); // Value decremented by setOverflow()
// wiki: "force all registers (Autoreload, prescaler, compare) to be taken into account"
// So, if the new overflow value is less than the count it will trigger a rollover interrupt.
if (overflow < timer_instance[timer_num]->getCount()) // Added 'if' here because reports say it won't boot without it
timer_instance[timer_num]->refresh();
}
}
#define HAL_timer_isr_prologue(TIMER_NUM)
#define HAL_timer_isr_epilogue(TIMER_NUM)

View File

@ -0,0 +1,44 @@
/**
* 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/>.
*
*/
#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
#include "../../inc/MarlinConfigPre.h"
#if ENABLED(USE_WATCHDOG)
#include "../../inc/MarlinConfig.h"
#include "watchdog.h"
#include <IWatchdog.h>
void watchdog_init() { IWatchdog.begin(4000000); } // 4 sec timeout
void HAL_watchdog_refresh() {
IWatchdog.reload();
#if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED)
TOGGLE(LED_PIN); // heartbeat indicator
#endif
}
#endif // USE_WATCHDOG
#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC

View File

@ -0,0 +1,25 @@
/**
* 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
void watchdog_init();
void HAL_watchdog_refresh();