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,393 @@
/**
* 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/>.
*
*/
/**
* HAL for stm32duino.com based on Libmaple and compatible (STM32F1)
*/
#ifdef __STM32F1__
#include "../../inc/MarlinConfig.h"
#include "HAL.h"
#include <STM32ADC.h>
// ------------------------
// Types
// ------------------------
#define __I
#define __IO volatile
typedef struct {
__I uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */
__IO uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */
__IO uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */
__IO uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */
__IO uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */
__IO uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */
__IO uint8_t SHP[12]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */
__IO uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */
__IO uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */
__IO uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */
__IO uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */
__IO uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */
__IO uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */
__IO uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */
__I uint32_t PFR[2]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */
__I uint32_t DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */
__I uint32_t ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */
__I uint32_t MMFR[4]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */
__I uint32_t ISAR[5]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */
uint32_t RESERVED0[5];
__IO uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */
} SCB_Type;
// ------------------------
// Local defines
// ------------------------
#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */
#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */
#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */
/* SCB Application Interrupt and Reset Control Register Definitions */
#define SCB_AIRCR_VECTKEY_Pos 16 /*!< SCB AIRCR: VECTKEY Position */
#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */
#define SCB_AIRCR_PRIGROUP_Pos 8 /*!< SCB AIRCR: PRIGROUP Position */
#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */
// ------------------------
// Public Variables
// ------------------------
#if (defined(SERIAL_USB) && !defined(USE_USB_COMPOSITE))
USBSerial SerialUSB;
#endif
uint16_t HAL_adc_result;
// ------------------------
// Private Variables
// ------------------------
STM32ADC adc(ADC1);
const uint8_t adc_pins[] = {
#if HAS_TEMP_ADC_0
TEMP_0_PIN,
#endif
#if HAS_HEATED_BED
TEMP_BED_PIN,
#endif
#if HAS_HEATED_CHAMBER
TEMP_CHAMBER_PIN,
#endif
#if HAS_TEMP_ADC_1
TEMP_1_PIN,
#endif
#if HAS_TEMP_ADC_2
TEMP_2_PIN,
#endif
#if HAS_TEMP_ADC_3
TEMP_3_PIN,
#endif
#if HAS_TEMP_ADC_4
TEMP_4_PIN,
#endif
#if HAS_TEMP_ADC_5
TEMP_5_PIN,
#endif
#if HAS_TEMP_ADC_6
TEMP_6_PIN,
#endif
#if HAS_TEMP_ADC_7
TEMP_7_PIN,
#endif
#if ENABLED(FILAMENT_WIDTH_SENSOR)
FILWIDTH_PIN,
#endif
#if ENABLED(ADC_KEYPAD)
ADC_KEYPAD_PIN,
#endif
#if HAS_JOY_ADC_X
JOY_X_PIN,
#endif
#if HAS_JOY_ADC_Y
JOY_Y_PIN,
#endif
#if HAS_JOY_ADC_Z
JOY_Z_PIN,
#endif
};
enum TEMP_PINS : char {
#if HAS_TEMP_ADC_0
TEMP_0,
#endif
#if HAS_HEATED_BED
TEMP_BED,
#endif
#if HAS_HEATED_CHAMBER
TEMP_CHAMBER,
#endif
#if HAS_TEMP_ADC_1
TEMP_1,
#endif
#if HAS_TEMP_ADC_2
TEMP_2,
#endif
#if HAS_TEMP_ADC_3
TEMP_3,
#endif
#if HAS_TEMP_ADC_4
TEMP_4,
#endif
#if HAS_TEMP_ADC_5
TEMP_5,
#endif
#if HAS_TEMP_ADC_6
TEMP_6,
#endif
#if HAS_TEMP_ADC_7
TEMP_7,
#endif
#if ENABLED(FILAMENT_WIDTH_SENSOR)
FILWIDTH,
#endif
#if ENABLED(ADC_KEYPAD)
ADC_KEY,
#endif
#if HAS_JOY_ADC_X
JOY_X,
#endif
#if HAS_JOY_ADC_Y
JOY_Y,
#endif
#if HAS_JOY_ADC_Z
JOY_Z,
#endif
ADC_PIN_COUNT
};
uint16_t HAL_adc_results[ADC_PIN_COUNT];
// ------------------------
// Private functions
// ------------------------
static void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) {
uint32_t reg_value;
uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07); /* only values 0..7 are used */
reg_value = SCB->AIRCR; /* read old register configuration */
reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk); /* clear bits to change */
reg_value = (reg_value |
((uint32_t)0x5FA << SCB_AIRCR_VECTKEY_Pos) |
(PriorityGroupTmp << 8)); /* Insert write key and priorty group */
SCB->AIRCR = reg_value;
}
// ------------------------
// Public functions
// ------------------------
//
// Leave PA11/PA12 intact if USBSerial is not used
//
#if SERIAL_USB
namespace wirish { namespace priv {
#if SERIAL_PORT > 0
#if SERIAL_PORT2
#if SERIAL_PORT2 > 0
void board_setup_usb() {}
#endif
#else
void board_setup_usb() {}
#endif
#endif
} }
#endif
void HAL_init() {
NVIC_SetPriorityGrouping(0x3);
#if PIN_EXISTS(LED)
OUT_WRITE(LED_PIN, LOW);
#endif
#ifdef USE_USB_COMPOSITE
MSC_SD_init();
#endif
#if PIN_EXISTS(USB_CONNECT)
OUT_WRITE(USB_CONNECT_PIN, !USB_CONNECT_INVERTING); // USB clear connection
delay(1000); // Give OS time to notice
OUT_WRITE(USB_CONNECT_PIN, USB_CONNECT_INVERTING);
#endif
}
// HAL idle task
void HAL_idletask() {
#ifdef USE_USB_COMPOSITE
#if ENABLED(SHARED_SD_CARD)
// If Marlin is using the SD card we need to lock it to prevent access from
// a PC via USB.
// Other HALs use IS_SD_PRINTING() and IS_SD_FILE_OPEN() to check for access but
// this will not reliably detect delete operations. To be safe we will lock
// the disk if Marlin has it mounted. Unfortunately there is currently no way
// to unmount the disk from the LCD menu.
// if (IS_SD_PRINTING() || IS_SD_FILE_OPEN())
/* copy from lpc1768 framework, should be fixed later for process SHARED_SD_CARD*/
#endif
// process USB mass storage device class loop
MarlinMSC.loop();
#endif
}
void HAL_clear_reset_source() { }
/**
* TODO: Check this and change or remove.
* currently returns 1 that's equal to poweron reset.
*/
uint8_t HAL_get_reset_source() { return 1; }
void _delay_ms(const int delay_ms) { delay(delay_ms); }
extern "C" {
extern unsigned int _ebss; // end of bss section
}
/**
* TODO: Change this to correct it for libmaple
*/
// return free memory between end of heap (or end bss) and whatever is current
/*
#include <wirish/syscalls.c>
//extern caddr_t _sbrk(int incr);
#ifndef CONFIG_HEAP_END
extern char _lm_heap_end;
#define CONFIG_HEAP_END ((caddr_t)&_lm_heap_end)
#endif
extern "C" {
static int freeMemory() {
char top = 't';
return &top - reinterpret_cast<char*>(sbrk(0));
}
int freeMemory() {
int free_memory;
int heap_end = (int)_sbrk(0);
free_memory = ((int)&free_memory) - ((int)heap_end);
return free_memory;
}
}
*/
// ------------------------
// ADC
// ------------------------
// Init the AD in continuous capture mode
void HAL_adc_init() {
// configure the ADC
adc.calibrate();
#if F_CPU > 72000000
adc.setSampleRate(ADC_SMPR_71_5); // 71.5 ADC cycles
#else
adc.setSampleRate(ADC_SMPR_41_5); // 41.5 ADC cycles
#endif
adc.setPins((uint8_t *)adc_pins, ADC_PIN_COUNT);
adc.setDMA(HAL_adc_results, (uint16_t)ADC_PIN_COUNT, (uint32_t)(DMA_MINC_MODE | DMA_CIRC_MODE), nullptr);
adc.setScanMode();
adc.setContinuous();
adc.startConversion();
}
void HAL_adc_start_conversion(const uint8_t adc_pin) {
TEMP_PINS pin_index;
switch (adc_pin) {
default: return;
#if HAS_TEMP_ADC_0
case TEMP_0_PIN: pin_index = TEMP_0; break;
#endif
#if HAS_HEATED_BED
case TEMP_BED_PIN: pin_index = TEMP_BED; break;
#endif
#if HAS_HEATED_CHAMBER
case TEMP_CHAMBER_PIN: pin_index = TEMP_CHAMBER; break;
#endif
#if HAS_TEMP_ADC_1
case TEMP_1_PIN: pin_index = TEMP_1; break;
#endif
#if HAS_TEMP_ADC_2
case TEMP_2_PIN: pin_index = TEMP_2; break;
#endif
#if HAS_TEMP_ADC_3
case TEMP_3_PIN: pin_index = TEMP_3; break;
#endif
#if HAS_TEMP_ADC_4
case TEMP_4_PIN: pin_index = TEMP_4; break;
#endif
#if HAS_TEMP_ADC_5
case TEMP_5_PIN: pin_index = TEMP_5; break;
#endif
#if HAS_TEMP_ADC_6
case TEMP_6_PIN: pin_index = TEMP_6; break;
#endif
#if HAS_TEMP_ADC_7
case TEMP_7_PIN: pin_index = TEMP_7; break;
#endif
#if HAS_JOY_ADC_X
case JOY_X_PIN: pin_index = JOY_X; break;
#endif
#if HAS_JOY_ADC_Y
case JOY_Y_PIN: pin_index = JOY_Y; break;
#endif
#if HAS_JOY_ADC_Z
case JOY_Z_PIN: pin_index = JOY_Z; break;
#endif
#if ENABLED(FILAMENT_WIDTH_SENSOR)
case FILWIDTH_PIN: pin_index = FILWIDTH; break;
#endif
#if ENABLED(ADC_KEYPAD)
case ADC_KEYPAD_PIN: pin_index = ADC_KEY; break;
#endif
}
HAL_adc_result = (HAL_adc_results[(int)pin_index] >> 2) & 0x3FF; // shift to get 10 bits only.
}
uint16_t HAL_adc_get_result() { return HAL_adc_result; }
uint16_t analogRead(pin_t pin) {
const bool is_analog = _GET_MODE(pin) == GPIO_INPUT_ANALOG;
return is_analog ? analogRead(uint8_t(pin)) : 0;
}
// Wrapper to maple unprotected analogWrite
void analogWrite(pin_t pin, int pwm_val8) {
if (PWM_PIN(pin))
analogWrite(uint8_t(pin), pwm_val8);
}
void flashFirmware(int16_t value) { nvic_sys_reset(); }
#endif // __STM32F1__

View File

@ -0,0 +1,290 @@
/**
* 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
/**
* HAL for stm32duino.com based on Libmaple and compatible (STM32F1)
*/
#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 "timers.h"
#include <stdint.h>
#include <util/atomic.h>
#include "../../inc/MarlinConfigPre.h"
#ifdef USE_USB_COMPOSITE
#include "msc_sd.h"
#endif
// ------------------------
// Defines
// ------------------------
#ifndef STM32_FLASH_SIZE
#ifdef MCU_STM32F103RE
#define STM32_FLASH_SIZE 512
#else
#define STM32_FLASH_SIZE 256
#endif
#endif
#ifdef SERIAL_USB
#ifndef USE_USB_COMPOSITE
#define UsbSerial Serial
#else
#define UsbSerial MarlinCompositeSerial
#endif
#define MSerial1 Serial1
#define MSerial2 Serial2
#define MSerial3 Serial3
#define MSerial4 Serial4
#define MSerial5 Serial5
#else
#define MSerial1 Serial
#define MSerial2 Serial1
#define MSerial3 Serial2
#define MSerial4 Serial3
#define MSerial5 Serial4
#endif
#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 UsbSerial
#elif SERIAL_PORT == 1
#define MYSERIAL0 MSerial1
#elif SERIAL_PORT == 2
#define MYSERIAL0 MSerial2
#elif SERIAL_PORT == 3
#define MYSERIAL0 MSerial3
#elif SERIAL_PORT == 4
#define MYSERIAL0 MSerial4
#elif SERIAL_PORT == 5
#define MYSERIAL0 MSerial5
#else
#error "SERIAL_PORT must be from -1 to 5. Please update your configuration."
#endif
#ifdef SERIAL_PORT_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 UsbSerial
#elif SERIAL_PORT_2 == 1
#define MYSERIAL1 MSerial1
#elif SERIAL_PORT_2 == 2
#define MYSERIAL1 MSerial2
#elif SERIAL_PORT_2 == 3
#define MYSERIAL1 MSerial3
#elif SERIAL_PORT_2 == 4
#define MYSERIAL1 MSerial4
#elif SERIAL_PORT_2 == 5
#define MYSERIAL1 MSerial5
#else
#error "SERIAL_PORT_2 must be from -1 to 5. Please update your configuration."
#endif
#define NUM_SERIAL 2
#else
#define NUM_SERIAL 1
#endif
#ifdef DGUS_SERIAL
#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 UsbSerial
#elif DGUS_SERIAL_PORT == 1
#define DGUS_SERIAL MSerial1
#elif DGUS_SERIAL_PORT == 2
#define DGUS_SERIAL MSerial2
#elif DGUS_SERIAL_PORT == 3
#define DGUS_SERIAL MSerial3
#elif DGUS_SERIAL_PORT == 4
#define DGUS_SERIAL MSerial4
#elif DGUS_SERIAL_PORT == 5
#define DGUS_SERIAL MSerial5
#else
#error "DGUS_SERIAL_PORT must be from -1 to 5. Please update your configuration."
#endif
#endif
// Set interrupt grouping for this MCU
void HAL_init();
#define HAL_IDLETASK 1
void HAL_idletask();
/**
* TODO: review this to return 1 for pins that are not analog input
*/
#ifndef analogInputToDigitalPin
#define analogInputToDigitalPin(p) (p)
#endif
#ifndef digitalPinHasPWM
#define digitalPinHasPWM(P) (PIN_MAP[P].timer_device != nullptr)
#endif
#define CRITICAL_SECTION_START() uint32_t primask = __get_primask(); (void)__iCliRetVal()
#define CRITICAL_SECTION_END() if (!primask) (void)__iSeiRetVal()
#define ISRS_ENABLED() (!__get_primask())
#define ENABLE_ISRS() ((void)__iSeiRetVal())
#define DISABLE_ISRS() ((void)__iCliRetVal())
// 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))
#define RST_POWER_ON 1
#define RST_EXTERNAL 2
#define RST_BROWN_OUT 4
#define RST_WATCHDOG 8
#define RST_JTAG 16
#define RST_SOFTWARE 32
#define RST_BACKUP 64
// ------------------------
// Types
// ------------------------
typedef int8_t pin_t;
// ------------------------
// Public Variables
// ------------------------
// Result of last ADC conversion
extern uint16_t HAL_adc_result;
// ------------------------
// Public functions
// ------------------------
// Disable interrupts
#define cli() noInterrupts()
// Enable interrupts
#define sei() interrupts()
// Memory related
#define __bss_end __bss_end__
// Clear reset reason
void HAL_clear_reset_source();
// Reset reason
uint8_t HAL_get_reset_source();
void _delay_ms(const int delay);
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-function"
/*
extern "C" {
int freeMemory();
}
*/
extern "C" char* _sbrk(int incr);
/*
static int freeMemory() {
volatile int top;
top = (int)((char*)&top - reinterpret_cast<char*>(_sbrk(0)));
return top;
}
*/
static int freeMemory() {
volatile char top;
return &top - reinterpret_cast<char*>(_sbrk(0));
}
#pragma GCC diagnostic pop
//
// EEPROM
//
/**
* TODO: Write all this EEPROM stuff. Can emulate EEPROM in flash as last resort.
* 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_ANALOG);
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();
uint16_t analogRead(pin_t pin); // need HAL_ANALOG_SELECT() first
void analogWrite(pin_t pin, int pwm_val8); // PWM only! mul by 257 in maple!?
#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 JTAG_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_SW_ONLY)
#define JTAGSWD_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_NONE)
#define PLATFORM_M997_SUPPORT
void flashFirmware(int16_t value);

View File

@ -0,0 +1,174 @@
/**
* 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/>.
*
*/
/**
* Software SPI functions originally from Arduino Sd2Card Library
* Copyright (c) 2009 by William Greiman
*/
/**
* Adapted to the STM32F1 HAL
*/
#ifdef __STM32F1__
#include "../../inc/MarlinConfig.h"
#include <SPI.h>
// ------------------------
// Public functions
// ------------------------
#if ENABLED(SOFTWARE_SPI)
// ------------------------
// Software SPI
// ------------------------
#error "Software SPI not supported for STM32F1. Use hardware SPI."
#else
// ------------------------
// Hardware SPI
// ------------------------
/**
* VGPV SPI speed start and F_CPU/2, by default 72/2 = 36Mhz
*/
/**
* @brief Begin SPI port setup
*
* @return Nothing
*
* @details Only configures SS pin since libmaple creates and initialize the SPI object
*/
void spiBegin() {
#if PIN_EXISTS(SS)
OUT_WRITE(SS_PIN, HIGH);
#endif
}
/**
* @brief Initialize SPI port to required speed rate and transfer mode (MSB, SPI MODE 0)
*
* @param spiRate Rate as declared in HAL.h (speed do not match AVR)
* @return Nothing
*
* @details
*/
void spiInit(uint8_t spiRate) {
/**
* STM32F1 APB2 = 72MHz, APB1 = 36MHz, max SPI speed of this MCU if 18Mhz
* STM32F1 has 3 SPI ports, SPI1 in APB2, SPI2/SPI3 in APB1
* so the minimum prescale of SPI1 is DIV4, SPI2/SPI3 is DIV2
*/
#if SPI_DEVICE == 1
#define SPI_CLOCK_MAX SPI_CLOCK_DIV4
#else
#define SPI_CLOCK_MAX SPI_CLOCK_DIV2
#endif
uint8_t clock;
switch (spiRate) {
case SPI_FULL_SPEED: clock = SPI_CLOCK_MAX ; break;
case SPI_HALF_SPEED: clock = SPI_CLOCK_DIV4 ; break;
case SPI_QUARTER_SPEED: clock = SPI_CLOCK_DIV8 ; break;
case SPI_EIGHTH_SPEED: clock = SPI_CLOCK_DIV16; break;
case SPI_SPEED_5: clock = SPI_CLOCK_DIV32; break;
case SPI_SPEED_6: clock = SPI_CLOCK_DIV64; break;
default: clock = SPI_CLOCK_DIV2; // Default from the SPI library
}
SPI.setModule(SPI_DEVICE);
SPI.begin();
SPI.setClockDivider(clock);
SPI.setBitOrder(MSBFIRST);
SPI.setDataMode(SPI_MODE0);
}
/**
* @brief Receive a single byte from the SPI port.
*
* @return Byte received
*
* @details
*/
uint8_t spiRec() {
uint8_t returnByte = SPI.transfer(ff);
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) {
SPI.dmaTransfer(0, const_cast<uint8_t*>(buf), nbyte);
}
/**
* @brief Send a single byte on SPI port
*
* @param b Byte to send
*
* @details
*/
void spiSend(uint8_t b) {
SPI.send(b);
}
/**
* @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) {
SPI.send(token);
SPI.dmaSend(const_cast<uint8_t*>(buf), 512);
}
#if ENABLED(SPI_EEPROM)
// Read single byte from specified SPI channel
uint8_t spiRec(uint32_t chan) { return SPI.transfer(ff); }
// Write single byte to specified SPI channel
void spiSend(uint32_t chan, byte b) { SPI.send(b); }
// Write buffer to specified SPI channel
void spiSend(uint32_t chan, const uint8_t* buf, size_t n) {
for (size_t p = 0; p < n; p++) spiSend(chan, buf[p]);
}
#endif // SPI_EEPROM
#endif // SOFTWARE_SPI
#endif // __STM32F1__

View File

@ -0,0 +1,11 @@
# STM32F1
This HAL is for STM32F103 boards used with [Arduino STM32](https://github.com/rogerclarkmelbourne/Arduino_STM32) framework.
Currently has been tested in Malyan M200 (103CBT6), SKRmini (103RCT6), Chitu 3d (103ZET6), and various 103VET6 boards.
### Main developers:
- Victorpv
- xC000005
- thisiskeithb
- tpruvot

View File

@ -0,0 +1,715 @@
/******************************************************************************
* The MIT License
*
* Copyright (c) 2010 Perry Hung.
*
* Permission is hereby granted, free of charge, to any person
* obtaining a copy of this software and associated documentation
* files (the "Software"), to deal in the Software without
* restriction, including without limitation the rights to use, copy,
* modify, merge, publish, distribute, sublicense, and/or sell copies
* of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be
* included in all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
* BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
* ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*****************************************************************************/
/**
* @author Marti Bolivar <mbolivar@leaflabs.com>
* @brief Wirish SPI implementation.
*/
#ifdef __STM32F1__
#include <SPI.h>
#include <libmaple/timer.h>
#include <libmaple/util.h>
#include <libmaple/rcc.h>
#include <boards.h>
#include <wirish.h>
/** Time in ms for DMA receive timeout */
#define DMA_TIMEOUT 100
#if CYCLES_PER_MICROSECOND != 72
#warning "Unexpected clock speed; SPI frequency calculation will be incorrect"
#endif
struct spi_pins { uint8_t nss, sck, miso, mosi; };
static const spi_pins* dev_to_spi_pins(spi_dev *dev);
static void configure_gpios(spi_dev *dev, bool as_master);
static spi_baud_rate determine_baud_rate(spi_dev *dev, uint32_t freq);
#if BOARD_NR_SPI >= 3 && !defined(STM32_HIGH_DENSITY)
#error "The SPI library is misconfigured: 3 SPI ports only available on high density STM32 devices"
#endif
static const spi_pins board_spi_pins[] __FLASH__ = {
#if BOARD_NR_SPI >= 1
{ BOARD_SPI1_NSS_PIN,
BOARD_SPI1_SCK_PIN,
BOARD_SPI1_MISO_PIN,
BOARD_SPI1_MOSI_PIN },
#endif
#if BOARD_NR_SPI >= 2
{ BOARD_SPI2_NSS_PIN,
BOARD_SPI2_SCK_PIN,
BOARD_SPI2_MISO_PIN,
BOARD_SPI2_MOSI_PIN },
#endif
#if BOARD_NR_SPI >= 3
{ BOARD_SPI3_NSS_PIN,
BOARD_SPI3_SCK_PIN,
BOARD_SPI3_MISO_PIN,
BOARD_SPI3_MOSI_PIN },
#endif
};
#if BOARD_NR_SPI >= 1
static void *_spi1_this;
#endif
#if BOARD_NR_SPI >= 2
static void *_spi2_this;
#endif
#if BOARD_NR_SPI >= 3
static void *_spi3_this;
#endif
/**
* Constructor
*/
SPIClass::SPIClass(uint32_t spi_num) {
_currentSetting = &_settings[spi_num - 1]; // SPI channels are called 1 2 and 3 but the array is zero indexed
switch (spi_num) {
#if BOARD_NR_SPI >= 1
case 1:
_currentSetting->spi_d = SPI1;
_spi1_this = (void*)this;
break;
#endif
#if BOARD_NR_SPI >= 2
case 2:
_currentSetting->spi_d = SPI2;
_spi2_this = (void*)this;
break;
#endif
#if BOARD_NR_SPI >= 3
case 3:
_currentSetting->spi_d = SPI3;
_spi3_this = (void*)this;
break;
#endif
default: ASSERT(0);
}
// Init things specific to each SPI device
// clock divider setup is a bit of hack, and needs to be improved at a later date.
#if BOARD_NR_SPI >= 1
_settings[0].spi_d = SPI1;
_settings[0].clockDivider = determine_baud_rate(_settings[0].spi_d, _settings[0].clock);
_settings[0].spiDmaDev = DMA1;
_settings[0].spiTxDmaChannel = DMA_CH3;
_settings[0].spiRxDmaChannel = DMA_CH2;
#endif
#if BOARD_NR_SPI >= 2
_settings[1].spi_d = SPI2;
_settings[1].clockDivider = determine_baud_rate(_settings[1].spi_d, _settings[1].clock);
_settings[1].spiDmaDev = DMA1;
_settings[1].spiTxDmaChannel = DMA_CH5;
_settings[1].spiRxDmaChannel = DMA_CH4;
#endif
#if BOARD_NR_SPI >= 3
_settings[2].spi_d = SPI3;
_settings[2].clockDivider = determine_baud_rate(_settings[2].spi_d, _settings[2].clock);
_settings[2].spiDmaDev = DMA2;
_settings[2].spiTxDmaChannel = DMA_CH2;
_settings[2].spiRxDmaChannel = DMA_CH1;
#endif
// added for DMA callbacks.
_currentSetting->state = SPI_STATE_IDLE;
}
/**
* Set up/tear down
*/
void SPIClass::updateSettings() {
uint32_t flags = ((_currentSetting->bitOrder == MSBFIRST ? SPI_FRAME_MSB : SPI_FRAME_LSB) | _currentSetting->dataSize | SPI_SW_SLAVE | SPI_SOFT_SS);
spi_master_enable(_currentSetting->spi_d, (spi_baud_rate)_currentSetting->clockDivider, (spi_mode)_currentSetting->dataMode, flags);
}
void SPIClass::begin() {
spi_init(_currentSetting->spi_d);
configure_gpios(_currentSetting->spi_d, 1);
updateSettings();
// added for DMA callbacks.
_currentSetting->state = SPI_STATE_READY;
}
void SPIClass::beginSlave() {
spi_init(_currentSetting->spi_d);
configure_gpios(_currentSetting->spi_d, 0);
uint32_t flags = ((_currentSetting->bitOrder == MSBFIRST ? SPI_FRAME_MSB : SPI_FRAME_LSB) | _currentSetting->dataSize);
spi_slave_enable(_currentSetting->spi_d, (spi_mode)_currentSetting->dataMode, flags);
// added for DMA callbacks.
_currentSetting->state = SPI_STATE_READY;
}
void SPIClass::end() {
if (!spi_is_enabled(_currentSetting->spi_d)) return;
// Follows RM0008's sequence for disabling a SPI in master/slave
// full duplex mode.
while (spi_is_rx_nonempty(_currentSetting->spi_d)) {
// FIXME [0.1.0] remove this once you have an interrupt based driver
volatile uint16_t rx __attribute__((unused)) = spi_rx_reg(_currentSetting->spi_d);
}
waitSpiTxEnd(_currentSetting->spi_d);
spi_peripheral_disable(_currentSetting->spi_d);
// added for DMA callbacks.
// Need to add unsetting the callbacks for the DMA channels.
_currentSetting->state = SPI_STATE_IDLE;
}
/* Roger Clark added 3 functions */
void SPIClass::setClockDivider(uint32_t clockDivider) {
_currentSetting->clockDivider = clockDivider;
uint32_t cr1 = _currentSetting->spi_d->regs->CR1 & ~(SPI_CR1_BR);
_currentSetting->spi_d->regs->CR1 = cr1 | (clockDivider & SPI_CR1_BR);
}
void SPIClass::setBitOrder(BitOrder bitOrder) {
_currentSetting->bitOrder = bitOrder;
uint32_t cr1 = _currentSetting->spi_d->regs->CR1 & ~(SPI_CR1_LSBFIRST);
if (bitOrder == LSBFIRST) cr1 |= SPI_CR1_LSBFIRST;
_currentSetting->spi_d->regs->CR1 = cr1;
}
/**
* Victor Perez. Added to test changing datasize from 8 to 16 bit modes on the fly.
* Input parameter should be SPI_CR1_DFF set to 0 or 1 on a 32bit word.
*/
void SPIClass::setDataSize(uint32_t datasize) {
_currentSetting->dataSize = datasize;
uint32_t cr1 = _currentSetting->spi_d->regs->CR1 & ~(SPI_CR1_DFF);
uint8_t en = spi_is_enabled(_currentSetting->spi_d);
spi_peripheral_disable(_currentSetting->spi_d);
_currentSetting->spi_d->regs->CR1 = cr1 | (datasize & SPI_CR1_DFF) | en;
}
void SPIClass::setDataMode(uint8_t dataMode) {
/**
* Notes:
* As far as we know the AVR numbers for dataMode match the numbers required by the STM32.
* From the AVR doc http://www.atmel.com/images/doc2585.pdf section 2.4
*
* SPI Mode CPOL CPHA Shift SCK-edge Capture SCK-edge
* 0 0 0 Falling Rising
* 1 0 1 Rising Falling
* 2 1 0 Rising Falling
* 3 1 1 Falling Rising
*
* On the STM32 it appears to be
*
* bit 1 - CPOL : Clock polarity
* (This bit should not be changed when communication is ongoing)
* 0 : CLK to 0 when idle
* 1 : CLK to 1 when idle
*
* bit 0 - CPHA : Clock phase
* (This bit should not be changed when communication is ongoing)
* 0 : The first clock transition is the first data capture edge
* 1 : The second clock transition is the first data capture edge
*
* If someone finds this is not the case or sees a logic error with this let me know ;-)
*/
_currentSetting->dataMode = dataMode;
uint32_t cr1 = _currentSetting->spi_d->regs->CR1 & ~(SPI_CR1_CPOL|SPI_CR1_CPHA);
_currentSetting->spi_d->regs->CR1 = cr1 | (dataMode & (SPI_CR1_CPOL|SPI_CR1_CPHA));
}
void SPIClass::beginTransaction(uint8_t pin, SPISettings settings) {
setBitOrder(settings.bitOrder);
setDataMode(settings.dataMode);
setDataSize(settings.dataSize);
setClockDivider(determine_baud_rate(_currentSetting->spi_d, settings.clock));
begin();
}
void SPIClass::beginTransactionSlave(SPISettings settings) {
setBitOrder(settings.bitOrder);
setDataMode(settings.dataMode);
setDataSize(settings.dataSize);
beginSlave();
}
void SPIClass::endTransaction() { }
/**
* I/O
*/
uint16_t SPIClass::read() {
while (!spi_is_rx_nonempty(_currentSetting->spi_d)) { /* nada */ }
return (uint16)spi_rx_reg(_currentSetting->spi_d);
}
void SPIClass::read(uint8_t *buf, uint32_t len) {
if (len == 0) return;
spi_rx_reg(_currentSetting->spi_d); // clear the RX buffer in case a byte is waiting on it.
spi_reg_map * regs = _currentSetting->spi_d->regs;
// start sequence: write byte 0
regs->DR = 0x00FF; // write the first byte
// main loop
while (--len) {
while(!(regs->SR & SPI_SR_TXE)) { /* nada */ } // wait for TXE flag
noInterrupts(); // go atomic level - avoid interrupts to surely get the previously received data
regs->DR = 0x00FF; // write the next data item to be transmitted into the SPI_DR register. This clears the TXE flag.
while (!(regs->SR & SPI_SR_RXNE)) { /* nada */ } // wait till data is available in the DR register
*buf++ = (uint8)(regs->DR); // read and store the received byte. This clears the RXNE flag.
interrupts(); // let systick do its job
}
// read remaining last byte
while (!(regs->SR & SPI_SR_RXNE)) { /* nada */ } // wait till data is available in the Rx register
*buf++ = (uint8)(regs->DR); // read and store the received byte
}
void SPIClass::write(uint16_t data) {
/* Added for 16bit data Victor Perez. Roger Clark
* Improved speed by just directly writing the single byte to the SPI data reg and wait for completion,
* by taking the Tx code from transfer(byte)
* This almost doubles the speed of this function.
*/
spi_tx_reg(_currentSetting->spi_d, data); // write the data to be transmitted into the SPI_DR register (this clears the TXE flag)
waitSpiTxEnd(_currentSetting->spi_d);
}
void SPIClass::write16(uint16_t data) {
// Added by stevestrong: write two consecutive bytes in 8 bit mode (DFF=0)
spi_tx_reg(_currentSetting->spi_d, data>>8); // write high byte
while (!spi_is_tx_empty(_currentSetting->spi_d)) { /* nada */ } // Wait until TXE=1
spi_tx_reg(_currentSetting->spi_d, data); // write low byte
waitSpiTxEnd(_currentSetting->spi_d);
}
void SPIClass::write(uint16_t data, uint32_t n) {
// Added by stevstrong: Repeatedly send same data by the specified number of times
spi_reg_map * regs = _currentSetting->spi_d->regs;
while (n--) {
regs->DR = data; // write the data to be transmitted into the SPI_DR register (this clears the TXE flag)
while (!(regs->SR & SPI_SR_TXE)) { /* nada */ } // wait till Tx empty
}
while (regs->SR & SPI_SR_BSY) { /* nada */ } // wait until BSY=0 before returning
}
void SPIClass::write(const void *data, uint32_t length) {
spi_dev * spi_d = _currentSetting->spi_d;
spi_tx(spi_d, data, length); // data can be array of bytes or words
waitSpiTxEnd(spi_d);
}
uint8_t SPIClass::transfer(uint8_t byte) const {
spi_dev * spi_d = _currentSetting->spi_d;
spi_rx_reg(spi_d); // read any previous data
spi_tx_reg(spi_d, byte); // Write the data item to be transmitted into the SPI_DR register
waitSpiTxEnd(spi_d);
return (uint8)spi_rx_reg(spi_d); // "... and read the last received data."
}
uint16_t SPIClass::transfer16(uint16_t data) const {
// Modified by stevestrong: write & read two consecutive bytes in 8 bit mode (DFF=0)
// This is more effective than two distinct byte transfers
spi_dev * spi_d = _currentSetting->spi_d;
spi_rx_reg(spi_d); // read any previous data
spi_tx_reg(spi_d, data>>8); // write high byte
waitSpiTxEnd(spi_d); // wait until TXE=1 and then wait until BSY=0
uint16_t ret = spi_rx_reg(spi_d)<<8; // read and shift high byte
spi_tx_reg(spi_d, data); // write low byte
waitSpiTxEnd(spi_d); // wait until TXE=1 and then wait until BSY=0
ret += spi_rx_reg(spi_d); // read low byte
return ret;
}
/**
* Roger Clark and Victor Perez, 2015
* Performs a DMA SPI transfer with at least a receive buffer.
* If a TX buffer is not provided, FF is sent over and over for the lenght of the transfer.
* On exit TX buffer is not modified, and RX buffer cotains the received data.
* Still in progress.
*/
void SPIClass::dmaTransferSet(const void *transmitBuf, void *receiveBuf) {
dma_init(_currentSetting->spiDmaDev);
//spi_rx_dma_enable(_currentSetting->spi_d);
//spi_tx_dma_enable(_currentSetting->spi_d);
dma_xfer_size dma_bit_size = (_currentSetting->dataSize==DATA_SIZE_16BIT) ? DMA_SIZE_16BITS : DMA_SIZE_8BITS;
dma_setup_transfer(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel, &_currentSetting->spi_d->regs->DR,
dma_bit_size, receiveBuf, dma_bit_size, (DMA_MINC_MODE | DMA_TRNS_CMPLT ));// receive buffer DMA
if (!transmitBuf) {
transmitBuf = &ff;
dma_setup_transfer(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &_currentSetting->spi_d->regs->DR,
dma_bit_size, (volatile void*)transmitBuf, dma_bit_size, (DMA_FROM_MEM));// Transmit FF repeatedly
}
else {
dma_setup_transfer(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &_currentSetting->spi_d->regs->DR,
dma_bit_size, (volatile void*)transmitBuf, dma_bit_size, (DMA_MINC_MODE | DMA_FROM_MEM ));// Transmit buffer DMA
}
dma_set_priority(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, DMA_PRIORITY_LOW);
dma_set_priority(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel, DMA_PRIORITY_VERY_HIGH);
}
uint8_t SPIClass::dmaTransferRepeat(uint16_t length) {
if (length == 0) return 0;
if (spi_is_rx_nonempty(_currentSetting->spi_d) == 1) spi_rx_reg(_currentSetting->spi_d);
_currentSetting->state = SPI_STATE_TRANSFER;
dma_set_num_transfers(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel, length);
dma_set_num_transfers(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, length);
dma_enable(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel);// enable receive
dma_enable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);// enable transmit
spi_rx_dma_enable(_currentSetting->spi_d);
spi_tx_dma_enable(_currentSetting->spi_d);
if (_currentSetting->receiveCallback)
return 0;
//uint32_t m = millis();
uint8_t b = 0;
uint32_t m = millis();
while (!(dma_get_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel) & DMA_ISR_TCIF1)) {
// Avoid interrupts and just loop waiting for the flag to be set.
if ((millis() - m) > DMA_TIMEOUT) { b = 2; break; }
}
waitSpiTxEnd(_currentSetting->spi_d); // until TXE=1 and BSY=0
spi_tx_dma_disable(_currentSetting->spi_d);
spi_rx_dma_disable(_currentSetting->spi_d);
dma_disable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
dma_disable(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel);
dma_clear_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel);
dma_clear_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
_currentSetting->state = SPI_STATE_READY;
return b;
}
/**
* Roger Clark and Victor Perez, 2015
* Performs a DMA SPI transfer with at least a receive buffer.
* If a TX buffer is not provided, FF is sent over and over for the length of the transfer.
* On exit TX buffer is not modified, and RX buffer contains the received data.
* Still in progress.
*/
uint8_t SPIClass::dmaTransfer(const void *transmitBuf, void *receiveBuf, uint16_t length) {
dmaTransferSet(transmitBuf, receiveBuf);
return dmaTransferRepeat(length);
}
/**
* Roger Clark and Victor Perez, 2015
* Performs a DMA SPI send using a TX buffer.
* On exit TX buffer is not modified.
* Still in progress.
* 2016 - stevstrong - reworked to automatically detect bit size from SPI setting
*/
void SPIClass::dmaSendSet(const void * transmitBuf, bool minc) {
uint32_t flags = ( (DMA_MINC_MODE*minc) | DMA_FROM_MEM | DMA_TRNS_CMPLT);
dma_init(_currentSetting->spiDmaDev);
dma_xfer_size dma_bit_size = (_currentSetting->dataSize==DATA_SIZE_16BIT) ? DMA_SIZE_16BITS : DMA_SIZE_8BITS;
dma_setup_transfer(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &_currentSetting->spi_d->regs->DR, dma_bit_size,
(volatile void*)transmitBuf, dma_bit_size, flags);// Transmit buffer DMA
dma_set_priority(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, DMA_PRIORITY_LOW);
}
uint8_t SPIClass::dmaSendRepeat(uint16_t length) {
if (length == 0) return 0;
dma_clear_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
dma_set_num_transfers(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, length);
_currentSetting->state = SPI_STATE_TRANSMIT;
dma_enable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel); // enable transmit
spi_tx_dma_enable(_currentSetting->spi_d);
if (_currentSetting->transmitCallback) return 0;
uint32_t m = millis();
uint8_t b = 0;
while (!(dma_get_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel) & DMA_ISR_TCIF1)) {
// Avoid interrupts and just loop waiting for the flag to be set.
if ((millis() - m) > DMA_TIMEOUT) { b = 2; break; }
}
waitSpiTxEnd(_currentSetting->spi_d); // until TXE=1 and BSY=0
spi_tx_dma_disable(_currentSetting->spi_d);
dma_disable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
dma_clear_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
_currentSetting->state = SPI_STATE_READY;
return b;
}
uint8_t SPIClass::dmaSend(const void * transmitBuf, uint16_t length, bool minc) {
dmaSendSet(transmitBuf, minc);
return dmaSendRepeat(length);
}
uint8_t SPIClass::dmaSendAsync(const void * transmitBuf, uint16_t length, bool minc) {
uint8_t b = 0;
if (_currentSetting->state != SPI_STATE_READY) {
uint32_t m = millis();
while (!(dma_get_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel) & DMA_ISR_TCIF1)) {
//Avoid interrupts and just loop waiting for the flag to be set.
//delayMicroseconds(10);
if ((millis() - m) > DMA_TIMEOUT) { b = 2; break; }
}
waitSpiTxEnd(_currentSetting->spi_d); // until TXE=1 and BSY=0
spi_tx_dma_disable(_currentSetting->spi_d);
dma_disable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
_currentSetting->state = SPI_STATE_READY;
}
if (length == 0) return 0;
uint32_t flags = ( (DMA_MINC_MODE*minc) | DMA_FROM_MEM | DMA_TRNS_CMPLT);
dma_init(_currentSetting->spiDmaDev);
// TX
dma_xfer_size dma_bit_size = (_currentSetting->dataSize==DATA_SIZE_16BIT) ? DMA_SIZE_16BITS : DMA_SIZE_8BITS;
dma_setup_transfer(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &_currentSetting->spi_d->regs->DR,
dma_bit_size, (volatile void*)transmitBuf, dma_bit_size, flags);// Transmit buffer DMA
dma_set_num_transfers(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, length);
dma_clear_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
dma_enable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);// enable transmit
spi_tx_dma_enable(_currentSetting->spi_d);
_currentSetting->state = SPI_STATE_TRANSMIT;
return b;
}
/**
* New functions added to manage callbacks.
* Victor Perez 2017
*/
void SPIClass::onReceive(void(*callback)()) {
_currentSetting->receiveCallback = callback;
if (callback) {
switch (_currentSetting->spi_d->clk_id) {
#if BOARD_NR_SPI >= 1
case RCC_SPI1:
dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel, &SPIClass::_spi1EventCallback);
break;
#endif
#if BOARD_NR_SPI >= 2
case RCC_SPI2:
dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel, &SPIClass::_spi2EventCallback);
break;
#endif
#if BOARD_NR_SPI >= 3
case RCC_SPI3:
dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel, &SPIClass::_spi3EventCallback);
break;
#endif
default:
ASSERT(0);
}
}
else {
dma_detach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel);
}
}
void SPIClass::onTransmit(void(*callback)()) {
_currentSetting->transmitCallback = callback;
if (callback) {
switch (_currentSetting->spi_d->clk_id) {
#if BOARD_NR_SPI >= 1
case RCC_SPI1:
dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &SPIClass::_spi1EventCallback);
break;
#endif
#if BOARD_NR_SPI >= 2
case RCC_SPI2:
dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &SPIClass::_spi2EventCallback);
break;
#endif
#if BOARD_NR_SPI >= 3
case RCC_SPI3:
dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &SPIClass::_spi3EventCallback);
break;
#endif
default:
ASSERT(0);
}
}
else {
dma_detach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
}
}
/**
* TODO: check if better to first call the customer code, next disable the DMA requests.
* Also see if we need to check whether callbacks are set or not, may be better to be checked
* during the initial setup and only set the callback to EventCallback if they are set.
*/
void SPIClass::EventCallback() {
waitSpiTxEnd(_currentSetting->spi_d);
switch (_currentSetting->state) {
case SPI_STATE_TRANSFER:
while (spi_is_rx_nonempty(_currentSetting->spi_d)) { /* nada */ }
_currentSetting->state = SPI_STATE_READY;
spi_tx_dma_disable(_currentSetting->spi_d);
spi_rx_dma_disable(_currentSetting->spi_d);
//dma_disable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
//dma_disable(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel);
if (_currentSetting->receiveCallback)
_currentSetting->receiveCallback();
break;
case SPI_STATE_TRANSMIT:
_currentSetting->state = SPI_STATE_READY;
spi_tx_dma_disable(_currentSetting->spi_d);
//dma_disable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
if (_currentSetting->transmitCallback)
_currentSetting->transmitCallback();
break;
default:
break;
}
}
void SPIClass::attachInterrupt() {
// Should be enableInterrupt()
}
void SPIClass::detachInterrupt() {
// Should be disableInterrupt()
}
/**
* Pin accessors
*/
uint8_t SPIClass::misoPin() {
return dev_to_spi_pins(_currentSetting->spi_d)->miso;
}
uint8_t SPIClass::mosiPin() {
return dev_to_spi_pins(_currentSetting->spi_d)->mosi;
}
uint8_t SPIClass::sckPin() {
return dev_to_spi_pins(_currentSetting->spi_d)->sck;
}
uint8_t SPIClass::nssPin() {
return dev_to_spi_pins(_currentSetting->spi_d)->nss;
}
/**
* Deprecated functions
*/
uint8_t SPIClass::send(uint8_t data) { write(data); return 1; }
uint8_t SPIClass::send(uint8_t *buf, uint32_t len) { write(buf, len); return len; }
uint8_t SPIClass::recv() { return read(); }
/**
* DMA call back functions, one per port.
*/
#if BOARD_NR_SPI >= 1
void SPIClass::_spi1EventCallback() {
reinterpret_cast<class SPIClass*>(_spi1_this)->EventCallback();
}
#endif
#if BOARD_NR_SPI >= 2
void SPIClass::_spi2EventCallback() {
reinterpret_cast<class SPIClass*>(_spi2_this)->EventCallback();
}
#endif
#if BOARD_NR_SPI >= 3
void SPIClass::_spi3EventCallback() {
reinterpret_cast<class SPIClass*>(_spi3_this)->EventCallback();
}
#endif
/**
* Auxiliary functions
*/
static const spi_pins* dev_to_spi_pins(spi_dev *dev) {
switch (dev->clk_id) {
#if BOARD_NR_SPI >= 1
case RCC_SPI1: return board_spi_pins;
#endif
#if BOARD_NR_SPI >= 2
case RCC_SPI2: return board_spi_pins + 1;
#endif
#if BOARD_NR_SPI >= 3
case RCC_SPI3: return board_spi_pins + 2;
#endif
default: return NULL;
}
}
static void disable_pwm(const stm32_pin_info *i) {
if (i->timer_device)
timer_set_mode(i->timer_device, i->timer_channel, TIMER_DISABLED);
}
static void configure_gpios(spi_dev *dev, bool as_master) {
const spi_pins *pins = dev_to_spi_pins(dev);
if (!pins) return;
const stm32_pin_info *nssi = &PIN_MAP[pins->nss],
*scki = &PIN_MAP[pins->sck],
*misoi = &PIN_MAP[pins->miso],
*mosii = &PIN_MAP[pins->mosi];
disable_pwm(nssi);
disable_pwm(scki);
disable_pwm(misoi);
disable_pwm(mosii);
spi_config_gpios(dev, as_master, nssi->gpio_device, nssi->gpio_bit,
scki->gpio_device, scki->gpio_bit, misoi->gpio_bit,
mosii->gpio_bit);
}
static const spi_baud_rate baud_rates[8] __FLASH__ = {
SPI_BAUD_PCLK_DIV_2,
SPI_BAUD_PCLK_DIV_4,
SPI_BAUD_PCLK_DIV_8,
SPI_BAUD_PCLK_DIV_16,
SPI_BAUD_PCLK_DIV_32,
SPI_BAUD_PCLK_DIV_64,
SPI_BAUD_PCLK_DIV_128,
SPI_BAUD_PCLK_DIV_256,
};
/**
* Note: This assumes you're on a LeafLabs-style board
* (CYCLES_PER_MICROSECOND == 72, APB2 at 72MHz, APB1 at 36MHz).
*/
static spi_baud_rate determine_baud_rate(spi_dev *dev, uint32_t freq) {
uint32_t clock = 0;
switch (rcc_dev_clk(dev->clk_id)) {
case RCC_AHB:
case RCC_APB2: clock = STM32_PCLK2; break; // 72 Mhz
case RCC_APB1: clock = STM32_PCLK1; break; // 36 Mhz
}
clock >>= 1;
uint8_t i = 0;
while (i < 7 && freq < clock) { clock >>= 1; i++; }
return baud_rates[i];
}
SPIClass SPI(1);
#endif // __STM32F1__

View File

@ -0,0 +1,417 @@
/******************************************************************************
* The MIT License
*
* Copyright (c) 2010 Perry Hung.
*
* Permission is hereby granted, free of charge, to any person
* obtaining a copy of this software and associated documentation
* files (the "Software"), to deal in the Software without
* restriction, including without limitation the rights to use, copy,
* modify, merge, publish, distribute, sublicense, and/or sell copies
* of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be
* included in all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
* BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
* ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*****************************************************************************/
#pragma once
#include <libmaple/libmaple_types.h>
#include <libmaple/spi.h>
#include <libmaple/dma.h>
#include <boards.h>
#include <stdint.h>
#include <wirish.h>
// SPI_HAS_TRANSACTION means SPI has
// - beginTransaction()
// - endTransaction()
// - usingInterrupt()
// - SPISetting(clock, bitOrder, dataMode)
//#define SPI_HAS_TRANSACTION
#define SPI_CLOCK_DIV2 SPI_BAUD_PCLK_DIV_2
#define SPI_CLOCK_DIV4 SPI_BAUD_PCLK_DIV_4
#define SPI_CLOCK_DIV8 SPI_BAUD_PCLK_DIV_8
#define SPI_CLOCK_DIV16 SPI_BAUD_PCLK_DIV_16
#define SPI_CLOCK_DIV32 SPI_BAUD_PCLK_DIV_32
#define SPI_CLOCK_DIV64 SPI_BAUD_PCLK_DIV_64
#define SPI_CLOCK_DIV128 SPI_BAUD_PCLK_DIV_128
#define SPI_CLOCK_DIV256 SPI_BAUD_PCLK_DIV_256
/*
* Roger Clark. 20150106
* Commented out redundant AVR defined
*
#define SPI_MODE_MASK 0x0C // CPOL = bit 3, CPHA = bit 2 on SPCR
#define SPI_CLOCK_MASK 0x03 // SPR1 = bit 1, SPR0 = bit 0 on SPCR
#define SPI_2XCLOCK_MASK 0x01 // SPI2X = bit 0 on SPSR
// define SPI_AVR_EIMSK for AVR boards with external interrupt pins
#ifdef EIMSK
#define SPI_AVR_EIMSK EIMSK
#elif defined(GICR)
#define SPI_AVR_EIMSK GICR
#elif defined(GIMSK)
#define SPI_AVR_EIMSK GIMSK
#endif
*/
#ifndef STM32_LSBFIRST
#define STM32_LSBFIRST 0
#endif
#ifndef STM32_MSBFIRST
#define STM32_MSBFIRST 1
#endif
// PC13 or PA4
#define BOARD_SPI_DEFAULT_SS PA4
//#define BOARD_SPI_DEFAULT_SS PC13
#define SPI_MODE0 SPI_MODE_0
#define SPI_MODE1 SPI_MODE_1
#define SPI_MODE2 SPI_MODE_2
#define SPI_MODE3 SPI_MODE_3
#define DATA_SIZE_8BIT SPI_CR1_DFF_8_BIT
#define DATA_SIZE_16BIT SPI_CR1_DFF_16_BIT
typedef enum {
SPI_STATE_IDLE,
SPI_STATE_READY,
SPI_STATE_RECEIVE,
SPI_STATE_TRANSMIT,
SPI_STATE_TRANSFER
} spi_mode_t;
class SPISettings {
public:
SPISettings(uint32_t inClock, BitOrder inBitOrder, uint8_t inDataMode) {
if (__builtin_constant_p(inClock))
init_AlwaysInline(inClock, inBitOrder, inDataMode, DATA_SIZE_8BIT);
else
init_MightInline(inClock, inBitOrder, inDataMode, DATA_SIZE_8BIT);
}
SPISettings(uint32_t inClock, BitOrder inBitOrder, uint8_t inDataMode, uint32_t inDataSize) {
if (__builtin_constant_p(inClock))
init_AlwaysInline(inClock, inBitOrder, inDataMode, inDataSize);
else
init_MightInline(inClock, inBitOrder, inDataMode, inDataSize);
}
SPISettings(uint32_t inClock) {
if (__builtin_constant_p(inClock))
init_AlwaysInline(inClock, MSBFIRST, SPI_MODE0, DATA_SIZE_8BIT);
else
init_MightInline(inClock, MSBFIRST, SPI_MODE0, DATA_SIZE_8BIT);
}
SPISettings() {
init_AlwaysInline(4000000, MSBFIRST, SPI_MODE0, DATA_SIZE_8BIT);
}
private:
void init_MightInline(uint32_t inClock, BitOrder inBitOrder, uint8_t inDataMode, uint32_t inDataSize) {
init_AlwaysInline(inClock, inBitOrder, inDataMode, inDataSize);
}
void init_AlwaysInline(uint32_t inClock, BitOrder inBitOrder, uint8_t inDataMode, uint32_t inDataSize) __attribute__((__always_inline__)) {
clock = inClock;
bitOrder = inBitOrder;
dataMode = inDataMode;
dataSize = inDataSize;
}
uint32_t clock;
uint32_t dataSize;
uint32_t clockDivider;
BitOrder bitOrder;
uint8_t dataMode;
uint8_t _SSPin;
volatile spi_mode_t state;
spi_dev *spi_d;
dma_channel spiRxDmaChannel, spiTxDmaChannel;
dma_dev* spiDmaDev;
void (*receiveCallback)() = NULL;
void (*transmitCallback)() = NULL;
friend class SPIClass;
};
/*
* Kept for compat.
*/
static const uint8_t ff = 0xFF;
/**
* @brief Wirish SPI interface.
*
* This implementation uses software slave management, so the caller
* is responsible for controlling the slave select line.
*/
class SPIClass {
public:
/**
* @param spiPortNumber Number of the SPI port to manage.
*/
SPIClass(uint32_t spiPortNumber);
/**
* @brief Equivalent to begin(SPI_1_125MHZ, MSBFIRST, 0).
*/
void begin();
/**
* @brief Turn on a SPI port and set its GPIO pin modes for use as a slave.
*
* SPI port is enabled in full duplex mode, with software slave management.
*
* @param bitOrder Either LSBFIRST (little-endian) or MSBFIRST(big-endian)
* @param mode SPI mode to use
*/
void beginSlave(uint32_t bitOrder, uint32_t mode);
/**
* @brief Equivalent to beginSlave(MSBFIRST, 0).
*/
void beginSlave();
/**
* @brief Disables the SPI port, but leaves its GPIO pin modes unchanged.
*/
void end();
void beginTransaction(SPISettings settings) { beginTransaction(BOARD_SPI_DEFAULT_SS, settings); }
void beginTransaction(uint8_t pin, SPISettings settings);
void endTransaction();
void beginTransactionSlave(SPISettings settings);
void setClockDivider(uint32_t clockDivider);
void setBitOrder(BitOrder bitOrder);
void setDataMode(uint8_t dataMode);
// SPI Configuration methods
void attachInterrupt();
void detachInterrupt();
/* Victor Perez. Added to change datasize from 8 to 16 bit modes on the fly.
* Input parameter should be SPI_CR1_DFF set to 0 or 1 on a 32bit word.
* Requires an added function spi_data_size on STM32F1 / cores / maple / libmaple / spi.c
*/
void setDataSize(uint32_t ds);
/* Victor Perez 2017. Added to set and clear callback functions for callback
* on DMA transfer completion.
* onReceive used to set the callback in case of dmaTransfer (tx/rx), once rx is completed
* onTransmit used to set the callback in case of dmaSend (tx only). That function
* will NOT be called in case of TX/RX
*/
void onReceive(void(*)());
void onTransmit(void(*)());
/*
* I/O
*/
/**
* @brief Return the next unread byte/word.
*
* If there is no unread byte/word waiting, this function will block
* until one is received.
*/
uint16_t read();
/**
* @brief Read length bytes, storing them into buffer.
* @param buffer Buffer to store received bytes into.
* @param length Number of bytes to store in buffer. This
* function will block until the desired number of
* bytes have been read.
*/
void read(uint8_t *buffer, uint32_t length);
/**
* @brief Transmit one byte/word.
* @param data to transmit.
*/
void write(uint16_t data);
void write16(uint16_t data); // write 2 bytes in 8 bit mode (DFF=0)
/**
* @brief Transmit one byte/word a specified number of times.
* @param data to transmit.
*/
void write(uint16_t data, uint32_t n);
/**
* @brief Transmit multiple bytes/words.
* @param buffer Bytes/words to transmit.
* @param length Number of bytes/words in buffer to transmit.
*/
void write(const void * buffer, uint32_t length);
/**
* @brief Transmit a byte, then return the next unread byte.
*
* This function transmits before receiving.
*
* @param data Byte to transmit.
* @return Next unread byte.
*/
uint8_t transfer(uint8_t data) const;
uint16_t transfer16(uint16_t data) const;
/**
* @brief Sets up a DMA Transfer for "length" bytes.
* The transfer mode (8 or 16 bit mode) is evaluated from the SPI peripheral setting.
*
* This function transmits and receives to buffers.
*
* @param transmitBuf buffer Bytes to transmit. If passed as 0, it sends FF repeatedly for "length" bytes
* @param receiveBuf buffer Bytes to save received data.
* @param length Number of bytes in buffer to transmit.
*/
uint8_t dmaTransfer(const void * transmitBuf, void * receiveBuf, uint16_t length);
void dmaTransferSet(const void *transmitBuf, void *receiveBuf);
uint8_t dmaTransferRepeat(uint16_t length);
/**
* @brief Sets up a DMA Transmit for SPI 8 or 16 bit transfer mode.
* The transfer mode (8 or 16 bit mode) is evaluated from the SPI peripheral setting.
*
* This function only transmits and does not care about the RX fifo.
*
* @param data buffer half words to transmit,
* @param length Number of bytes in buffer to transmit.
* @param minc Set to use Memory Increment mode, clear to use Circular mode.
*/
uint8_t dmaSend(const void * transmitBuf, uint16_t length, bool minc = 1);
void dmaSendSet(const void * transmitBuf, bool minc);
uint8_t dmaSendRepeat(uint16_t length);
uint8_t dmaSendAsync(const void * transmitBuf, uint16_t length, bool minc = 1);
/*
* Pin accessors
*/
/**
* @brief Return the number of the MISO (master in, slave out) pin
*/
uint8_t misoPin();
/**
* @brief Return the number of the MOSI (master out, slave in) pin
*/
uint8_t mosiPin();
/**
* @brief Return the number of the SCK (serial clock) pin
*/
uint8_t sckPin();
/**
* @brief Return the number of the NSS (slave select) pin
*/
uint8_t nssPin();
/* Escape hatch */
/**
* @brief Get a pointer to the underlying libmaple spi_dev for
* this HardwareSPI instance.
*/
spi_dev* c_dev() { return _currentSetting->spi_d; }
spi_dev* dev() { return _currentSetting->spi_d; }
/**
* @brief Sets the number of the SPI peripheral to be used by
* this HardwareSPI instance.
*
* @param spi_num Number of the SPI port. 1-2 in low density devices
* or 1-3 in high density devices.
*/
void setModule(int spi_num) {
_currentSetting = &_settings[spi_num - 1];// SPI channels are called 1 2 and 3 but the array is zero indexed
}
/* -- The following methods are deprecated --------------------------- */
/**
* @brief Deprecated.
*
* Use HardwareSPI::transfer() instead.
*
* @see HardwareSPI::transfer()
*/
uint8_t send(uint8_t data);
/**
* @brief Deprecated.
*
* Use HardwareSPI::write() in combination with
* HardwareSPI::read() (or HardwareSPI::transfer()) instead.
*
* @see HardwareSPI::write()
* @see HardwareSPI::read()
* @see HardwareSPI::transfer()
*/
uint8_t send(uint8_t *data, uint32_t length);
/**
* @brief Deprecated.
*
* Use HardwareSPI::read() instead.
*
* @see HardwareSPI::read()
*/
uint8_t recv();
private:
SPISettings _settings[BOARD_NR_SPI];
SPISettings *_currentSetting;
void updateSettings();
/*
* Functions added for DMA transfers with Callback.
* Experimental.
*/
void EventCallback();
#if BOARD_NR_SPI >= 1
static void _spi1EventCallback();
#endif
#if BOARD_NR_SPI >= 2
static void _spi2EventCallback();
#endif
#if BOARD_NR_SPI >= 3
static void _spi3EventCallback();
#endif
/*
spi_dev *spi_d;
uint8_t _SSPin;
uint32_t clockDivider;
uint8_t dataMode;
BitOrder bitOrder;
*/
};
/**
* @brief Wait until TXE (tx empty) flag is set and BSY (busy) flag unset.
*/
static inline void waitSpiTxEnd(spi_dev *spi_d) {
while (spi_is_tx_empty(spi_d) == 0) { /* nada */ } // wait until TXE=1
while (spi_is_busy(spi_d) != 0) { /* nada */ } // wait until BSY=0
}
extern SPIClass SPI;

View File

@ -0,0 +1,229 @@
/**
* 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/>.
*
*/
#ifdef __STM32F1__
#include "../../inc/MarlinConfig.h"
#if HAS_SERVOS
uint8_t ServoCount = 0;
#include "Servo.h"
#include "timers.h"
//#include "Servo.h"
#include <boards.h>
#include <io.h>
#include <pwm.h>
#include <wirish_math.h>
/**
* 20 millisecond period config. For a 1-based prescaler,
*
* (prescaler * overflow / CYC_MSEC) msec = 1 timer cycle = 20 msec
* => prescaler * overflow = 20 * CYC_MSEC
*
* This uses the smallest prescaler that allows an overflow < 2^16.
*/
#define MAX_OVERFLOW UINT16_MAX //((1 << 16) - 1)
#define CYC_MSEC (1000 * CYCLES_PER_MICROSECOND)
#define TAU_MSEC 20
#define TAU_USEC (TAU_MSEC * 1000)
#define TAU_CYC (TAU_MSEC * CYC_MSEC)
#define SERVO_PRESCALER (TAU_CYC / MAX_OVERFLOW + 1)
#define SERVO_OVERFLOW ((uint16_t)round((double)TAU_CYC / SERVO_PRESCALER))
// Unit conversions
#define US_TO_COMPARE(us) uint16_t(map((us), 0, TAU_USEC, 0, SERVO_OVERFLOW))
#define COMPARE_TO_US(c) uint32_t(map((c), 0, SERVO_OVERFLOW, 0, TAU_USEC))
#define ANGLE_TO_US(a) uint16_t(map((a), minAngle, maxAngle, SERVO_DEFAULT_MIN_PW, SERVO_DEFAULT_MAX_PW))
#define US_TO_ANGLE(us) int16_t(map((us), SERVO_DEFAULT_MIN_PW, SERVO_DEFAULT_MAX_PW, minAngle, maxAngle))
void libServo::servoWrite(uint8_t inPin, uint16_t duty_cycle) {
#ifdef SERVO0_TIMER_NUM
if (servoIndex == 0) {
pwmSetDuty(duty_cycle);
return;
}
#endif
timer_dev *tdev = PIN_MAP[inPin].timer_device;
uint8_t tchan = PIN_MAP[inPin].timer_channel;
if (tdev) timer_set_compare(tdev, tchan, duty_cycle);
}
libServo::libServo() {
servoIndex = ServoCount < MAX_SERVOS ? ServoCount++ : INVALID_SERVO;
}
bool libServo::attach(const int32_t inPin, const int32_t inMinAngle, const int32_t inMaxAngle) {
if (servoIndex >= MAX_SERVOS) return false;
if (inPin >= BOARD_NR_GPIO_PINS) return false;
minAngle = inMinAngle;
maxAngle = inMaxAngle;
angle = -1;
#ifdef SERVO0_TIMER_NUM
if (servoIndex == 0 && setupSoftPWM(inPin)) {
pin = inPin; // set attached()
return true;
}
#endif
if (!PWM_PIN(inPin)) return false;
timer_dev *tdev = PIN_MAP[inPin].timer_device;
//uint8_t tchan = PIN_MAP[inPin].timer_channel;
SET_PWM(inPin);
servoWrite(inPin, 0);
timer_pause(tdev);
timer_set_prescaler(tdev, SERVO_PRESCALER - 1); // prescaler is 1-based
timer_set_reload(tdev, SERVO_OVERFLOW);
timer_generate_update(tdev);
timer_resume(tdev);
pin = inPin; // set attached()
return true;
}
bool libServo::detach() {
if (!attached()) return false;
angle = -1;
servoWrite(pin, 0);
return true;
}
int32_t libServo::read() const {
if (attached()) {
#ifdef SERVO0_TIMER_NUM
if (servoIndex == 0) return angle;
#endif
timer_dev *tdev = PIN_MAP[pin].timer_device;
uint8_t tchan = PIN_MAP[pin].timer_channel;
return US_TO_ANGLE(COMPARE_TO_US(timer_get_compare(tdev, tchan)));
}
return 0;
}
void libServo::move(const int32_t value) {
constexpr uint16_t servo_delay[] = SERVO_DELAY;
static_assert(COUNT(servo_delay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long.");
if (attached()) {
angle = constrain(value, minAngle, maxAngle);
servoWrite(pin, US_TO_COMPARE(ANGLE_TO_US(angle)));
safe_delay(servo_delay[servoIndex]);
#if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE)
detach();
#endif
}
}
#ifdef SERVO0_TIMER_NUM
extern "C" void Servo_IRQHandler() {
static timer_dev *tdev = get_timer_dev(SERVO0_TIMER_NUM);
uint16_t SR = timer_get_status(tdev);
if (SR & TIMER_SR_CC1IF) { // channel 1 off
#ifdef SERVO0_PWM_OD
OUT_WRITE_OD(SERVO0_PIN, 1); // off
#else
OUT_WRITE(SERVO0_PIN, 0);
#endif
timer_reset_status_bit(tdev, TIMER_SR_CC1IF_BIT);
}
if (SR & TIMER_SR_CC2IF) { // channel 2 resume
#ifdef SERVO0_PWM_OD
OUT_WRITE_OD(SERVO0_PIN, 0); // on
#else
OUT_WRITE(SERVO0_PIN, 1);
#endif
timer_reset_status_bit(tdev, TIMER_SR_CC2IF_BIT);
}
}
bool libServo::setupSoftPWM(const int32_t inPin) {
timer_dev *tdev = get_timer_dev(SERVO0_TIMER_NUM);
if (!tdev) return false;
#ifdef SERVO0_PWM_OD
OUT_WRITE_OD(inPin, 1);
#else
OUT_WRITE(inPin, 0);
#endif
timer_pause(tdev);
timer_set_mode(tdev, 1, TIMER_OUTPUT_COMPARE); // counter with isr
timer_oc_set_mode(tdev, 1, TIMER_OC_MODE_FROZEN, 0); // no pin output change
timer_oc_set_mode(tdev, 2, TIMER_OC_MODE_FROZEN, 0); // no pin output change
timer_set_prescaler(tdev, SERVO_PRESCALER - 1); // prescaler is 1-based
timer_set_reload(tdev, SERVO_OVERFLOW);
timer_set_compare(tdev, 1, SERVO_OVERFLOW);
timer_set_compare(tdev, 2, SERVO_OVERFLOW);
timer_attach_interrupt(tdev, 1, Servo_IRQHandler);
timer_attach_interrupt(tdev, 2, Servo_IRQHandler);
timer_generate_update(tdev);
timer_resume(tdev);
return true;
}
void libServo::pwmSetDuty(const uint16_t duty_cycle) {
timer_dev *tdev = get_timer_dev(SERVO0_TIMER_NUM);
timer_set_compare(tdev, 1, duty_cycle);
timer_generate_update(tdev);
if (duty_cycle) {
timer_enable_irq(tdev, 1);
timer_enable_irq(tdev, 2);
}
else {
timer_disable_irq(tdev, 1);
timer_disable_irq(tdev, 2);
#ifdef SERVO0_PWM_OD
OUT_WRITE_OD(pin, 1); // off
#else
OUT_WRITE(pin, 0);
#endif
}
}
void libServo::pauseSoftPWM() { // detach
timer_dev *tdev = get_timer_dev(SERVO0_TIMER_NUM);
timer_pause(tdev);
pwmSetDuty(0);
}
#else
bool libServo::setupSoftPWM(const int32_t inPin) { return false; }
void libServo::pwmSetDuty(const uint16_t duty_cycle) {}
void libServo::pauseSoftPWM() {}
#endif
#endif // HAS_SERVOS
#endif // __STM32F1__

View File

@ -0,0 +1,60 @@
/**
* 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
// Pin number of unattached pins
#define NOT_ATTACHED (-1)
#define INVALID_SERVO 255
#ifndef MAX_SERVOS
#define MAX_SERVOS 3
#endif
#define SERVO_DEFAULT_MIN_PW 544
#define SERVO_DEFAULT_MAX_PW 2400
#define SERVO_DEFAULT_MIN_ANGLE 0
#define SERVO_DEFAULT_MAX_ANGLE 180
#define HAL_SERVO_LIB libServo
class libServo {
public:
libServo();
bool attach(const int32_t pin, const int32_t minAngle=SERVO_DEFAULT_MIN_ANGLE, const int32_t maxAngle=SERVO_DEFAULT_MAX_ANGLE);
bool attached() const { return pin != NOT_ATTACHED; }
bool detach();
void move(const int32_t value);
int32_t read() const;
private:
void servoWrite(uint8_t pin, const uint16_t duty_cycle);
uint8_t servoIndex; // index into the channel data for this servo
int32_t pin = NOT_ATTACHED;
int32_t minAngle;
int32_t maxAngle;
int32_t angle;
bool setupSoftPWM(const int32_t pin);
void pauseSoftPWM();
void pwmSetDuty(const uint16_t duty_cycle);
};

View File

@ -0,0 +1,60 @@
/**
* 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/>.
*
*/
#if defined(__STM32F1__) && !defined(HAVE_SW_SERIAL)
/**
* Empty class for Software Serial implementation (Custom RX/TX pins)
*
* TODO: Optionally use https://github.com/FYSETC/SoftwareSerialM if TMC UART is wanted
*/
#include "SoftwareSerial.h"
// Constructor
SoftwareSerial::SoftwareSerial(int8_t RX_pin, int8_t TX_pin) {}
// Public
void SoftwareSerial::begin(const uint32_t baudrate) {
}
bool SoftwareSerial::available() {
return false;
}
uint8_t SoftwareSerial::read() {
return 0;
}
uint16_t SoftwareSerial::write(uint8_t byte) {
return 0;
}
void SoftwareSerial::flush() {}
void SoftwareSerial::listen() {
listening = true;
}
void SoftwareSerial::stopListening() {
listening = false;
}
#endif //__STM32F1__

View File

@ -0,0 +1,44 @@
/**
* 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 <stdint.h>
#ifndef HAVE_SW_SERIAL
#define SW_SERIAL_PLACEHOLDER 1
#endif
class SoftwareSerial {
public:
SoftwareSerial(int8_t RX_pin, int8_t TX_pin);
void begin(const uint32_t baudrate);
bool available();
uint8_t read();
uint16_t write(uint8_t byte);
void flush();
void listen();
void stopListening();
protected:
bool listening;
};

View File

@ -0,0 +1,53 @@
from __future__ import print_function
import sys
#dynamic build flags for generic compile options
if __name__ == "__main__":
args = " ".join([ "-std=gnu11",
"-Os",
"-mcpu=cortex-m3",
"-mthumb",
"-fsigned-char",
"-fno-move-loop-invariants",
"-fno-strict-aliasing",
"--specs=nano.specs",
"--specs=nosys.specs",
"-IMarlin/src/HAL/STM32F1",
"-MMD",
"-MP",
"-DTARGET_STM32F1"
])
for i in range(1, len(sys.argv)):
args += " " + sys.argv[i]
print(args)
# extra script for linker options
else:
from SCons.Script import DefaultEnvironment
env = DefaultEnvironment()
env.Append(
ARFLAGS=["rcs"],
ASFLAGS=["-x", "assembler-with-cpp"],
CXXFLAGS=[
"-fabi-version=0",
"-fno-use-cxa-atexit",
"-fno-threadsafe-statics"
],
LINKFLAGS=[
"-Os",
"-mcpu=cortex-m3",
"-ffreestanding",
"-mthumb",
"--specs=nano.specs",
"--specs=nosys.specs",
"-u_printf_float",
],
)

View File

@ -0,0 +1,335 @@
/**
* 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/>.
*
*/
/**
* u8g_com_stm32duino_fsmc.cpp
*
* Communication interface for FSMC
*/
#include "../../../inc/MarlinConfig.h"
#if defined(ARDUINO_ARCH_STM32F1) && PIN_EXISTS(FSMC_CS) // FSMC on 100/144 pins SoCs
#if HAS_GRAPHICAL_LCD
#include <U8glib.h>
#include <libmaple/fsmc.h>
#include <libmaple/gpio.h>
#include <libmaple/dma.h>
#include <boards.h>
#ifndef LCD_READ_ID
#define LCD_READ_ID 0x04 // Read display identification information (0xD3 on ILI9341)
#endif
/* Timing configuration */
#define FSMC_ADDRESS_SETUP_TIME 15 // AddressSetupTime
#define FSMC_DATA_SETUP_TIME 15 // DataSetupTime
void LCD_IO_Init(uint8_t cs, uint8_t rs);
void LCD_IO_WriteData(uint16_t RegValue);
void LCD_IO_WriteReg(uint16_t Reg);
uint16_t LCD_IO_ReadData(uint16_t RegValue);
uint32_t LCD_IO_ReadData(uint16_t RegValue, uint8_t ReadSize);
#ifdef LCD_USE_DMA_FSMC
void LCD_IO_WriteMultiple(uint16_t data, uint32_t count);
void LCD_IO_WriteSequence(uint16_t *data, uint16_t length);
#endif
static uint8_t msgInitCount = 2; // Ignore all messages until 2nd U8G_COM_MSG_INIT
uint8_t u8g_com_stm32duino_fsmc_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) {
if (msgInitCount) {
if (msg == U8G_COM_MSG_INIT) msgInitCount--;
if (msgInitCount) return -1;
}
static uint8_t isCommand;
switch (msg) {
case U8G_COM_MSG_STOP: break;
case U8G_COM_MSG_INIT:
u8g_SetPIOutput(u8g, U8G_PI_RESET);
#ifdef LCD_USE_DMA_FSMC
dma_init(FSMC_DMA_DEV);
dma_disable(FSMC_DMA_DEV, FSMC_DMA_CHANNEL);
dma_set_priority(FSMC_DMA_DEV, FSMC_DMA_CHANNEL, DMA_PRIORITY_MEDIUM);
#endif
LCD_IO_Init(u8g->pin_list[U8G_PI_CS], u8g->pin_list[U8G_PI_A0]);
u8g_Delay(50);
if (arg_ptr) {
*((uint32_t *)arg_ptr) = LCD_IO_ReadData(0x0000);
if (*((uint32_t *)arg_ptr) == 0)
*((uint32_t *)arg_ptr) = (LCD_READ_ID << 24) | LCD_IO_ReadData(LCD_READ_ID, 3);
}
isCommand = 0;
break;
case U8G_COM_MSG_ADDRESS: // define cmd (arg_val = 0) or data mode (arg_val = 1)
isCommand = arg_val == 0 ? 1 : 0;
break;
case U8G_COM_MSG_RESET:
u8g_SetPILevel(u8g, U8G_PI_RESET, arg_val);
break;
case U8G_COM_MSG_WRITE_BYTE:
if (isCommand)
LCD_IO_WriteReg(arg_val);
else
LCD_IO_WriteData((uint16_t)arg_val);
break;
case U8G_COM_MSG_WRITE_SEQ:
for (uint8_t i = 0; i < arg_val; i += 2)
LCD_IO_WriteData(*(uint16_t *)(((uint32_t)arg_ptr) + i));
break;
}
return 1;
}
/**
* FSMC LCD IO
*/
#define __ASM __asm
#define __STATIC_INLINE static inline
__attribute__((always_inline)) __STATIC_INLINE void __DSB() {
__ASM volatile ("dsb 0xF":::"memory");
}
#define FSMC_CS_NE1 PD7
#if ENABLED(STM32_XL_DENSITY)
#define FSMC_CS_NE2 PG9
#define FSMC_CS_NE3 PG10
#define FSMC_CS_NE4 PG12
#define FSMC_RS_A0 PF0
#define FSMC_RS_A1 PF1
#define FSMC_RS_A2 PF2
#define FSMC_RS_A3 PF3
#define FSMC_RS_A4 PF4
#define FSMC_RS_A5 PF5
#define FSMC_RS_A6 PF12
#define FSMC_RS_A7 PF13
#define FSMC_RS_A8 PF14
#define FSMC_RS_A9 PF15
#define FSMC_RS_A10 PG0
#define FSMC_RS_A11 PG1
#define FSMC_RS_A12 PG2
#define FSMC_RS_A13 PG3
#define FSMC_RS_A14 PG4
#define FSMC_RS_A15 PG5
#endif
#define FSMC_RS_A16 PD11
#define FSMC_RS_A17 PD12
#define FSMC_RS_A18 PD13
#define FSMC_RS_A19 PE3
#define FSMC_RS_A20 PE4
#define FSMC_RS_A21 PE5
#define FSMC_RS_A22 PE6
#define FSMC_RS_A23 PE2
#if ENABLED(STM32_XL_DENSITY)
#define FSMC_RS_A24 PG13
#define FSMC_RS_A25 PG14
#endif
static uint8_t fsmcInit = 0;
typedef struct {
__IO uint16_t REG;
__IO uint16_t RAM;
} LCD_CONTROLLER_TypeDef;
LCD_CONTROLLER_TypeDef *LCD;
void LCD_IO_Init(uint8_t cs, uint8_t rs) {
uint32_t controllerAddress;
if (fsmcInit) return;
fsmcInit = 1;
switch (cs) {
case FSMC_CS_NE1: controllerAddress = (uint32_t)FSMC_NOR_PSRAM_REGION1; break;
#if ENABLED(STM32_XL_DENSITY)
case FSMC_CS_NE2: controllerAddress = (uint32_t)FSMC_NOR_PSRAM_REGION2; break;
case FSMC_CS_NE3: controllerAddress = (uint32_t)FSMC_NOR_PSRAM_REGION3; break;
case FSMC_CS_NE4: controllerAddress = (uint32_t)FSMC_NOR_PSRAM_REGION4; break;
#endif
default: return;
}
#define _ORADDR(N) controllerAddress |= (_BV32(N) - 2)
switch (rs) {
#if ENABLED(STM32_XL_DENSITY)
case FSMC_RS_A0: _ORADDR( 1); break;
case FSMC_RS_A1: _ORADDR( 2); break;
case FSMC_RS_A2: _ORADDR( 3); break;
case FSMC_RS_A3: _ORADDR( 4); break;
case FSMC_RS_A4: _ORADDR( 5); break;
case FSMC_RS_A5: _ORADDR( 6); break;
case FSMC_RS_A6: _ORADDR( 7); break;
case FSMC_RS_A7: _ORADDR( 8); break;
case FSMC_RS_A8: _ORADDR( 9); break;
case FSMC_RS_A9: _ORADDR(10); break;
case FSMC_RS_A10: _ORADDR(11); break;
case FSMC_RS_A11: _ORADDR(12); break;
case FSMC_RS_A12: _ORADDR(13); break;
case FSMC_RS_A13: _ORADDR(14); break;
case FSMC_RS_A14: _ORADDR(15); break;
case FSMC_RS_A15: _ORADDR(16); break;
#endif
case FSMC_RS_A16: _ORADDR(17); break;
case FSMC_RS_A17: _ORADDR(18); break;
case FSMC_RS_A18: _ORADDR(19); break;
case FSMC_RS_A19: _ORADDR(20); break;
case FSMC_RS_A20: _ORADDR(21); break;
case FSMC_RS_A21: _ORADDR(22); break;
case FSMC_RS_A22: _ORADDR(23); break;
case FSMC_RS_A23: _ORADDR(24); break;
#if ENABLED(STM32_XL_DENSITY)
case FSMC_RS_A24: _ORADDR(25); break;
case FSMC_RS_A25: _ORADDR(26); break;
#endif
default: return;
}
rcc_clk_enable(RCC_FSMC);
gpio_set_mode(GPIOD, 14, GPIO_AF_OUTPUT_PP); // FSMC_D00
gpio_set_mode(GPIOD, 15, GPIO_AF_OUTPUT_PP); // FSMC_D01
gpio_set_mode(GPIOD, 0, GPIO_AF_OUTPUT_PP); // FSMC_D02
gpio_set_mode(GPIOD, 1, GPIO_AF_OUTPUT_PP); // FSMC_D03
gpio_set_mode(GPIOE, 7, GPIO_AF_OUTPUT_PP); // FSMC_D04
gpio_set_mode(GPIOE, 8, GPIO_AF_OUTPUT_PP); // FSMC_D05
gpio_set_mode(GPIOE, 9, GPIO_AF_OUTPUT_PP); // FSMC_D06
gpio_set_mode(GPIOE, 10, GPIO_AF_OUTPUT_PP); // FSMC_D07
gpio_set_mode(GPIOE, 11, GPIO_AF_OUTPUT_PP); // FSMC_D08
gpio_set_mode(GPIOE, 12, GPIO_AF_OUTPUT_PP); // FSMC_D09
gpio_set_mode(GPIOE, 13, GPIO_AF_OUTPUT_PP); // FSMC_D10
gpio_set_mode(GPIOE, 14, GPIO_AF_OUTPUT_PP); // FSMC_D11
gpio_set_mode(GPIOE, 15, GPIO_AF_OUTPUT_PP); // FSMC_D12
gpio_set_mode(GPIOD, 8, GPIO_AF_OUTPUT_PP); // FSMC_D13
gpio_set_mode(GPIOD, 9, GPIO_AF_OUTPUT_PP); // FSMC_D14
gpio_set_mode(GPIOD, 10, GPIO_AF_OUTPUT_PP); // FSMC_D15
gpio_set_mode(GPIOD, 4, GPIO_AF_OUTPUT_PP); // FSMC_NOE
gpio_set_mode(GPIOD, 5, GPIO_AF_OUTPUT_PP); // FSMC_NWE
gpio_set_mode(PIN_MAP[cs].gpio_device, PIN_MAP[cs].gpio_bit, GPIO_AF_OUTPUT_PP); //FSMC_CS_NEx
gpio_set_mode(PIN_MAP[rs].gpio_device, PIN_MAP[rs].gpio_bit, GPIO_AF_OUTPUT_PP); //FSMC_RS_Ax
#if ENABLED(STM32_XL_DENSITY)
FSMC_NOR_PSRAM4_BASE->BCR = FSMC_BCR_WREN | FSMC_BCR_MTYP_SRAM | FSMC_BCR_MWID_16BITS | FSMC_BCR_MBKEN;
FSMC_NOR_PSRAM4_BASE->BTR = (FSMC_DATA_SETUP_TIME << 8) | FSMC_ADDRESS_SETUP_TIME;
#else // PSRAM1 for STM32F103V (high density)
FSMC_NOR_PSRAM1_BASE->BCR = FSMC_BCR_WREN | FSMC_BCR_MTYP_SRAM | FSMC_BCR_MWID_16BITS | FSMC_BCR_MBKEN;
FSMC_NOR_PSRAM1_BASE->BTR = (FSMC_DATA_SETUP_TIME << 8) | FSMC_ADDRESS_SETUP_TIME;
#endif
afio_remap(AFIO_REMAP_FSMC_NADV);
LCD = (LCD_CONTROLLER_TypeDef*)controllerAddress;
}
void LCD_IO_WriteData(uint16_t RegValue) {
LCD->RAM = RegValue;
__DSB();
}
void LCD_IO_WriteReg(uint16_t Reg) {
LCD->REG = Reg;
__DSB();
}
uint16_t LCD_IO_ReadData(uint16_t RegValue) {
LCD->REG = RegValue;
__DSB();
return LCD->RAM;
}
uint32_t LCD_IO_ReadData(uint16_t RegValue, uint8_t ReadSize) {
volatile uint32_t data;
LCD->REG = RegValue;
__DSB();
data = LCD->RAM; // dummy read
data = LCD->RAM & 0x00FF;
while (--ReadSize) {
data <<= 8;
data |= (LCD->RAM & 0x00FF);
}
return uint32_t(data);
}
#if ENABLED(LCD_USE_DMA_FSMC)
void LCD_IO_WriteMultiple(uint16_t color, uint32_t count) {
while (count > 0) {
dma_setup_transfer(FSMC_DMA_DEV, FSMC_DMA_CHANNEL, &color, DMA_SIZE_16BITS, &LCD->RAM, DMA_SIZE_16BITS, DMA_MEM_2_MEM);
dma_set_num_transfers(FSMC_DMA_DEV, FSMC_DMA_CHANNEL, count > 65535 ? 65535 : count);
dma_clear_isr_bits(FSMC_DMA_DEV, FSMC_DMA_CHANNEL);
dma_enable(FSMC_DMA_DEV, FSMC_DMA_CHANNEL);
while ((dma_get_isr_bits(FSMC_DMA_DEV, FSMC_DMA_CHANNEL) & 0x0A) == 0) {};
dma_disable(FSMC_DMA_DEV, FSMC_DMA_CHANNEL);
count = count > 65535 ? count - 65535 : 0;
}
}
void LCD_IO_WriteSequence(uint16_t *data, uint16_t length) {
dma_setup_transfer(FSMC_DMA_DEV, FSMC_DMA_CHANNEL, data, DMA_SIZE_16BITS, &LCD->RAM, DMA_SIZE_16BITS, DMA_MEM_2_MEM | DMA_PINC_MODE);
dma_set_num_transfers(FSMC_DMA_DEV, FSMC_DMA_CHANNEL, length);
dma_clear_isr_bits(FSMC_DMA_DEV, FSMC_DMA_CHANNEL);
dma_enable(FSMC_DMA_DEV, FSMC_DMA_CHANNEL);
while ((dma_get_isr_bits(FSMC_DMA_DEV, FSMC_DMA_CHANNEL) & 0x0A) == 0) {};
dma_disable(FSMC_DMA_DEV, FSMC_DMA_CHANNEL);
}
void LCD_IO_WriteSequence_Async(uint16_t *data, uint16_t length) {
dma_setup_transfer(FSMC_DMA_DEV, FSMC_DMA_CHANNEL, data, DMA_SIZE_16BITS, &LCD->RAM, DMA_SIZE_16BITS, DMA_MEM_2_MEM | DMA_PINC_MODE);
dma_set_num_transfers(FSMC_DMA_DEV, FSMC_DMA_CHANNEL, length);
dma_clear_isr_bits(FSMC_DMA_DEV, FSMC_DMA_CHANNEL);
dma_enable(FSMC_DMA_DEV, FSMC_DMA_CHANNEL);
}
void LCD_IO_WaitSequence_Async() {
while ((dma_get_isr_bits(FSMC_DMA_DEV, FSMC_DMA_CHANNEL) & 0x0A) == 0) {};
dma_disable(FSMC_DMA_DEV, FSMC_DMA_CHANNEL);
}
#endif // LCD_USE_DMA_FSMC
#endif // HAS_GRAPHICAL_LCD
#endif // ARDUINO_ARCH_STM32F1 && FSMC_CS_PIN

View File

@ -0,0 +1,165 @@
/**
* 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/>.
*
*/
#ifdef __STM32F1__
#include "../../../inc/MarlinConfig.h"
#if HAS_GRAPHICAL_LCD && ENABLED(FORCE_SOFT_SPI)
#include "../HAL.h"
#include <U8glib.h>
#undef SPI_SPEED
#define SPI_SPEED 0 // Fastest
//#define SPI_SPEED 2 // Slower
static uint8_t SPI_speed = SPI_SPEED;
static inline uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, const pin_t miso_pin=-1) {
for (uint8_t i = 0; i < 8; i++) {
if (spi_speed == 0) {
WRITE(DOGLCD_MOSI, !!(b & 0x80));
WRITE(DOGLCD_SCK, HIGH);
b <<= 1;
if (miso_pin >= 0 && READ(miso_pin)) b |= 1;
WRITE(DOGLCD_SCK, LOW);
}
else {
const uint8_t state = (b & 0x80) ? HIGH : LOW;
for (uint8_t j = 0; j < spi_speed; j++)
WRITE(DOGLCD_MOSI, state);
for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); j++)
WRITE(DOGLCD_SCK, HIGH);
b <<= 1;
if (miso_pin >= 0 && READ(miso_pin)) b |= 1;
for (uint8_t j = 0; j < spi_speed; j++)
WRITE(DOGLCD_SCK, LOW);
}
}
return b;
}
static inline uint8_t swSpiTransfer_mode_3(uint8_t b, const uint8_t spi_speed, const pin_t miso_pin=-1) {
for (uint8_t i = 0; i < 8; i++) {
const uint8_t state = (b & 0x80) ? HIGH : LOW;
if (spi_speed == 0) {
WRITE(DOGLCD_SCK, LOW);
WRITE(DOGLCD_MOSI, state);
WRITE(DOGLCD_MOSI, state); // need some setup time
WRITE(DOGLCD_SCK, HIGH);
}
else {
for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); j++)
WRITE(DOGLCD_SCK, LOW);
for (uint8_t j = 0; j < spi_speed; j++)
WRITE(DOGLCD_MOSI, state);
for (uint8_t j = 0; j < spi_speed; j++)
WRITE(DOGLCD_SCK, HIGH);
}
b <<= 1;
if (miso_pin >= 0 && READ(miso_pin)) b |= 1;
}
return b;
}
static void u8g_sw_spi_HAL_STM32F1_shift_out(uint8_t val) {
#if ENABLED(FYSETC_MINI_12864)
swSpiTransfer_mode_3(val, SPI_speed);
#else
swSpiTransfer_mode_0(val, SPI_speed);
#endif
}
static uint8_t swSpiInit(const uint8_t spi_speed) {
#if PIN_EXISTS(LCD_RESET)
SET_OUTPUT(LCD_RESET_PIN);
#endif
SET_OUTPUT(DOGLCD_A0);
OUT_WRITE(DOGLCD_SCK, LOW);
OUT_WRITE(DOGLCD_MOSI, LOW);
OUT_WRITE(DOGLCD_CS, HIGH);
return spi_speed;
}
uint8_t u8g_com_HAL_STM32F1_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) {
switch (msg) {
case U8G_COM_MSG_INIT:
SPI_speed = swSpiInit(SPI_SPEED);
break;
case U8G_COM_MSG_STOP:
break;
case U8G_COM_MSG_RESET:
#if PIN_EXISTS(LCD_RESET)
WRITE(LCD_RESET_PIN, arg_val);
#endif
break;
case U8G_COM_MSG_CHIP_SELECT:
#if ENABLED(FYSETC_MINI_12864) // This LCD SPI is running mode 3 while SD card is running mode 0
if (arg_val) { // SCK idle state needs to be set to the proper idle state before
// the next chip select goes active
WRITE(DOGLCD_SCK, HIGH); // Set SCK to mode 3 idle state before CS goes active
WRITE(DOGLCD_CS, LOW);
}
else {
WRITE(DOGLCD_CS, HIGH);
WRITE(DOGLCD_SCK, LOW); // Set SCK to mode 0 idle state after CS goes inactive
}
#else
WRITE(DOGLCD_CS, !arg_val);
#endif
break;
case U8G_COM_MSG_WRITE_BYTE:
u8g_sw_spi_HAL_STM32F1_shift_out(arg_val);
break;
case U8G_COM_MSG_WRITE_SEQ: {
uint8_t *ptr = (uint8_t *)arg_ptr;
while (arg_val > 0) {
u8g_sw_spi_HAL_STM32F1_shift_out(*ptr++);
arg_val--;
}
} break;
case U8G_COM_MSG_WRITE_SEQ_P: {
uint8_t *ptr = (uint8_t *)arg_ptr;
while (arg_val > 0) {
u8g_sw_spi_HAL_STM32F1_shift_out(u8g_pgm_read(ptr));
ptr++;
arg_val--;
}
} break;
case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */
WRITE(DOGLCD_A0, arg_val);
break;
}
return 1;
}
#endif // HAS_GRAPHICAL_LCD
#endif // STM32F1

View File

@ -0,0 +1,95 @@
/**
* 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
/**
* Endstop interrupts for Libmaple STM32F1 based targets.
*
* On STM32F, all pins support external interrupt capability.
* Any pin can be used for external interrupts, but there are some restrictions.
* At most 16 different external interrupts can be used at one time.
* Further, you cant just pick any 16 pins to use. This is because every pin on the STM32
* connects to what is called an EXTI line, and only one pin per EXTI line can be used for external interrupts at a time
* Check the Reference Manual of the MCU to confirm which line is used by each pin
*/
/**
* Endstop Interrupts
*
* Without endstop interrupts the endstop pins must be polled continually in
* the temperature-ISR via endstops.update(), most of the time finding no change.
* With this feature endstops.update() is called only when we know that at
* least one endstop has changed state, saving valuable CPU cycles.
*
* This feature only works when all used endstop pins can generate an 'external interrupt'.
*
* Test whether pins issue interrupts on your board by flashing 'pin_interrupt_test.ino'.
* (Located in Marlin/buildroot/share/pin_interrupt_test/pin_interrupt_test.ino)
*/
#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); // assign it
#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,186 @@
/**
* 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 STM32F1
* These use GPIO functions instead of Direct Port Manipulation, as on AVR.
*/
#include <libmaple/gpio.h>
#define READ(IO) (PIN_MAP[IO].gpio_device->regs->IDR & (1U << PIN_MAP[IO].gpio_bit) ? HIGH : LOW)
#define WRITE(IO,V) (PIN_MAP[IO].gpio_device->regs->BSRR = (1U << PIN_MAP[IO].gpio_bit) << ((V) ? 0 : 16))
#define TOGGLE(IO) (PIN_MAP[IO].gpio_device->regs->ODR = PIN_MAP[IO].gpio_device->regs->ODR ^ (1U << PIN_MAP[IO].gpio_bit))
#define _GET_MODE(IO) gpio_get_mode(PIN_MAP[IO].gpio_device, PIN_MAP[IO].gpio_bit)
#define _SET_MODE(IO,M) gpio_set_mode(PIN_MAP[IO].gpio_device, PIN_MAP[IO].gpio_bit, M)
#define _SET_OUTPUT(IO) _SET_MODE(IO, GPIO_OUTPUT_PP)
#define _SET_OUTPUT_OD(IO) _SET_MODE(IO, GPIO_OUTPUT_OD)
#define OUT_WRITE(IO,V) do{ _SET_OUTPUT(IO); WRITE(IO,V); }while(0)
#define OUT_WRITE_OD(IO,V) do{ _SET_OUTPUT_OD(IO); WRITE(IO,V); }while(0)
#define SET_INPUT(IO) _SET_MODE(IO, GPIO_INPUT_FLOATING)
#define SET_INPUT_PULLUP(IO) _SET_MODE(IO, GPIO_INPUT_PU)
#define SET_INPUT_PULLDOWN(IO) _SET_MODE(IO, GPIO_INPUT_PD)
#define SET_OUTPUT(IO) OUT_WRITE(IO, LOW)
#define SET_PWM(IO) pinMode(IO, PWM) // do{ gpio_set_mode(PIN_MAP[pin].gpio_device, PIN_MAP[pin].gpio_bit, GPIO_AF_OUTPUT_PP); timer_set_mode(PIN_MAP[pin].timer_device, PIN_MAP[pin].timer_channel, TIMER_PWM); }while(0)
#define SET_PWM_OD(IO) pinMode(IO, PWM_OPEN_DRAIN)
#define IS_INPUT(IO) (_GET_MODE(IO) == GPIO_INPUT_FLOATING || _GET_MODE(IO) == GPIO_INPUT_ANALOG || _GET_MODE(IO) == GPIO_INPUT_PU || _GET_MODE(IO) == GPIO_INPUT_PD)
#define IS_OUTPUT(IO) (_GET_MODE(IO) == GPIO_OUTPUT_PP || _GET_MODE(IO) == GPIO_OUTPUT_OD)
#define PWM_PIN(IO) (PIN_MAP[IO].timer_device != nullptr)
// digitalRead/Write wrappers
#define extDigitalRead(IO) digitalRead(IO)
#define extDigitalWrite(IO,V) digitalWrite(IO,V)
//
// Pins Definitions
//
#define PA0 0x00
#define PA1 0x01
#define PA2 0x02
#define PA3 0x03
#define PA4 0x04
#define PA5 0x05
#define PA6 0x06
#define PA7 0x07
#define PA8 0x08
#define PA9 0x09
#define PA10 0x0A
#define PA11 0x0B
#define PA12 0x0C
#define PA13 0x0D
#define PA14 0x0E
#define PA15 0x0F
#define PB0 0x10
#define PB1 0x11
#define PB2 0x12
#define PB3 0x13
#define PB4 0x14
#define PB5 0x15
#define PB6 0x16
#define PB7 0x17 // 36 pins (F103T)
#define PB8 0x18
#define PB9 0x19
#define PB10 0x1A
#define PB11 0x1B
#define PB12 0x1C
#define PB13 0x1D
#define PB14 0x1E
#define PB15 0x1F
#if defined(MCU_STM32F103CB) || defined(MCU_STM32F103C8)
#define PC13 0x20
#define PC14 0x21
#define PC15 0x22
#else
#define PC0 0x20
#define PC1 0x21
#define PC2 0x22
#define PC3 0x23
#define PC4 0x24
#define PC5 0x25
#define PC6 0x26
#define PC7 0x27
#define PC8 0x28
#define PC9 0x29
#define PC10 0x2A
#define PC11 0x2B
#define PC12 0x2C
#define PC13 0x2D
#define PC14 0x2E
#define PC15 0x2F
#endif
#define PD0 0x30
#define PD1 0x31
#define PD2 0x32 // 64 pins (F103R)
#define PD3 0x33
#define PD4 0x34
#define PD5 0x35
#define PD6 0x36
#define PD7 0x37
#define PD8 0x38
#define PD9 0x39
#define PD10 0x3A
#define PD11 0x3B
#define PD12 0x3C
#define PD13 0x3D
#define PD14 0x3E
#define PD15 0x3F
#define PE0 0x40
#define PE1 0x41
#define PE2 0x42
#define PE3 0x43
#define PE4 0x44
#define PE5 0x45
#define PE6 0x46
#define PE7 0x47
#define PE8 0x48
#define PE9 0x49
#define PE10 0x4A
#define PE11 0x4B
#define PE12 0x4C
#define PE13 0x4D
#define PE14 0x4E
#define PE15 0x4F // 100 pins (F103V)
#define PF0 0x50
#define PF1 0x51
#define PF2 0x52
#define PF3 0x53
#define PF4 0x54
#define PF5 0x55
#define PF6 0x56
#define PF7 0x57
#define PF8 0x58
#define PF9 0x59
#define PF10 0x5A
#define PF11 0x5B
#define PF12 0x5C
#define PF13 0x5D
#define PF14 0x5E
#define PF15 0x5F
#define PG0 0x60
#define PG1 0x61
#define PG2 0x62
#define PG3 0x63
#define PG4 0x64
#define PG5 0x65
#define PG6 0x66
#define PG7 0x67
#define PG8 0x68
#define PG9 0x69
#define PG10 0x6A
#define PG11 0x6B
#define PG12 0x6C
#define PG13 0x6D
#define PG14 0x6E
#define PG15 0x6F // 144 pins (F103Z)

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,43 @@
/**
* 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 STM32F1-specific configuration values for errors at compile-time.
*/
#if ENABLED(EMERGENCY_PARSER)
#error "EMERGENCY_PARSER is not yet implemented for STM32F1. Disable EMERGENCY_PARSER to continue."
#endif
#if ENABLED(SDIO_SUPPORT) && DISABLED(SDSUPPORT)
#error "SDIO_SUPPORT requires SDSUPPORT. Enable SDSUPPORT to continue."
#endif
#if ENABLED(FAST_PWM_FAN)
#error "FAST_PWM_FAN is not yet implemented for this platform."
#endif
#if !defined(HAVE_SW_SERIAL) && HAS_TMC_SW_SERIAL
#warning "With TMC2208/9 consider using SoftwareSerialM with HAVE_SW_SERIAL and appropriate SS_TIMER."
#error "Missing SoftwareSerial implementation."
#endif

View File

@ -0,0 +1,56 @@
;
; STMicroelectronics Communication Device Class driver installation file
; (C)2006 Copyright STMicroelectronics
;
[Version]
Signature="$Windows NT$"
Class=Ports
ClassGuid={4D36E978-E325-11CE-BFC1-08002BE10318}
Provider=%STM%
LayoutFile=layout.inf
[Manufacturer]
%MFGNAME%=VirComDevice,NT,NTamd64
[DestinationDirs]
DefaultDestDir = 12
[VirComDevice.NT]
%DESCRIPTION%=DriverInstall,USB\VID_1EAF&PID_0029&MI_01
%DESCRIPTION%=DriverInstall,USB\VID_1EAF&PID_0029&MI_01
[VirComDevice.NTamd64]
%DESCRIPTION%=DriverInstall,USB\VID_1EAF&PID_0029&MI_01
%DESCRIPTION%=DriverInstall,USB\VID_1EAF&PID_0029&MI_01
[DriverInstall.NT]
Include=mdmcpq.inf
CopyFiles=FakeModemCopyFileSection
AddReg=DriverInstall.NT.AddReg
[DriverInstall.NT.AddReg]
HKR,,DevLoader,,*ntkern
HKR,,NTMPDriver,,usbser.sys
HKR,,EnumPropPages32,,"MsPorts.dll,SerialPortPropPageProvider"
[DriverInstall.NT.Services]
AddService=usbser, 0x00000002, DriverServiceInst
[DriverServiceInst]
DisplayName=%SERVICE%
ServiceType=1
StartType=3
ErrorControl=1
ServiceBinary=%12%\usbser.sys
;------------------------------------------------------------------------------
; String Definitions
;------------------------------------------------------------------------------
[Strings]
STM = "LeafLabs"
MFGNAME = "LeafLabs"
DESCRIPTION = "Maple R3"
SERVICE = "USB Virtual COM port"

View File

@ -0,0 +1,64 @@
/**
* Marlin 3D Printer Firmware
*
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
* Copyright (c) 2019 BigTreeTech [https://github.com/bigtreetech]
*
* 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.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifdef USE_USB_COMPOSITE
#include "msc_sd.h"
#include "SPI.h"
#define PRODUCT_ID 0x29
USBMassStorage MarlinMSC;
USBCompositeSerial MarlinCompositeSerial;
#include "../../inc/MarlinConfig.h"
#ifdef HAS_ONBOARD_SD
#include "onboard_sd.h"
static bool MSC_Write(const uint8_t *writebuff, uint32_t startSector, uint16_t numSectors) {
return (disk_write(0, writebuff, startSector, numSectors) == RES_OK);
}
static bool MSC_Read(uint8_t *readbuff, uint32_t startSector, uint16_t numSectors) {
return (disk_read(0, readbuff, startSector, numSectors) == RES_OK);
}
#endif
void MSC_SD_init() {
USBComposite.setProductId(PRODUCT_ID);
// Just set MarlinCompositeSerial enabled to true
// because when MarlinCompositeSerial.begin() is used in setup()
// it clears all USBComposite devices.
MarlinCompositeSerial.begin();
USBComposite.end();
USBComposite.clear();
// Set api and register mass storage
#ifdef HAS_ONBOARD_SD
uint32_t cardSize;
if (disk_initialize(0) == RES_OK) {
if (disk_ioctl(0, GET_SECTOR_COUNT, (void *)(&cardSize)) == RES_OK) {
MarlinMSC.setDriveData(0, cardSize, MSC_Read, MSC_Write);
MarlinMSC.registerComponent();
}
}
#endif
// Register composite Serial
MarlinCompositeSerial.registerComponent();
USBComposite.begin();
}
#endif // USE_USB_COMPOSITE

View File

@ -0,0 +1,23 @@
/**
* Marlin 3D Printer Firmware
*
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
* Copyright (c) 2019 BigTreeTech [https://github.com/bigtreetech]
*
* 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.
*
* 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 <USBComposite.h>
extern USBMassStorage MarlinMSC;
extern USBCompositeSerial MarlinCompositeSerial;
void MSC_SD_init();

View File

@ -0,0 +1,556 @@
/**
* STM32F1: MMCv3/SDv1/SDv2 (SPI mode) control module
*
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
* Copyright (c) 2019 BigTreeTech [https://github.com/bigtreetech]
* Copyright (C) 2015, ChaN, all right reserved.
*
* This software is a free software and there is NO WARRANTY.
* No restriction on use. You can use, modify and redistribute it for
* personal, non-profit or commercial products UNDER YOUR RESPONSIBILITY.
* Redistributions of source code must retain the above copyright notice.
*
*/
#include "../../inc/MarlinConfig.h"
#ifdef HAS_ONBOARD_SD
#include "onboard_sd.h"
#include "SPI.h"
#include "fastio.h"
#ifdef SHARED_SD_CARD
#ifndef ON_BOARD_SPI_DEVICE
#define ON_BOARD_SPI_DEVICE SPI_DEVICE
#endif
#define ONBOARD_SD_SPI SPI
#else
SPIClass OnBoardSPI(ON_BOARD_SPI_DEVICE);
#define ONBOARD_SD_SPI OnBoardSPI
#endif
#if ON_BOARD_SPI_DEVICE == 1
#define SPI_CLOCK_MAX SPI_BAUD_PCLK_DIV_4
#else
#define SPI_CLOCK_MAX SPI_BAUD_PCLK_DIV_2
#endif
#define CS_LOW() WRITE(ONBOARD_SD_CS_PIN, LOW) /* Set OnBoardSPI cs low */
#define CS_HIGH() WRITE(ONBOARD_SD_CS_PIN, HIGH) /* Set OnBoardSPI cs high */
#define FCLK_FAST() ONBOARD_SD_SPI.setClockDivider(SPI_CLOCK_MAX)
#define FCLK_SLOW() ONBOARD_SD_SPI.setClockDivider(SPI_BAUD_PCLK_DIV_256)
/*--------------------------------------------------------------------------
Module Private Functions
---------------------------------------------------------------------------*/
/* MMC/SD command */
#define CMD0 (0) /* GO_IDLE_STATE */
#define CMD1 (1) /* SEND_OP_COND (MMC) */
#define ACMD41 (0x80+41) /* SEND_OP_COND (SDC) */
#define CMD8 (8) /* SEND_IF_COND */
#define CMD9 (9) /* SEND_CSD */
#define CMD10 (10) /* SEND_CID */
#define CMD12 (12) /* STOP_TRANSMISSION */
#define ACMD13 (0x80+13) /* SD_STATUS (SDC) */
#define CMD16 (16) /* SET_BLOCKLEN */
#define CMD17 (17) /* READ_SINGLE_BLOCK */
#define CMD18 (18) /* READ_MULTIPLE_BLOCK */
#define CMD23 (23) /* SET_BLOCK_COUNT (MMC) */
#define ACMD23 (0x80+23) /* SET_WR_BLK_ERASE_COUNT (SDC) */
#define CMD24 (24) /* WRITE_BLOCK */
#define CMD25 (25) /* WRITE_MULTIPLE_BLOCK */
#define CMD32 (32) /* ERASE_ER_BLK_START */
#define CMD33 (33) /* ERASE_ER_BLK_END */
#define CMD38 (38) /* ERASE */
#define CMD48 (48) /* READ_EXTR_SINGLE */
#define CMD49 (49) /* WRITE_EXTR_SINGLE */
#define CMD55 (55) /* APP_CMD */
#define CMD58 (58) /* READ_OCR */
static volatile DSTATUS Stat = STA_NOINIT; /* Physical drive status */
static volatile UINT timeout;
static BYTE CardType; /* Card type flags */
/*-----------------------------------------------------------------------*/
/* Send/Receive data to the MMC (Platform dependent) */
/*-----------------------------------------------------------------------*/
/* Exchange a byte */
static BYTE xchg_spi (
BYTE dat /* Data to send */
) {
BYTE returnByte = ONBOARD_SD_SPI.transfer(dat);
return returnByte;
}
/* Receive multiple byte */
static void rcvr_spi_multi (
BYTE *buff, /* Pointer to data buffer */
UINT btr /* Number of bytes to receive (16, 64 or 512) */
) {
ONBOARD_SD_SPI.dmaTransfer(0, const_cast<uint8_t*>(buff), btr);
}
#if _DISKIO_WRITE
/* Send multiple bytes */
static void xmit_spi_multi (
const BYTE *buff, /* Pointer to the data */
UINT btx /* Number of bytes to send (multiple of 16) */
) {
ONBOARD_SD_SPI.dmaSend(const_cast<uint8_t*>(buff), btx);
}
#endif // _DISKIO_WRITE
/*-----------------------------------------------------------------------*/
/* Wait for card ready */
/*-----------------------------------------------------------------------*/
static int wait_ready ( /* 1:Ready, 0:Timeout */
UINT wt /* Timeout [ms] */
) {
BYTE d;
timeout = millis() + wt;
do {
d = xchg_spi(0xFF);
/* This loop takes a while. Insert rot_rdq() here for multitask environment. */
} while (d != 0xFF && (timeout > millis())); /* Wait for card goes ready or timeout */
return (d == 0xFF) ? 1 : 0;
}
/*-----------------------------------------------------------------------*/
/* Deselect card and release SPI */
/*-----------------------------------------------------------------------*/
static void deselect() {
CS_HIGH(); /* CS = H */
xchg_spi(0xFF); /* Dummy clock (force DO hi-z for multiple slave SPI) */
}
/*-----------------------------------------------------------------------*/
/* Select card and wait for ready */
/*-----------------------------------------------------------------------*/
static int select() { /* 1:OK, 0:Timeout */
CS_LOW(); /* CS = L */
xchg_spi(0xFF); /* Dummy clock (force DO enabled) */
if (wait_ready(500)) return 1; /* Leading busy check: Wait for card ready */
deselect(); /* Timeout */
return 0;
}
/*-----------------------------------------------------------------------*/
/* Control SPI module (Platform dependent) */
/*-----------------------------------------------------------------------*/
static void power_on() { /* Enable SSP module and attach it to I/O pads */
ONBOARD_SD_SPI.setModule(ON_BOARD_SPI_DEVICE);
ONBOARD_SD_SPI.begin();
ONBOARD_SD_SPI.setBitOrder(MSBFIRST);
ONBOARD_SD_SPI.setDataMode(SPI_MODE0);
OUT_WRITE(ONBOARD_SD_CS_PIN, HIGH); /* Set CS# high */
}
static void power_off() { /* Disable SPI function */
select(); /* Wait for card ready */
deselect();
}
/*-----------------------------------------------------------------------*/
/* Receive a data packet from the MMC */
/*-----------------------------------------------------------------------*/
static int rcvr_datablock ( /* 1:OK, 0:Error */
BYTE *buff, /* Data buffer */
UINT btr /* Data block length (byte) */
) {
BYTE token;
timeout = millis() + 200;
do { /* Wait for DataStart token in timeout of 200ms */
token = xchg_spi(0xFF);
/* This loop will take a while. Insert rot_rdq() here for multitask environment. */
} while ((token == 0xFF) && (timeout > millis()));
if (token != 0xFE) return 0; /* Function fails if invalid DataStart token or timeout */
rcvr_spi_multi(buff, btr); /* Store trailing data to the buffer */
xchg_spi(0xFF); xchg_spi(0xFF); /* Discard CRC */
return 1; /* Function succeeded */
}
/*-----------------------------------------------------------------------*/
/* Send a data packet to the MMC */
/*-----------------------------------------------------------------------*/
#if _DISKIO_WRITE
static int xmit_datablock ( /* 1:OK, 0:Failed */
const BYTE *buff, /* Ponter to 512 byte data to be sent */
BYTE token /* Token */
) {
BYTE resp;
if (!wait_ready(500)) return 0; /* Leading busy check: Wait for card ready to accept data block */
xchg_spi(token); /* Send token */
if (token == 0xFD) return 1; /* Do not send data if token is StopTran */
xmit_spi_multi(buff, 512); /* Data */
xchg_spi(0xFF); xchg_spi(0xFF); /* Dummy CRC */
resp = xchg_spi(0xFF); /* Receive data resp */
return (resp & 0x1F) == 0x05 ? 1 : 0; /* Data was accepted or not */
/* Busy check is done at next transmission */
}
#endif // _DISKIO_WRITE
/*-----------------------------------------------------------------------*/
/* Send a command packet to the MMC */
/*-----------------------------------------------------------------------*/
static BYTE send_cmd ( /* Return value: R1 resp (bit7==1:Failed to send) */
BYTE cmd, /* Command index */
DWORD arg /* Argument */
) {
BYTE n, res;
if (cmd & 0x80) { /* Send a CMD55 prior to ACMD<n> */
cmd &= 0x7F;
res = send_cmd(CMD55, 0);
if (res > 1) return res;
}
/* Select the card and wait for ready except to stop multiple block read */
if (cmd != CMD12) {
deselect();
if (!select()) return 0xFF;
}
/* Send command packet */
xchg_spi(0x40 | cmd); /* Start + command index */
xchg_spi((BYTE)(arg >> 24)); /* Argument[31..24] */
xchg_spi((BYTE)(arg >> 16)); /* Argument[23..16] */
xchg_spi((BYTE)(arg >> 8)); /* Argument[15..8] */
xchg_spi((BYTE)arg); /* Argument[7..0] */
n = 0x01; /* Dummy CRC + Stop */
if (cmd == CMD0) n = 0x95; /* Valid CRC for CMD0(0) */
if (cmd == CMD8) n = 0x87; /* Valid CRC for CMD8(0x1AA) */
xchg_spi(n);
/* Receive command resp */
if (cmd == CMD12) xchg_spi(0xFF); /* Diacard following one byte when CMD12 */
n = 10; /* Wait for response (10 bytes max) */
do
res = xchg_spi(0xFF);
while ((res & 0x80) && --n);
return res; /* Return received response */
}
/*--------------------------------------------------------------------------
Public Functions
---------------------------------------------------------------------------*/
/*-----------------------------------------------------------------------*/
/* Initialize disk drive */
/*-----------------------------------------------------------------------*/
DSTATUS disk_initialize (
BYTE drv /* Physical drive number (0) */
) {
BYTE n, cmd, ty, ocr[4];
if (drv) return STA_NOINIT; /* Supports only drive 0 */
power_on(); /* Initialize SPI */
if (Stat & STA_NODISK) return Stat; /* Is a card existing in the soket? */
FCLK_SLOW();
for (n = 10; n; n--) xchg_spi(0xFF); /* Send 80 dummy clocks */
ty = 0;
if (send_cmd(CMD0, 0) == 1) { /* Put the card SPI state */
timeout = millis() + 1000; /* Initialization timeout = 1 sec */
if (send_cmd(CMD8, 0x1AA) == 1) { /* Is the catd SDv2? */
for (n = 0; n < 4; n++) ocr[n] = xchg_spi(0xFF); /* Get 32 bit return value of R7 resp */
if (ocr[2] == 0x01 && ocr[3] == 0xAA) { /* Does the card support 2.7-3.6V? */
while ((timeout > millis()) && send_cmd(ACMD41, 1UL << 30)) ; /* Wait for end of initialization with ACMD41(HCS) */
if ((timeout > millis()) && send_cmd(CMD58, 0) == 0) { /* Check CCS bit in the OCR */
for (n = 0; n < 4; n++) ocr[n] = xchg_spi(0xFF);
ty = (ocr[0] & 0x40) ? CT_SD2 | CT_BLOCK : CT_SD2; /* Check if the card is SDv2 */
}
}
} else { /* Not an SDv2 card */
if (send_cmd(ACMD41, 0) <= 1) { /* SDv1 or MMCv3? */
ty = CT_SD1; cmd = ACMD41; /* SDv1 (ACMD41(0)) */
} else {
ty = CT_MMC; cmd = CMD1; /* MMCv3 (CMD1(0)) */
}
while ((timeout > millis()) && send_cmd(cmd, 0)) ; /* Wait for the card leaves idle state */
if (!(timeout > millis()) || send_cmd(CMD16, 512) != 0) /* Set block length: 512 */
ty = 0;
}
}
CardType = ty; /* Card type */
deselect();
if (ty) { /* OK */
FCLK_FAST(); /* Set fast clock */
Stat &= ~STA_NOINIT; /* Clear STA_NOINIT flag */
} else { /* Failed */
power_off();
Stat = STA_NOINIT;
}
return Stat;
}
/*-----------------------------------------------------------------------*/
/* Get disk status */
/*-----------------------------------------------------------------------*/
DSTATUS disk_status (
BYTE drv /* Physical drive number (0) */
) {
if (drv) return STA_NOINIT; /* Supports only drive 0 */
return Stat; /* Return disk status */
}
/*-----------------------------------------------------------------------*/
/* Read sector(s) */
/*-----------------------------------------------------------------------*/
DRESULT disk_read (
BYTE drv, /* Physical drive number (0) */
BYTE *buff, /* Pointer to the data buffer to store read data */
DWORD sector, /* Start sector number (LBA) */
UINT count /* Number of sectors to read (1..128) */
) {
BYTE cmd;
if (drv || !count) return RES_PARERR; /* Check parameter */
if (Stat & STA_NOINIT) return RES_NOTRDY; /* Check if drive is ready */
if (!(CardType & CT_BLOCK)) sector *= 512; /* LBA ot BA conversion (byte addressing cards) */
FCLK_FAST();
cmd = count > 1 ? CMD18 : CMD17; /* READ_MULTIPLE_BLOCK : READ_SINGLE_BLOCK */
if (send_cmd(cmd, sector) == 0) {
do {
if (!rcvr_datablock(buff, 512)) break;
buff += 512;
} while (--count);
if (cmd == CMD18) send_cmd(CMD12, 0); /* STOP_TRANSMISSION */
}
deselect();
return count ? RES_ERROR : RES_OK; /* Return result */
}
/*-----------------------------------------------------------------------*/
/* Write sector(s) */
/*-----------------------------------------------------------------------*/
#if _DISKIO_WRITE
DRESULT disk_write(
BYTE drv, /* Physical drive number (0) */
const BYTE *buff, /* Ponter to the data to write */
DWORD sector, /* Start sector number (LBA) */
UINT count /* Number of sectors to write (1..128) */
) {
if (drv || !count) return RES_PARERR; /* Check parameter */
if (Stat & STA_NOINIT) return RES_NOTRDY; /* Check drive status */
if (Stat & STA_PROTECT) return RES_WRPRT; /* Check write protect */
FCLK_FAST();
if (!(CardType & CT_BLOCK)) sector *= 512; /* LBA ==> BA conversion (byte addressing cards) */
if (count == 1) { /* Single sector write */
if ((send_cmd(CMD24, sector) == 0) /* WRITE_BLOCK */
&& xmit_datablock(buff, 0xFE)) {
count = 0;
}
}
else { /* Multiple sector write */
if (CardType & CT_SDC) send_cmd(ACMD23, count); /* Predefine number of sectors */
if (send_cmd(CMD25, sector) == 0) { /* WRITE_MULTIPLE_BLOCK */
do {
if (!xmit_datablock(buff, 0xFC)) break;
buff += 512;
} while (--count);
if (!xmit_datablock(0, 0xFD)) count = 1; /* STOP_TRAN token */
}
}
deselect();
return count ? RES_ERROR : RES_OK; /* Return result */
}
#endif // _DISKIO_WRITE
/*-----------------------------------------------------------------------*/
/* Miscellaneous drive controls other than data read/write */
/*-----------------------------------------------------------------------*/
#if _DISKIO_IOCTL
DRESULT disk_ioctl (
BYTE drv, /* Physical drive number (0) */
BYTE cmd, /* Control command code */
void *buff /* Pointer to the conrtol data */
) {
DRESULT res;
BYTE n, csd[16], *ptr = (BYTE *)buff;
DWORD *dp, st, ed, csize;
#if _DISKIO_ISDIO
SDIO_CMD *sdio = buff;
BYTE rc, *buf;
UINT dc;
#endif
if (drv) return RES_PARERR; /* Check parameter */
if (Stat & STA_NOINIT) return RES_NOTRDY; /* Check if drive is ready */
res = RES_ERROR;
FCLK_FAST();
switch (cmd) {
case CTRL_SYNC: /* Wait for end of internal write process of the drive */
if (select()) res = RES_OK;
break;
case GET_SECTOR_COUNT: /* Get drive capacity in unit of sector (DWORD) */
if ((send_cmd(CMD9, 0) == 0) && rcvr_datablock(csd, 16)) {
if ((csd[0] >> 6) == 1) { /* SDC ver 2.00 */
csize = csd[9] + ((WORD)csd[8] << 8) + ((DWORD)(csd[7] & 63) << 16) + 1;
*(DWORD*)buff = csize << 10;
} else { /* SDC ver 1.XX or MMC ver 3 */
n = (csd[5] & 15) + ((csd[10] & 128) >> 7) + ((csd[9] & 3) << 1) + 2;
csize = (csd[8] >> 6) + ((WORD)csd[7] << 2) + ((WORD)(csd[6] & 3) << 10) + 1;
*(DWORD*)buff = csize << (n - 9);
}
res = RES_OK;
}
break;
case GET_BLOCK_SIZE: /* Get erase block size in unit of sector (DWORD) */
if (CardType & CT_SD2) { /* SDC ver 2.00 */
if (send_cmd(ACMD13, 0) == 0) { /* Read SD status */
xchg_spi(0xFF);
if (rcvr_datablock(csd, 16)) { /* Read partial block */
for (n = 64 - 16; n; n--) xchg_spi(0xFF); /* Purge trailing data */
*(DWORD*)buff = 16UL << (csd[10] >> 4);
res = RES_OK;
}
}
} else { /* SDC ver 1.XX or MMC */
if ((send_cmd(CMD9, 0) == 0) && rcvr_datablock(csd, 16)) { /* Read CSD */
if (CardType & CT_SD1) { /* SDC ver 1.XX */
*(DWORD*)buff = (((csd[10] & 63) << 1) + ((WORD)(csd[11] & 128) >> 7) + 1) << ((csd[13] >> 6) - 1);
} else { /* MMC */
*(DWORD*)buff = ((WORD)((csd[10] & 124) >> 2) + 1) * (((csd[11] & 3) << 3) + ((csd[11] & 224) >> 5) + 1);
}
res = RES_OK;
}
}
break;
case CTRL_TRIM: /* Erase a block of sectors (used when _USE_TRIM in ffconf.h is 1) */
if (!(CardType & CT_SDC)) break; /* Check if the card is SDC */
if (disk_ioctl(drv, MMC_GET_CSD, csd)) break; /* Get CSD */
if (!(csd[0] >> 6) && !(csd[10] & 0x40)) break; /* Check if sector erase can be applied to the card */
dp = (DWORD *)buff; st = dp[0]; ed = dp[1]; /* Load sector block */
if (!(CardType & CT_BLOCK)) {
st *= 512; ed *= 512;
}
if (send_cmd(CMD32, st) == 0 && send_cmd(CMD33, ed) == 0 && send_cmd(CMD38, 0) == 0 && wait_ready(30000)) { /* Erase sector block */
res = RES_OK; /* FatFs does not check result of this command */
}
break;
/* Following commands are never used by FatFs module */
case MMC_GET_TYPE: /* Get MMC/SDC type (BYTE) */
*ptr = CardType;
res = RES_OK;
break;
case MMC_GET_CSD: /* Read CSD (16 bytes) */
if (send_cmd(CMD9, 0) == 0 && rcvr_datablock(ptr, 16)) { /* READ_CSD */
res = RES_OK;
}
break;
case MMC_GET_CID: /* Read CID (16 bytes) */
if (send_cmd(CMD10, 0) == 0 && rcvr_datablock(ptr, 16)) { /* READ_CID */
res = RES_OK;
}
break;
case MMC_GET_OCR: /* Read OCR (4 bytes) */
if (send_cmd(CMD58, 0) == 0) { /* READ_OCR */
for (n = 4; n; n--) *ptr++ = xchg_spi(0xFF);
res = RES_OK;
}
break;
case MMC_GET_SDSTAT: /* Read SD status (64 bytes) */
if (send_cmd(ACMD13, 0) == 0) { /* SD_STATUS */
xchg_spi(0xFF);
if (rcvr_datablock(ptr, 64)) res = RES_OK;
}
break;
#if _DISKIO_ISDIO
case ISDIO_READ:
sdio = buff;
if (send_cmd(CMD48, 0x80000000 | sdio->func << 28 | sdio->addr << 9 | ((sdio->ndata - 1) & 0x1FF)) == 0) {
for (Timer1 = 1000; (rc = xchg_spi(0xFF)) == 0xFF && Timer1; ) ;
if (rc == 0xFE) {
for (buf = sdio->data, dc = sdio->ndata; dc; dc--) *buf++ = xchg_spi(0xFF);
for (dc = 514 - sdio->ndata; dc; dc--) xchg_spi(0xFF);
res = RES_OK;
}
}
break;
case ISDIO_WRITE:
sdio = buff;
if (send_cmd(CMD49, 0x80000000 | sdio->func << 28 | sdio->addr << 9 | ((sdio->ndata - 1) & 0x1FF)) == 0) {
xchg_spi(0xFF); xchg_spi(0xFE);
for (buf = sdio->data, dc = sdio->ndata; dc; dc--) xchg_spi(*buf++);
for (dc = 514 - sdio->ndata; dc; dc--) xchg_spi(0xFF);
if ((xchg_spi(0xFF) & 0x1F) == 0x05) res = RES_OK;
}
break;
case ISDIO_MRITE:
sdio = buff;
if (send_cmd(CMD49, 0x84000000 | sdio->func << 28 | sdio->addr << 9 | sdio->ndata >> 8) == 0) {
xchg_spi(0xFF); xchg_spi(0xFE);
xchg_spi(sdio->ndata);
for (dc = 513; dc; dc--) xchg_spi(0xFF);
if ((xchg_spi(0xFF) & 0x1F) == 0x05) res = RES_OK;
}
break;
#endif // _DISKIO_ISDIO
default: res = RES_PARERR;
}
deselect();
return res;
}
#endif // _DISKIO_IOCTL
#endif // HAS_ONBOARD_SD

View File

@ -0,0 +1,96 @@
/*-----------------------------------------------------------------------
/ * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
/ * Copyright (c) 2019 BigTreeTech [https://github.com/bigtreetech]
/ * Low level disk interface module include file (C)ChaN, 2015
/-----------------------------------------------------------------------*/
#pragma once
#define _DISKIO_WRITE 1 /* 1: Enable disk_write function */
#define _DISKIO_IOCTL 1 /* 1: Enable disk_ioctl fucntion */
#define _DISKIO_ISDIO 0 /* 1: Enable iSDIO control fucntion */
typedef unsigned char BYTE;
typedef unsigned short WORD;
typedef unsigned long DWORD;
typedef unsigned int UINT;
/* Status of Disk Functions */
typedef BYTE DSTATUS;
/* Results of Disk Functions */
typedef enum {
RES_OK = 0, /* 0: Successful */
RES_ERROR, /* 1: R/W Error */
RES_WRPRT, /* 2: Write Protected */
RES_NOTRDY, /* 3: Not Ready */
RES_PARERR /* 4: Invalid Parameter */
} DRESULT;
#if _DISKIO_ISDIO
/* Command structure for iSDIO ioctl command */
typedef struct {
BYTE func; /* Function number: 0..7 */
WORD ndata; /* Number of bytes to transfer: 1..512, or mask + data */
DWORD addr; /* Register address: 0..0x1FFFF */
void* data; /* Pointer to the data (to be written | read buffer) */
} SDIO_CMD;
#endif
/*---------------------------------------*/
/* Prototypes for disk control functions */
DSTATUS disk_initialize(BYTE pdrv);
DSTATUS disk_status(BYTE pdrv);
DRESULT disk_read(BYTE pdrv, BYTE* buff, DWORD sector, UINT count);
#if _DISKIO_WRITE
DRESULT disk_write(BYTE pdrv, const BYTE* buff, DWORD sector, UINT count);
#endif
#if _DISKIO_IOCTL
DRESULT disk_ioctl(BYTE pdrv, BYTE cmd, void* buff);
#endif
/* Disk Status Bits (DSTATUS) */
#define STA_NOINIT 0x01 /* Drive not initialized */
#define STA_NODISK 0x02 /* No medium in the drive */
#define STA_PROTECT 0x04 /* Write protected */
/* Command code for disk_ioctrl fucntion */
/* Generic command (Used by FatFs) */
#define CTRL_SYNC 0 /* Complete pending write process (needed at _FS_READONLY == 0) */
#define GET_SECTOR_COUNT 1 /* Get media size (needed at _USE_MKFS == 1) */
#define GET_SECTOR_SIZE 2 /* Get sector size (needed at _MAX_SS != _MIN_SS) */
#define GET_BLOCK_SIZE 3 /* Get erase block size (needed at _USE_MKFS == 1) */
#define CTRL_TRIM 4 /* Inform device that the data on the block of sectors is no longer used (needed at _USE_TRIM == 1) */
/* Generic command (Not used by FatFs) */
#define CTRL_FORMAT 5 /* Create physical format on the media */
#define CTRL_POWER_IDLE 6 /* Put the device idle state */
#define CTRL_POWER_OFF 7 /* Put the device off state */
#define CTRL_LOCK 8 /* Lock media removal */
#define CTRL_UNLOCK 9 /* Unlock media removal */
#define CTRL_EJECT 10 /* Eject media */
/* MMC/SDC specific ioctl command (Not used by FatFs) */
#define MMC_GET_TYPE 50 /* Get card type */
#define MMC_GET_CSD 51 /* Get CSD */
#define MMC_GET_CID 52 /* Get CID */
#define MMC_GET_OCR 53 /* Get OCR */
#define MMC_GET_SDSTAT 54 /* Get SD status */
#define ISDIO_READ 55 /* Read data form SD iSDIO register */
#define ISDIO_WRITE 56 /* Write data to SD iSDIO register */
#define ISDIO_MRITE 57 /* Masked write data to SD iSDIO register */
/* ATA/CF specific ioctl command (Not used by FatFs) */
#define ATA_GET_REV 60 /* Get F/W revision */
#define ATA_GET_MODEL 61 /* Get model name */
#define ATA_GET_SN 62 /* Get serial number */
/* MMC card type flags (MMC_GET_TYPE) */
#define CT_MMC 0x01 /* MMC ver 3 */
#define CT_SD1 0x02 /* SD ver 1 */
#define CT_SD2 0x04 /* SD ver 2 */
#define CT_SDC (CT_SD1|CT_SD2) /* SD */
#define CT_BLOCK 0x08 /* Block addressing */

View File

@ -0,0 +1,77 @@
/**
* 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/>.
*
*/
#ifdef __STM32F1__
#include "../../inc/MarlinConfig.h"
#if USE_REAL_EEPROM
#include "../shared/persistent_store_api.h"
bool PersistentStore::access_start() {
#if ENABLED(SPI_EEPROM)
#if SPI_CHAN_EEPROM1 == 1
SET_OUTPUT(BOARD_SPI1_SCK_PIN);
SET_OUTPUT(BOARD_SPI1_MOSI_PIN);
SET_INPUT(BOARD_SPI1_MISO_PIN);
SET_OUTPUT(SPI_EEPROM1_CS);
#endif
spiInit(0);
#endif
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 * const p = (uint8_t * const)pos;
uint8_t v = *value;
// EEPROM has only ~100,000 write cycles,
// so only write bytes that have changed!
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;
}
}
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 {
uint8_t c = eeprom_read_byte((uint8_t*)pos);
if (writing && value) *value = c;
crc16(crc, &c, 1);
pos++;
value++;
} while (--size);
return false;
}
size_t PersistentStore::capacity() { return E2END + 1; }
#endif // USE_REAL_EEPROM
#endif // __STM32F1__

View File

@ -0,0 +1,112 @@
/**
* 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/>.
*
*/
/**
* persistent_store_flash.cpp
* HAL for stm32duino and compatible (STM32F1)
* Implementation of EEPROM settings in SDCard
*/
#ifdef __STM32F1__
#include "../../inc/MarlinConfig.h"
// This is for EEPROM emulation in flash
#if BOTH(EEPROM_SETTINGS, FLASH_EEPROM_EMULATION)
#include "../shared/persistent_store_api.h"
#include <flash_stm32.h>
#include <EEPROM.h>
// Store settings in the last two pages
#define EEPROM_SIZE (EEPROM_PAGE_SIZE * 2)
#define ACCESS_FINISHED(TF) do{ FLASH_Lock(); eeprom_dirty = false; return TF; }while(0)
static uint8_t ram_eeprom[EEPROM_SIZE] __attribute__((aligned(4))) = {0};
static bool eeprom_dirty = false;
bool PersistentStore::access_start() {
const uint32_t* source = reinterpret_cast<const uint32_t*>(EEPROM_PAGE0_BASE);
uint32_t* destination = reinterpret_cast<uint32_t*>(ram_eeprom);
static_assert(0 == EEPROM_SIZE % 4, "EEPROM_SIZE is corrupted. (Must be a multiple of 4.)"); // Ensure copying as uint32_t is safe
constexpr size_t eeprom_size_u32 = EEPROM_SIZE / 4;
for (size_t i = 0; i < eeprom_size_u32; ++i, ++destination, ++source)
*destination = *source;
eeprom_dirty = false;
return true;
}
bool PersistentStore::access_finish() {
if (eeprom_dirty) {
FLASH_Status status;
// Instead of erasing all (both) pages, maybe in the loop we check what page we are in, and if the
// data has changed in that page. We then erase the first time we "detect" a change. In theory, if
// nothing changed in a page, we wouldn't need to erase/write it.
// Or, instead of checking at this point, turn eeprom_dirty into an array of bool the size of number
// of pages. Inside write_data, we set the flag to true at that time if something in that
// page changes...either way, something to look at later.
FLASH_Unlock();
status = FLASH_ErasePage(EEPROM_PAGE0_BASE);
if (status != FLASH_COMPLETE) ACCESS_FINISHED(true);
status = FLASH_ErasePage(EEPROM_PAGE1_BASE);
if (status != FLASH_COMPLETE) ACCESS_FINISHED(true);
const uint16_t *source = reinterpret_cast<const uint16_t*>(ram_eeprom);
for (size_t i = 0; i < EEPROM_SIZE; i += 2, ++source) {
if (FLASH_ProgramHalfWord(EEPROM_PAGE0_BASE + i, *source) != FLASH_COMPLETE)
ACCESS_FINISHED(false);
}
ACCESS_FINISHED(true);
}
return true;
}
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
for (size_t i = 0; i < size; ++i) ram_eeprom[pos + i] = value[i];
eeprom_dirty = true;
crc16(crc, value, size);
pos += size;
return false; // return true for any error
}
bool PersistentStore::read_data(int &pos, uint8_t* value, const size_t size, uint16_t *crc, const bool writing/*=true*/) {
const uint8_t * const buff = writing ? &value[0] : &ram_eeprom[pos];
if (writing) for (size_t i = 0; i < size; i++) value[i] = ram_eeprom[pos + i];
crc16(crc, buff, size);
pos += size;
return false; // return true for any error
}
size_t PersistentStore::capacity() { return EEPROM_SIZE; }
#endif // EEPROM_SETTINGS && EEPROM FLASH
#endif // __STM32F1__

View File

@ -0,0 +1,105 @@
/**
* 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/>.
*
*/
/**
* HAL for stm32duino.com based on Libmaple and compatible (STM32F1)
* Implementation of EEPROM settings in SD Card
*/
#ifdef __STM32F1__
#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 (E2END + 1)
#define _ALIGN(x) __attribute__ ((aligned(x))) // SDIO uint32_t* compat.
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; // false aborts the save
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 SPI_EEPROM (in Configuration.h) 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 // __STM32F1__

View File

@ -0,0 +1,27 @@
/**
* 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
#ifdef NUM_DIGITAL_PINS // Only in ST's Arduino core (STM32duino, STM32Core)
#include "../STM32/pinsDebug_STM32duino.h"
#elif defined(BOARD_NR_GPIO_PINS) // Only in STM32GENERIC (Maple)
#include "../STM32/pinsDebug_STM32GENERIC.h"
#else
#error "M43 not supported for this board"
#endif

View File

@ -0,0 +1,288 @@
/**
* 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/>.
*
*/
#ifdef ARDUINO_ARCH_STM32F1
#include <libmaple/stm32.h>
#include "../../inc/MarlinConfig.h" // Allow pins/pins.h to set density
#if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY)
#include "sdio.h"
SDIO_CardInfoTypeDef SdCard;
bool SDIO_Init() {
uint32_t count = 0U;
SdCard.CardType = SdCard.CardVersion = SdCard.Class = SdCard.RelCardAdd = SdCard.BlockNbr = SdCard.BlockSize = SdCard.LogBlockNbr = SdCard.LogBlockSize = 0;
sdio_begin();
sdio_set_dbus_width(SDIO_CLKCR_WIDBUS_1BIT);
dma_init(SDIO_DMA_DEV);
dma_disable(SDIO_DMA_DEV, SDIO_DMA_CHANNEL);
dma_set_priority(SDIO_DMA_DEV, SDIO_DMA_CHANNEL, DMA_PRIORITY_MEDIUM);
if (!SDIO_CmdGoIdleState()) return false;
if (!SDIO_CmdGoIdleState()) return false; /* Hotplugged cards tends to miss first CMD0, so give them a second chance. */
SdCard.CardVersion = SDIO_CmdOperCond() ? CARD_V2_X : CARD_V1_X;
do {
if (count++ == SDMMC_MAX_VOLT_TRIAL) return false;
SDIO_CmdAppOperCommand(SdCard.CardVersion == CARD_V2_X ? SDMMC_HIGH_CAPACITY : SDMMC_STD_CAPACITY);
} while ((SDIO_GetResponse(SDIO_RESP1) & 0x80000000) == 0);
SdCard.CardType = (SDIO_GetResponse(SDIO_RESP1) & SDMMC_HIGH_CAPACITY) ? CARD_SDHC_SDXC : CARD_SDSC;
if (!SDIO_CmdSendCID()) return false;
if (!SDIO_CmdSetRelAdd(&SdCard.RelCardAdd)) return false; /* Send CMD3 SET_REL_ADDR with argument 0. SD Card publishes its RCA. */
if (!SDIO_CmdSendCSD(SdCard.RelCardAdd << 16U)) return false;
SdCard.Class = (SDIO_GetResponse(SDIO_RESP2) >> 20U);
if (SdCard.CardType == CARD_SDHC_SDXC) {
SdCard.LogBlockNbr = SdCard.BlockNbr = (((SDIO_GetResponse(SDIO_RESP2) & 0x0000003FU) << 26U) | ((SDIO_GetResponse(SDIO_RESP3) & 0xFFFF0000U) >> 6U)) + 1024;
SdCard.LogBlockSize = SdCard.BlockSize = 512U;
}
else {
SdCard.BlockNbr = ((((SDIO_GetResponse(SDIO_RESP2) & 0x000003FFU) << 2U ) | ((SDIO_GetResponse(SDIO_RESP3) & 0xC0000000U) >> 30U)) + 1U) * (4U << ((SDIO_GetResponse(SDIO_RESP3) & 0x00038000U) >> 15U));
SdCard.BlockSize = 1U << ((SDIO_GetResponse(SDIO_RESP2) >> 16) & 0x0FU);
SdCard.LogBlockNbr = (SdCard.BlockNbr) * ((SdCard.BlockSize) / 512U);
SdCard.LogBlockSize = 512U;
}
if (!SDIO_CmdSelDesel(SdCard.RelCardAdd << 16U)) return false;
if (!SDIO_CmdAppSetClearCardDetect(SdCard.RelCardAdd << 16U)) return false;
if (!SDIO_CmdAppSetBusWidth(SdCard.RelCardAdd << 16U, 2)) return false;
sdio_set_dbus_width(SDIO_CLKCR_WIDBUS_4BIT);
sdio_set_clock(SDIO_CLOCK);
return true;
}
bool SDIO_ReadBlock_DMA(uint32_t blockAddress, uint8_t *data) {
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; }
dma_setup_transfer(SDIO_DMA_DEV, SDIO_DMA_CHANNEL, &SDIO->FIFO, DMA_SIZE_32BITS, data, DMA_SIZE_32BITS, DMA_MINC_MODE);
dma_set_num_transfers(SDIO_DMA_DEV, SDIO_DMA_CHANNEL, 128);
dma_clear_isr_bits(SDIO_DMA_DEV, SDIO_DMA_CHANNEL);
dma_enable(SDIO_DMA_DEV, SDIO_DMA_CHANNEL);
sdio_setup_transfer(SDIO_DATA_TIMEOUT * (F_CPU / 1000U), 512, SDIO_BLOCKSIZE_512 | SDIO_DCTRL_DMAEN | SDIO_DCTRL_DTEN | SDIO_DIR_RX);
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_ReadBlock(uint32_t blockAddress, uint8_t *data) {
uint32_t retries = 3;
while (retries--) if (SDIO_ReadBlock_DMA(blockAddress, data)) return true;
return false;
}
uint32_t millis();
bool SDIO_WriteBlock(uint32_t blockAddress, const uint8_t *data) {
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; }
dma_setup_transfer(SDIO_DMA_DEV, SDIO_DMA_CHANNEL, &SDIO->FIFO, DMA_SIZE_32BITS, (volatile void *) data, DMA_SIZE_32BITS, DMA_MINC_MODE | DMA_FROM_MEM);
dma_set_num_transfers(SDIO_DMA_DEV, SDIO_DMA_CHANNEL, 128);
dma_clear_isr_bits(SDIO_DMA_DEV, SDIO_DMA_CHANNEL);
dma_enable(SDIO_DMA_DEV, SDIO_DMA_CHANNEL);
if (!SDIO_CmdWriteSingleBlock(blockAddress)) {
dma_disable(SDIO_DMA_DEV, SDIO_DMA_CHANNEL);
return false;
}
sdio_setup_transfer(SDIO_DATA_TIMEOUT * (F_CPU / 1000U), 512U, SDIO_BLOCKSIZE_512 | SDIO_DCTRL_DMAEN | SDIO_DCTRL_DTEN);
while (!SDIO_GET_FLAG(SDIO_STA_DATAEND | SDIO_STA_TRX_ERROR_FLAGS)) {}
dma_disable(SDIO_DMA_DEV, SDIO_DMA_CHANNEL);
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);
uint32_t timeout = millis() + SDIO_WRITE_TIMEOUT;
while (timeout > millis()) {
if (SDIO_GetCardState() == SDIO_CARD_TRANSFER) {
return true;
}
}
return false;
}
inline uint32_t SDIO_GetCardState() { return SDIO_CmdSendStatus(SdCard.RelCardAdd << 16U) ? (SDIO_GetResponse(SDIO_RESP1) >> 9U) & 0x0FU : SDIO_CARD_ERROR; }
// ------------------------
// SD Commands and Responses
// ------------------------
void SDIO_SendCommand(uint16_t command, uint32_t argument) { SDIO->ARG = argument; SDIO->CMD = (uint32_t)(SDIO_CMD_CPSMEN | command); }
uint8_t SDIO_GetCommandResponse() { return (uint8_t)(SDIO->RESPCMD); }
uint32_t SDIO_GetResponse(uint32_t response) { return SDIO->RESP[response]; }
bool SDIO_CmdGoIdleState() { SDIO_SendCommand(CMD0_GO_IDLE_STATE, 0); return SDIO_GetCmdError(); }
bool SDIO_CmdSendCID() { SDIO_SendCommand(CMD2_ALL_SEND_CID, 0); return SDIO_GetCmdResp2(); }
bool SDIO_CmdSetRelAdd(uint32_t *rca) { SDIO_SendCommand(CMD3_SET_REL_ADDR, 0); return SDIO_GetCmdResp6(SDMMC_CMD_SET_REL_ADDR, rca); }
bool SDIO_CmdSelDesel(uint32_t address) { SDIO_SendCommand(CMD7_SEL_DESEL_CARD, address); return SDIO_GetCmdResp1(SDMMC_CMD_SEL_DESEL_CARD); }
bool SDIO_CmdOperCond() { SDIO_SendCommand(CMD8_HS_SEND_EXT_CSD, SDMMC_CHECK_PATTERN); return SDIO_GetCmdResp7(); }
bool SDIO_CmdSendCSD(uint32_t argument) { SDIO_SendCommand(CMD9_SEND_CSD, argument); return SDIO_GetCmdResp2(); }
bool SDIO_CmdSendStatus(uint32_t argument) { SDIO_SendCommand(CMD13_SEND_STATUS, argument); return SDIO_GetCmdResp1(SDMMC_CMD_SEND_STATUS); }
bool SDIO_CmdReadSingleBlock(uint32_t address) { SDIO_SendCommand(CMD17_READ_SINGLE_BLOCK, address); return SDIO_GetCmdResp1(SDMMC_CMD_READ_SINGLE_BLOCK); }
bool SDIO_CmdWriteSingleBlock(uint32_t address) { SDIO_SendCommand(CMD24_WRITE_SINGLE_BLOCK, address); return SDIO_GetCmdResp1(SDMMC_CMD_WRITE_SINGLE_BLOCK); }
bool SDIO_CmdAppCommand(uint32_t rsa) { SDIO_SendCommand(CMD55_APP_CMD, rsa); return SDIO_GetCmdResp1(SDMMC_CMD_APP_CMD); }
bool SDIO_CmdAppSetBusWidth(uint32_t rsa, uint32_t argument) {
if (!SDIO_CmdAppCommand(rsa)) return false;
SDIO_SendCommand(ACMD6_APP_SD_SET_BUSWIDTH, argument);
return SDIO_GetCmdResp2();
}
bool SDIO_CmdAppOperCommand(uint32_t sdType) {
if (!SDIO_CmdAppCommand(0)) return false;
SDIO_SendCommand(ACMD41_SD_APP_OP_COND , SDMMC_VOLTAGE_WINDOW_SD | sdType);
return SDIO_GetCmdResp3();
}
bool SDIO_CmdAppSetClearCardDetect(uint32_t rsa) {
if (!SDIO_CmdAppCommand(rsa)) return false;
SDIO_SendCommand(ACMD42_SD_APP_SET_CLR_CARD_DETECT, 0);
return SDIO_GetCmdResp2();
}
// Wait until given flags are unset or till timeout
#define SDIO_WAIT(FLAGS) do{ \
uint32_t count = 1 + (SDIO_CMDTIMEOUT) * ((F_CPU) / 8U / 1000U); \
do { if (!--count) return false; } while (!SDIO_GET_FLAG(FLAGS)); \
}while(0)
bool SDIO_GetCmdError() {
SDIO_WAIT(SDIO_STA_CMDSENT);
SDIO_CLEAR_FLAG(SDIO_ICR_CMD_FLAGS);
return true;
}
bool SDIO_GetCmdResp1(uint8_t command) {
SDIO_WAIT(SDIO_STA_CCRCFAIL | SDIO_STA_CMDREND | SDIO_STA_CTIMEOUT);
if (SDIO_GET_FLAG(SDIO_STA_CCRCFAIL | SDIO_STA_CTIMEOUT)) {
SDIO_CLEAR_FLAG(SDIO_STA_CCRCFAIL | SDIO_STA_CTIMEOUT);
return false;
}
if (SDIO_GetCommandResponse() != command) return false;
SDIO_CLEAR_FLAG(SDIO_ICR_CMD_FLAGS);
return (SDIO_GetResponse(SDIO_RESP1) & SDMMC_OCR_ERRORBITS) == SDMMC_ALLZERO;
}
bool SDIO_GetCmdResp2() {
SDIO_WAIT(SDIO_STA_CCRCFAIL | SDIO_STA_CMDREND | SDIO_STA_CTIMEOUT);
if (SDIO_GET_FLAG(SDIO_STA_CCRCFAIL | SDIO_STA_CTIMEOUT)) {
SDIO_CLEAR_FLAG(SDIO_STA_CCRCFAIL | SDIO_STA_CTIMEOUT);
return false;
}
SDIO_CLEAR_FLAG(SDIO_ICR_CMD_FLAGS);
return true;
}
bool SDIO_GetCmdResp3() {
SDIO_WAIT(SDIO_STA_CCRCFAIL | SDIO_STA_CMDREND | SDIO_STA_CTIMEOUT);
if (SDIO_GET_FLAG(SDIO_STA_CTIMEOUT)) {
SDIO_CLEAR_FLAG(SDIO_STA_CTIMEOUT);
return false;
}
SDIO_CLEAR_FLAG(SDIO_ICR_CMD_FLAGS);
return true;
}
bool SDIO_GetCmdResp6(uint8_t command, uint32_t *rca) {
SDIO_WAIT(SDIO_STA_CCRCFAIL | SDIO_STA_CMDREND | SDIO_STA_CTIMEOUT);
if (SDIO_GET_FLAG(SDIO_STA_CCRCFAIL | SDIO_STA_CTIMEOUT)) {
SDIO_CLEAR_FLAG(SDIO_STA_CCRCFAIL | SDIO_STA_CTIMEOUT);
return false;
}
if (SDIO_GetCommandResponse() != command) return false;
SDIO_CLEAR_FLAG(SDIO_ICR_CMD_FLAGS);
if (SDIO_GetResponse(SDIO_RESP1) & (SDMMC_R6_GENERAL_UNKNOWN_ERROR | SDMMC_R6_ILLEGAL_CMD | SDMMC_R6_COM_CRC_FAILED)) return false;
*rca = SDIO_GetResponse(SDIO_RESP1) >> 16;
return true;
}
bool SDIO_GetCmdResp7() {
SDIO_WAIT(SDIO_STA_CCRCFAIL | SDIO_STA_CMDREND | SDIO_STA_CTIMEOUT);
if (SDIO_GET_FLAG(SDIO_STA_CTIMEOUT)) {
SDIO_CLEAR_FLAG(SDIO_STA_CTIMEOUT);
return false;
}
if (SDIO_GET_FLAG(SDIO_STA_CMDREND)) { SDIO_CLEAR_FLAG(SDIO_STA_CMDREND); }
return true;
}
#endif // STM32_HIGH_DENSITY || STM32_XL_DENSITY
#endif // ARDUINO_ARCH_STM32F1

View File

@ -0,0 +1,149 @@
/**
* 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 "../shared/Marduino.h"
#include <libmaple/sdio.h>
#include <libmaple/dma.h>
// ------------------------
// Defines
// ------------------------
#define SDMMC_CMD_GO_IDLE_STATE ((uint8_t)0) /* Resets the SD memory card. */
#define SDMMC_CMD_ALL_SEND_CID ((uint8_t)2) /* Asks any card connected to the host to send the CID numbers on the CMD line. */
#define SDMMC_CMD_SET_REL_ADDR ((uint8_t)3) /* Asks the card to publish a new relative address (RCA). */
#define SDMMC_CMD_SEL_DESEL_CARD ((uint8_t)7) /* Selects the card by its own relative address and gets deselected by any other address */
#define SDMMC_CMD_HS_SEND_EXT_CSD ((uint8_t)8) /* Sends SD Memory Card interface condition, which includes host supply voltage information and asks the card whether card supports voltage. */
#define SDMMC_CMD_SEND_CSD ((uint8_t)9) /* Addressed card sends its card specific data (CSD) on the CMD line. */
#define SDMMC_CMD_SEND_STATUS ((uint8_t)13) /*!< Addressed card sends its status register. */
#define SDMMC_CMD_READ_SINGLE_BLOCK ((uint8_t)17) /* Reads single block of size selected by SET_BLOCKLEN in case of SDSC, and a block of fixed 512 bytes in case of SDHC and SDXC. */
#define SDMMC_CMD_WRITE_SINGLE_BLOCK ((uint8_t)24) /* Writes single block of size selected by SET_BLOCKLEN in case of SDSC, and a block of fixed 512 bytes in case of SDHC and SDXC. */
#define SDMMC_CMD_APP_CMD ((uint8_t)55) /* Indicates to the card that the next command is an application specific command rather than a standard command. */
#define SDMMC_ACMD_APP_SD_SET_BUSWIDTH ((uint8_t)6) /* (ACMD6) Defines the data bus width to be used for data transfer. The allowed data bus widths are given in SCR register. */
#define SDMMC_ACMD_SD_APP_OP_COND ((uint8_t)41) /* (ACMD41) Sends host capacity support information (HCS) and asks the accessed card to send its operating condition register (OCR) content in the response on the CMD line. */
#define SDMMC_ACMD_SD_APP_SET_CLR_CARD_DETECT ((uint8_t)42) /* (ACMD42) Connect/Disconnect the 50 KOhm pull-up resistor on CD/DAT3 (pin 1) of the card */
#define CMD0_GO_IDLE_STATE (uint16_t)(SDMMC_CMD_GO_IDLE_STATE | SDIO_CMD_WAIT_NO_RESP)
#define CMD2_ALL_SEND_CID (uint16_t)(SDMMC_CMD_ALL_SEND_CID | SDIO_CMD_WAIT_LONG_RESP)
#define CMD3_SET_REL_ADDR (uint16_t)(SDMMC_CMD_SET_REL_ADDR | SDIO_CMD_WAIT_SHORT_RESP)
#define CMD7_SEL_DESEL_CARD (uint16_t)(SDMMC_CMD_SEL_DESEL_CARD | SDIO_CMD_WAIT_SHORT_RESP)
#define CMD8_HS_SEND_EXT_CSD (uint16_t)(SDMMC_CMD_HS_SEND_EXT_CSD | SDIO_CMD_WAIT_SHORT_RESP)
#define CMD9_SEND_CSD (uint16_t)(SDMMC_CMD_SEND_CSD | SDIO_CMD_WAIT_LONG_RESP)
#define CMD13_SEND_STATUS (uint16_t)(SDMMC_CMD_SEND_STATUS | SDIO_CMD_WAIT_SHORT_RESP)
#define CMD17_READ_SINGLE_BLOCK (uint16_t)(SDMMC_CMD_READ_SINGLE_BLOCK | SDIO_CMD_WAIT_SHORT_RESP)
#define CMD24_WRITE_SINGLE_BLOCK (uint16_t)(SDMMC_CMD_WRITE_SINGLE_BLOCK | SDIO_CMD_WAIT_SHORT_RESP)
#define CMD55_APP_CMD (uint16_t)(SDMMC_CMD_APP_CMD | SDIO_CMD_WAIT_SHORT_RESP)
#define ACMD6_APP_SD_SET_BUSWIDTH (uint16_t)(SDMMC_ACMD_APP_SD_SET_BUSWIDTH | SDIO_CMD_WAIT_SHORT_RESP)
#define ACMD41_SD_APP_OP_COND (uint16_t)(SDMMC_ACMD_SD_APP_OP_COND | SDIO_CMD_WAIT_SHORT_RESP)
#define ACMD42_SD_APP_SET_CLR_CARD_DETECT (uint16_t)(SDMMC_ACMD_SD_APP_SET_CLR_CARD_DETECT | SDIO_CMD_WAIT_SHORT_RESP)
#define SDMMC_ALLZERO 0x00000000U
#define SDMMC_OCR_ERRORBITS 0xFDFFE008U
#define SDMMC_R6_GENERAL_UNKNOWN_ERROR 0x00002000U
#define SDMMC_R6_ILLEGAL_CMD 0x00004000U
#define SDMMC_R6_COM_CRC_FAILED 0x00008000U
#define SDMMC_VOLTAGE_WINDOW_SD 0x80100000U
#define SDMMC_HIGH_CAPACITY 0x40000000U
#define SDMMC_STD_CAPACITY 0x00000000U
#define SDMMC_CHECK_PATTERN 0x000001AAU
#define SDIO_TRANSFER_MODE_BLOCK 0x00000000U
#define SDIO_DPSM_ENABLE 0x00000001U
#define SDIO_TRANSFER_DIR_TO_CARD 0x00000000U
#define SDIO_DATABLOCK_SIZE_512B 0x00000090U
#define SDIO_TRANSFER_DIR_TO_SDIO 0x00000100U
#define SDIO_DMA_ENABLE 0x00001000U
#define CARD_V1_X 0x00000000U
#define CARD_V2_X 0x00000001U
#define CARD_SDSC 0x00000000U
#define CARD_SDHC_SDXC 0x00000001U
#define SDIO_RESP1 0
#define SDIO_RESP2 1
#define SDIO_RESP3 2
#define SDIO_RESP4 3
#define SDIO_GET_FLAG(__FLAG__) !!((SDIO->STA) & (__FLAG__))
#define SDIO_CLEAR_FLAG(__FLAG__) (SDIO->ICR = (__FLAG__))
#define SDMMC_MAX_VOLT_TRIAL 0x00000FFFU
#define SDIO_CARD_TRANSFER 0x00000004U /* Card is in transfer state */
#define SDIO_CARD_ERROR 0x000000FFU /* Card response Error */
#define SDIO_CMDTIMEOUT 200U /* Command send and response timeout */
#define SDIO_DATA_TIMEOUT 100U /* Read data transfer timeout */
#define SDIO_WRITE_TIMEOUT 200U /* Write data transfer timeout */
#define SDIO_CLOCK 18000000 /* 18 MHz */
// ------------------------
// Types
// ------------------------
typedef struct {
uint32_t CardType; // Card Type
uint32_t CardVersion; // Card version
uint32_t Class; // Class of the card class
uint32_t RelCardAdd; // Relative Card Address
uint32_t BlockNbr; // Card Capacity in blocks
uint32_t BlockSize; // One block size in bytes
uint32_t LogBlockNbr; // Card logical Capacity in blocks
uint32_t LogBlockSize; // Logical block size in bytes
} SDIO_CardInfoTypeDef;
// ------------------------
// Public functions
// ------------------------
inline uint32_t SDIO_GetCardState();
bool SDIO_CmdGoIdleState();
bool SDIO_CmdSendCID();
bool SDIO_CmdSetRelAdd(uint32_t *rca);
bool SDIO_CmdSelDesel(uint32_t address);
bool SDIO_CmdOperCond();
bool SDIO_CmdSendCSD(uint32_t argument);
bool SDIO_CmdSendStatus(uint32_t argument);
bool SDIO_CmdReadSingleBlock(uint32_t address);
bool SDIO_CmdWriteSingleBlock(uint32_t address);
bool SDIO_CmdAppCommand(uint32_t rsa);
bool SDIO_CmdAppSetBusWidth(uint32_t rsa, uint32_t argument);
bool SDIO_CmdAppOperCommand(uint32_t sdType);
bool SDIO_CmdAppSetClearCardDetect(uint32_t rsa);
void SDIO_SendCommand(uint16_t command, uint32_t argument);
uint8_t SDIO_GetCommandResponse();
uint32_t SDIO_GetResponse(uint32_t response);
bool SDIO_GetCmdError();
bool SDIO_GetCmdResp1(uint8_t command);
bool SDIO_GetCmdResp2();
bool SDIO_GetCmdResp3();
bool SDIO_GetCmdResp6(uint8_t command, uint32_t *rca);
bool SDIO_GetCmdResp7();

View File

@ -0,0 +1,58 @@
/**
* 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
/**
* HAL for stm32duino.com based on Libmaple and compatible (STM32F1)
*/
/**
* STM32F1 Default SPI Pins
*
* SS SCK MISO MOSI
* +-----------------------------+
* SPI1 | PA4 PA5 PA6 PA7 |
* SPI2 | PB12 PB13 PB14 PB15 |
* SPI3 | PA15 PB3 PB4 PB5 |
* +-----------------------------+
* Any pin can be used for Chip Select (SS_PIN)
* SPI1 is enabled by default
*/
#ifndef SCK_PIN
#define SCK_PIN PA5
#endif
#ifndef MISO_PIN
#define MISO_PIN PA6
#endif
#ifndef MOSI_PIN
#define MOSI_PIN PA7
#endif
#ifndef SS_PIN
#define SS_PIN PA4
#endif
#undef SDSS
#define SDSS SS_PIN
#if ENABLED(ENABLE_SPI3)
#define SPI_DEVICE 3
#elif ENABLED(ENABLE_SPI2)
#define SPI_DEVICE 2
#else
#define SPI_DEVICE 1
#endif

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) 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/>.
*
*/
/**
* HAL for stm32duino.com based on Libmaple and compatible (STM32F1)
*/
#ifdef __STM32F1__
#include "../../inc/MarlinConfig.h"
#include "HAL.h"
#include "timers.h"
// ------------------------
// Local defines
// ------------------------
// ------------------------
// Public functions
// ------------------------
/**
* Timer_clock1: Prescaler 2 -> 36 MHz
* Timer_clock2: Prescaler 8 -> 9 MHz
* Timer_clock3: Prescaler 32 -> 2.25 MHz
* Timer_clock4: Prescaler 128 -> 562.5 kHz
*/
/**
* TODO: Calculate Timer prescale value, so we get the 32bit to adjust
*/
void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
nvic_irq_num irq_num;
switch (timer_num) {
case 1: irq_num = NVIC_TIMER1_CC; break;
case 2: irq_num = NVIC_TIMER2; break;
case 3: irq_num = NVIC_TIMER3; break;
case 4: irq_num = NVIC_TIMER4; break;
case 5: irq_num = NVIC_TIMER5; break;
#ifdef STM32_HIGH_DENSITY
// 6 & 7 are basic timers, avoid them
case 8: irq_num = NVIC_TIMER8_CC; break;
#endif
default:
/**
* This should never happen. Add a Sanitycheck for timer number.
* Should be a general timer since basic timers have no CC channels.
*/
break;
}
/**
* Give the Stepper ISR a higher priority (lower number)
* so it automatically preempts the Temperature ISR.
*/
switch (timer_num) {
case STEP_TIMER_NUM:
timer_pause(STEP_TIMER_DEV);
timer_set_mode(STEP_TIMER_DEV, STEP_TIMER_CHAN, TIMER_OUTPUT_COMPARE); // counter
timer_set_count(STEP_TIMER_DEV, 0);
timer_set_prescaler(STEP_TIMER_DEV, (uint16_t)(STEPPER_TIMER_PRESCALE - 1));
timer_set_reload(STEP_TIMER_DEV, 0xFFFF);
timer_oc_set_mode(STEP_TIMER_DEV, STEP_TIMER_CHAN, TIMER_OC_MODE_FROZEN, TIMER_OC_NO_PRELOAD); // no output pin change
timer_set_compare(STEP_TIMER_DEV, STEP_TIMER_CHAN, _MIN(hal_timer_t(HAL_TIMER_TYPE_MAX), (STEPPER_TIMER_RATE) / frequency));
timer_no_ARR_preload_ARPE(STEP_TIMER_DEV); // Need to be sure no preload on ARR register
timer_attach_interrupt(STEP_TIMER_DEV, STEP_TIMER_CHAN, stepTC_Handler);
nvic_irq_set_priority(irq_num, STEP_TIMER_IRQ_PRIO);
timer_generate_update(STEP_TIMER_DEV);
timer_resume(STEP_TIMER_DEV);
break;
case TEMP_TIMER_NUM:
timer_pause(TEMP_TIMER_DEV);
timer_set_mode(TEMP_TIMER_DEV, TEMP_TIMER_CHAN, TIMER_OUTPUT_COMPARE);
timer_set_count(TEMP_TIMER_DEV, 0);
timer_set_prescaler(TEMP_TIMER_DEV, (uint16_t)(TEMP_TIMER_PRESCALE - 1));
timer_set_reload(TEMP_TIMER_DEV, 0xFFFF);
timer_set_compare(TEMP_TIMER_DEV, TEMP_TIMER_CHAN, _MIN(hal_timer_t(HAL_TIMER_TYPE_MAX), (F_CPU) / (TEMP_TIMER_PRESCALE) / frequency));
timer_attach_interrupt(TEMP_TIMER_DEV, TEMP_TIMER_CHAN, tempTC_Handler);
nvic_irq_set_priority(irq_num, TEMP_TIMER_IRQ_PRIO);
timer_generate_update(TEMP_TIMER_DEV);
timer_resume(TEMP_TIMER_DEV);
break;
}
}
void HAL_timer_enable_interrupt(const uint8_t timer_num) {
switch (timer_num) {
case STEP_TIMER_NUM: ENABLE_STEPPER_DRIVER_INTERRUPT(); break;
case TEMP_TIMER_NUM: ENABLE_TEMPERATURE_INTERRUPT(); break;
}
}
void HAL_timer_disable_interrupt(const uint8_t timer_num) {
switch (timer_num) {
case STEP_TIMER_NUM: DISABLE_STEPPER_DRIVER_INTERRUPT(); break;
case TEMP_TIMER_NUM: DISABLE_TEMPERATURE_INTERRUPT(); break;
}
}
static inline bool timer_irq_enabled(const timer_dev * const dev, const uint8_t interrupt) {
return bool(*bb_perip(&(dev->regs).gen->DIER, interrupt));
}
bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
switch (timer_num) {
case STEP_TIMER_NUM: return timer_irq_enabled(STEP_TIMER_DEV, STEP_TIMER_CHAN);
case TEMP_TIMER_NUM: return timer_irq_enabled(TEMP_TIMER_DEV, TEMP_TIMER_CHAN);
}
return false;
}
timer_dev* get_timer_dev(int number) {
switch (number) {
#if STM32_HAVE_TIMER(1)
case 1: return &timer1;
#endif
#if STM32_HAVE_TIMER(2)
case 2: return &timer2;
#endif
#if STM32_HAVE_TIMER(3)
case 3: return &timer3;
#endif
#if STM32_HAVE_TIMER(4)
case 4: return &timer4;
#endif
#if STM32_HAVE_TIMER(5)
case 5: return &timer5;
#endif
#if STM32_HAVE_TIMER(6)
case 6: return &timer6;
#endif
#if STM32_HAVE_TIMER(7)
case 7: return &timer7;
#endif
#if STM32_HAVE_TIMER(8)
case 8: return &timer8;
#endif
#if STM32_HAVE_TIMER(9)
case 9: return &timer9;
#endif
#if STM32_HAVE_TIMER(10)
case 10: return &timer10;
#endif
#if STM32_HAVE_TIMER(11)
case 11: return &timer11;
#endif
#if STM32_HAVE_TIMER(12)
case 12: return &timer12;
#endif
#if STM32_HAVE_TIMER(13)
case 13: return &timer13;
#endif
#if STM32_HAVE_TIMER(14)
case 14: return &timer14;
#endif
default: return nullptr;
}
}
#endif // __STM32F1__

View File

@ -0,0 +1,182 @@
/**
* 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
/**
* HAL for stm32duino.com based on Libmaple and compatible (STM32F1)
*/
#include <stdint.h>
#include <libmaple/timer.h>
#include "../../core/boards.h"
// ------------------------
// Defines
// ------------------------
/**
* TODO: Check and confirm what timer we will use for each Temps and stepper driving.
* We should probable drive temps with PWM.
*/
#define FORCE_INLINE __attribute__((always_inline)) inline
typedef uint16_t hal_timer_t;
#define HAL_TIMER_TYPE_MAX 0xFFFF
#define HAL_TIMER_RATE uint32_t(F_CPU) // frequency of timers peripherals
#define STEP_TIMER_CHAN 1 // Channel of the timer to use for compare and interrupts
#define TEMP_TIMER_CHAN 1 // Channel of the timer to use for compare and interrupts
/**
* Note: Timers may be used by platforms and libraries
*
* FAN PWMs:
* With FAN_SOFT_PWM disabled the Temperature class uses
* FANx_PIN timers to generate FAN PWM signals.
*
* Speaker:
* When SPEAKER is enabled, one timer is allocated by maple/tone.cpp.
* - If BEEPER_PIN has a timer channel (and USE_PIN_TIMER is
* defined in tone.cpp) it uses the pin's own timer.
* - Otherwise it uses Timer 8 on boards with STM32_HIGH_DENSITY
* or Timer 4 on other boards.
*/
#if defined(MCU_STM32F103CB) || defined(MCU_STM32F103C8)
#define STEP_TIMER_NUM 4 // For C8/CB boards, use timer 4
#else
#define STEP_TIMER_NUM 5 // for other boards, five is fine.
#endif
#define TEMP_TIMER_NUM 2 // index of timer to use for temperature
//#define TEMP_TIMER_NUM 4 // 2->4, Timer 2 for Stepper Current PWM
#define PULSE_TIMER_NUM STEP_TIMER_NUM
#if MB(BTT_SKR_MINI_E3_V1_0, BTT_SKR_E3_DIP, BTT_SKR_MINI_E3_V1_2, MKS_ROBIN_LITE)
// SKR Mini E3 boards use PA8 as FAN_PIN, so TIMER 1 is used for Fan PWM.
#ifdef STM32_HIGH_DENSITY
#define SERVO0_TIMER_NUM 8 // tone.cpp uses Timer 4
#else
#define SERVO0_TIMER_NUM 3 // tone.cpp uses Timer 8
#endif
#else
#define SERVO0_TIMER_NUM 1 // SERVO0 or BLTOUCH
#endif
#define STEP_TIMER_IRQ_PRIO 1
#define TEMP_TIMER_IRQ_PRIO 2
#define TEMP_TIMER_PRESCALE 1000 // prescaler for setting Temp timer, 72Khz
#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency
#define STEPPER_TIMER_PRESCALE 18 // prescaler for setting stepper timer, 4Mhz
#define STEPPER_TIMER_RATE (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) // frequency of stepper timer
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
timer_dev* get_timer_dev(int number);
#define TIMER_DEV(num) get_timer_dev(num)
#define STEP_TIMER_DEV TIMER_DEV(STEP_TIMER_NUM)
#define TEMP_TIMER_DEV TIMER_DEV(TEMP_TIMER_NUM)
#define ENABLE_STEPPER_DRIVER_INTERRUPT() timer_enable_irq(STEP_TIMER_DEV, STEP_TIMER_CHAN)
#define DISABLE_STEPPER_DRIVER_INTERRUPT() timer_disable_irq(STEP_TIMER_DEV, STEP_TIMER_CHAN)
#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM)
#define ENABLE_TEMPERATURE_INTERRUPT() timer_enable_irq(TEMP_TIMER_DEV, TEMP_TIMER_CHAN)
#define DISABLE_TEMPERATURE_INTERRUPT() timer_disable_irq(TEMP_TIMER_DEV, TEMP_TIMER_CHAN)
#define HAL_timer_get_count(timer_num) timer_get_count(TIMER_DEV(timer_num))
// TODO change this
#define HAL_TEMP_TIMER_ISR() extern "C" void tempTC_Handler()
#define HAL_STEP_TIMER_ISR() extern "C" void stepTC_Handler()
extern "C" void tempTC_Handler();
extern "C" void stepTC_Handler();
// ------------------------
// Public Variables
// ------------------------
//static HardwareTimer StepperTimer(STEP_TIMER_NUM);
//static HardwareTimer TempTimer(TEMP_TIMER_NUM);
// ------------------------
// 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);
/**
* NOTE: By default libmaple sets ARPE = 1, which means the Auto reload register is preloaded (will only update with an update event)
* Thus we have to pause the timer, update the value, refresh, resume the timer.
* That seems like a big waste of time and may be better to change the timer config to ARPE = 0, so ARR can be updated any time.
* We are using a Channel in each timer in Capture/Compare mode. We could also instead use the Time Update Event Interrupt, but need to disable ARPE
* so we can change the ARR value on the fly (without calling refresh), and not get an interrupt right there because we caused an UEV.
* This mode pretty much makes 2 timers unusable for PWM since they have their counts updated all the time on ISRs.
* The way Marlin manages timer interrupts doesn't make for an efficient usage in STM32F1
* Todo: Look at that possibility later.
*/
FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) {
switch (timer_num) {
case STEP_TIMER_NUM:
// NOTE: WE have set ARPE = 0, which means the Auto reload register is not preloaded
// and there is no need to use any compare, as in the timer mode used, setting ARR to the compare value
// will result in exactly the same effect, ie trigerring an interrupt, and on top, set counter to 0
timer_set_reload(STEP_TIMER_DEV, compare); // We reload direct ARR as needed during counting up
break;
case TEMP_TIMER_NUM:
timer_set_compare(TEMP_TIMER_DEV, TEMP_TIMER_CHAN, compare);
break;
}
}
FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) {
switch (timer_num) {
case STEP_TIMER_NUM:
// No counter to clear
timer_generate_update(STEP_TIMER_DEV);
return;
case TEMP_TIMER_NUM:
timer_set_count(TEMP_TIMER_DEV, 0);
timer_generate_update(TEMP_TIMER_DEV);
return;
}
}
#define HAL_timer_isr_epilogue(TIMER_NUM)
// No command is available in framework to turn off ARPE bit, which is turned on by default in libmaple.
// Needed here to reset ARPE=0 for stepper timer
FORCE_INLINE static void timer_no_ARR_preload_ARPE(timer_dev *dev) {
bb_peri_set_bit(&(dev->regs).gen->CR1, TIMER_CR1_ARPE_BIT, 0);
}
#define TIMER_OC_NO_PRELOAD 0 // Need to disable preload also on compare registers.

View File

@ -0,0 +1,59 @@
/**
* 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/>.
*
*/
/**
* HAL for stm32duino.com based on Libmaple and compatible (STM32F1)
*/
#ifdef __STM32F1__
#include "../../inc/MarlinConfig.h"
#if ENABLED(USE_WATCHDOG)
#include <libmaple/iwdg.h>
#include "watchdog.h"
void HAL_watchdog_refresh() {
#if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED)
TOGGLE(LED_PIN); // heartbeat indicator
#endif
iwdg_feed();
}
void watchdogSetup() {
// do whatever. don't remove this function.
}
/**
* @brief Initialized the independent hardware watchdog.
*
* @return No return
*
* @details The watchdog clock is 40Khz. We need a 4 seconds interval, so use a /256 preescaler and 625 reload value (counts down to 0)
*/
void watchdog_init() {
//iwdg_init(IWDG_PRE_256, STM32F1_WD_RELOAD);
}
#endif // USE_WATCHDOG
#endif // __STM32F1__

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/>.
*
*/
#pragma once
/**
* HAL for stm32duino.com based on Libmaple and compatible (STM32F1)
*/
#include <libmaple/iwdg.h>
/**
* The watchdog clock is 40Khz. We need a 4 seconds interval, so use a /256 preescaler and
* 625 reload value (counts down to 0)
* use 1250 for 8 seconds
*/
#define STM32F1_WD_RELOAD 625
// Arduino STM32F1 core now has watchdog support
// Initialize watchdog with a 4 second countdown time
void watchdog_init();
// Reset watchdog. MUST be called at least every 4 seconds after the
// first watchdog_init or STM32F1 will reset.
void HAL_watchdog_refresh();