update code base to Marlin 2.0.9.2
This commit is contained in:
123
Marlin/src/HAL/STM32F1/HAL.cpp
Executable file → Normal file
123
Marlin/src/HAL/STM32F1/HAL.cpp
Executable file → Normal file
@@ -17,7 +17,7 @@
|
||||
* 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/>.
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
@@ -82,8 +82,34 @@
|
||||
// Public Variables
|
||||
// ------------------------
|
||||
|
||||
#if (defined(SERIAL_USB) && !defined(USE_USB_COMPOSITE))
|
||||
#if defined(SERIAL_USB) && !HAS_SD_HOST_DRIVE
|
||||
USBSerial SerialUSB;
|
||||
DefaultSerial1 MSerial0(true, SerialUSB);
|
||||
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
#include "../libmaple/usb/stm32f1/usb_reg_map.h"
|
||||
#include "libmaple/usb_cdcacm.h"
|
||||
// The original callback is not called (no way to retrieve address).
|
||||
// That callback detects a special STM32 reset sequence: this functionality is not essential
|
||||
// as M997 achieves the same.
|
||||
void my_rx_callback(unsigned int, void*) {
|
||||
// max length of 16 is enough to contain all emergency commands
|
||||
uint8 buf[16];
|
||||
|
||||
//rx is usbSerialPart.endpoints[2]
|
||||
uint16 len = usb_get_ep_rx_count(USB_CDCACM_RX_ENDP);
|
||||
uint32 total = usb_cdcacm_data_available();
|
||||
|
||||
if (len == 0 || total == 0 || !WITHIN(total, len, COUNT(buf)))
|
||||
return;
|
||||
|
||||
// cannot get character by character due to bug in composite_cdcacm_peek_ex
|
||||
len = usb_cdcacm_peek(buf, total);
|
||||
|
||||
for (uint32 i = 0; i < len; i++)
|
||||
emergency_parser.update(MSerial0.emergency_state, buf[i + total - len]);
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
|
||||
uint16_t HAL_adc_result;
|
||||
@@ -97,12 +123,18 @@ const uint8_t adc_pins[] = {
|
||||
#if HAS_TEMP_ADC_0
|
||||
TEMP_0_PIN,
|
||||
#endif
|
||||
#if HAS_TEMP_ADC_PROBE
|
||||
TEMP_PROBE_PIN,
|
||||
#endif
|
||||
#if HAS_HEATED_BED
|
||||
TEMP_BED_PIN,
|
||||
#endif
|
||||
#if HAS_HEATED_CHAMBER
|
||||
#if HAS_TEMP_CHAMBER
|
||||
TEMP_CHAMBER_PIN,
|
||||
#endif
|
||||
#if HAS_TEMP_COOLER
|
||||
TEMP_COOLER_PIN,
|
||||
#endif
|
||||
#if HAS_TEMP_ADC_1
|
||||
TEMP_1_PIN,
|
||||
#endif
|
||||
@@ -127,7 +159,7 @@ const uint8_t adc_pins[] = {
|
||||
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||
FILWIDTH_PIN,
|
||||
#endif
|
||||
#if ENABLED(ADC_KEYPAD)
|
||||
#if HAS_ADC_BUTTONS
|
||||
ADC_KEYPAD_PIN,
|
||||
#endif
|
||||
#if HAS_JOY_ADC_X
|
||||
@@ -139,18 +171,30 @@ const uint8_t adc_pins[] = {
|
||||
#if HAS_JOY_ADC_Z
|
||||
JOY_Z_PIN,
|
||||
#endif
|
||||
#if ENABLED(POWER_MONITOR_CURRENT)
|
||||
POWER_MONITOR_CURRENT_PIN,
|
||||
#endif
|
||||
#if ENABLED(POWER_MONITOR_VOLTAGE)
|
||||
POWER_MONITOR_VOLTAGE_PIN,
|
||||
#endif
|
||||
};
|
||||
|
||||
enum TEMP_PINS : char {
|
||||
enum TempPinIndex : char {
|
||||
#if HAS_TEMP_ADC_0
|
||||
TEMP_0,
|
||||
#endif
|
||||
#if HAS_TEMP_ADC_PROBE
|
||||
TEMP_PROBE,
|
||||
#endif
|
||||
#if HAS_HEATED_BED
|
||||
TEMP_BED,
|
||||
#endif
|
||||
#if HAS_HEATED_CHAMBER
|
||||
#if HAS_TEMP_CHAMBER
|
||||
TEMP_CHAMBER,
|
||||
#endif
|
||||
#if HAS_TEMP_COOLER
|
||||
TEMP_COOLER_PIN,
|
||||
#endif
|
||||
#if HAS_TEMP_ADC_1
|
||||
TEMP_1,
|
||||
#endif
|
||||
@@ -175,7 +219,7 @@ enum TEMP_PINS : char {
|
||||
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||
FILWIDTH,
|
||||
#endif
|
||||
#if ENABLED(ADC_KEYPAD)
|
||||
#if HAS_ADC_BUTTONS
|
||||
ADC_KEY,
|
||||
#endif
|
||||
#if HAS_JOY_ADC_X
|
||||
@@ -187,6 +231,12 @@ enum TEMP_PINS : char {
|
||||
#if HAS_JOY_ADC_Z
|
||||
JOY_Z,
|
||||
#endif
|
||||
#if ENABLED(POWER_MONITOR_CURRENT)
|
||||
POWERMON_CURRENT,
|
||||
#endif
|
||||
#if ENABLED(POWER_MONITOR_VOLTAGE)
|
||||
POWERMON_VOLTS,
|
||||
#endif
|
||||
ADC_PIN_COUNT
|
||||
};
|
||||
|
||||
@@ -203,7 +253,7 @@ static void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) {
|
||||
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 */
|
||||
(PriorityGroupTmp << 8)); /* Insert write key & priority group */
|
||||
SCB->AIRCR = reg_value;
|
||||
}
|
||||
|
||||
@@ -228,34 +278,37 @@ static void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) {
|
||||
} }
|
||||
#endif
|
||||
|
||||
TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial());
|
||||
|
||||
void HAL_init() {
|
||||
NVIC_SetPriorityGrouping(0x3);
|
||||
#if PIN_EXISTS(LED)
|
||||
OUT_WRITE(LED_PIN, LOW);
|
||||
#endif
|
||||
#ifdef USE_USB_COMPOSITE
|
||||
#if HAS_SD_HOST_DRIVE
|
||||
MSC_SD_init();
|
||||
#elif BOTH(SERIAL_USB, EMERGENCY_PARSER)
|
||||
usb_cdcacm_set_hooks(USB_CDCACM_HOOK_RX, my_rx_callback);
|
||||
#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);
|
||||
WRITE(USB_CONNECT_PIN, USB_CONNECT_INVERTING);
|
||||
#endif
|
||||
TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); // Install the minimal serial handler
|
||||
}
|
||||
|
||||
// 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
|
||||
#if HAS_SHARED_MEDIA
|
||||
// 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 HAS_SD_HOST_DRIVE*/
|
||||
// process USB mass storage device class loop
|
||||
MarlinMSC.loop();
|
||||
#endif
|
||||
@@ -265,9 +318,8 @@ 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; }
|
||||
uint8_t HAL_get_reset_source() { return RST_POWER_ON; }
|
||||
|
||||
void _delay_ms(const int delay_ms) { delay(delay_ms); }
|
||||
|
||||
@@ -323,18 +375,25 @@ void HAL_adc_init() {
|
||||
}
|
||||
|
||||
void HAL_adc_start_conversion(const uint8_t adc_pin) {
|
||||
TEMP_PINS pin_index;
|
||||
//TEMP_PINS pin_index;
|
||||
TempPinIndex pin_index;
|
||||
switch (adc_pin) {
|
||||
default: return;
|
||||
#if HAS_TEMP_ADC_0
|
||||
case TEMP_0_PIN: pin_index = TEMP_0; break;
|
||||
#endif
|
||||
#if HAS_TEMP_ADC_PROBE
|
||||
case TEMP_PROBE_PIN: pin_index = TEMP_PROBE; break;
|
||||
#endif
|
||||
#if HAS_HEATED_BED
|
||||
case TEMP_BED_PIN: pin_index = TEMP_BED; break;
|
||||
#endif
|
||||
#if HAS_HEATED_CHAMBER
|
||||
#if HAS_TEMP_CHAMBER
|
||||
case TEMP_CHAMBER_PIN: pin_index = TEMP_CHAMBER; break;
|
||||
#endif
|
||||
#if HAS_TEMP_COOLER
|
||||
case TEMP_COOLER_PIN: pin_index = TEMP_COOLER; break;
|
||||
#endif
|
||||
#if HAS_TEMP_ADC_1
|
||||
case TEMP_1_PIN: pin_index = TEMP_1; break;
|
||||
#endif
|
||||
@@ -368,11 +427,17 @@ void HAL_adc_start_conversion(const uint8_t adc_pin) {
|
||||
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||
case FILWIDTH_PIN: pin_index = FILWIDTH; break;
|
||||
#endif
|
||||
#if ENABLED(ADC_KEYPAD)
|
||||
#if HAS_ADC_BUTTONS
|
||||
case ADC_KEYPAD_PIN: pin_index = ADC_KEY; break;
|
||||
#endif
|
||||
#if ENABLED(POWER_MONITOR_CURRENT)
|
||||
case POWER_MONITOR_CURRENT_PIN: pin_index = POWERMON_CURRENT; break;
|
||||
#endif
|
||||
#if ENABLED(POWER_MONITOR_VOLTAGE)
|
||||
case POWER_MONITOR_VOLTAGE_PIN: pin_index = POWERMON_VOLTS; break;
|
||||
#endif
|
||||
}
|
||||
HAL_adc_result = (HAL_adc_results[(int)pin_index] >> 2) & 0x3FF; // shift to get 10 bits only.
|
||||
HAL_adc_result = HAL_adc_results[(int)pin_index] >> (12 - HAL_ADC_RESOLUTION); // shift out unused bits
|
||||
}
|
||||
|
||||
uint16_t HAL_adc_get_result() { return HAL_adc_result; }
|
||||
@@ -388,6 +453,8 @@ void analogWrite(pin_t pin, int pwm_val8) {
|
||||
analogWrite(uint8_t(pin), pwm_val8);
|
||||
}
|
||||
|
||||
void flashFirmware(const int16_t) { nvic_sys_reset(); }
|
||||
void HAL_reboot() { nvic_sys_reset(); }
|
||||
|
||||
void flashFirmware(const int16_t) { HAL_reboot(); }
|
||||
|
||||
#endif // __STM32F1__
|
||||
|
213
Marlin/src/HAL/STM32F1/HAL.h
Executable file → Normal file
213
Marlin/src/HAL/STM32F1/HAL.h
Executable file → Normal file
@@ -17,7 +17,7 @@
|
||||
* 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/>.
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
@@ -36,23 +36,30 @@
|
||||
#include "fastio.h"
|
||||
#include "watchdog.h"
|
||||
|
||||
#include "timers.h"
|
||||
|
||||
#include <stdint.h>
|
||||
#include <util/atomic.h>
|
||||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
|
||||
#ifdef USE_USB_COMPOSITE
|
||||
#if HAS_SD_HOST_DRIVE
|
||||
#include "msc_sd.h"
|
||||
#endif
|
||||
|
||||
#include "MarlinSerial.h"
|
||||
|
||||
// ------------------------
|
||||
// Defines
|
||||
// ------------------------
|
||||
|
||||
//
|
||||
// Default graphical display delays
|
||||
//
|
||||
#define CPU_ST7920_DELAY_1 300
|
||||
#define CPU_ST7920_DELAY_2 40
|
||||
#define CPU_ST7920_DELAY_3 340
|
||||
|
||||
#ifndef STM32_FLASH_SIZE
|
||||
#ifdef MCU_STM32F103RE
|
||||
#if ANY(MCU_STM32F103RE, MCU_STM32F103VE, MCU_STM32F103ZE)
|
||||
#define STM32_FLASH_SIZE 512
|
||||
#else
|
||||
#define STM32_FLASH_SIZE 256
|
||||
@@ -60,91 +67,79 @@
|
||||
#endif
|
||||
|
||||
#ifdef SERIAL_USB
|
||||
#ifndef USE_USB_COMPOSITE
|
||||
#define UsbSerial Serial
|
||||
#else
|
||||
typedef ForwardSerial1Class< USBSerial > DefaultSerial1;
|
||||
extern DefaultSerial1 MSerial0;
|
||||
#if HAS_SD_HOST_DRIVE
|
||||
#define UsbSerial MarlinCompositeSerial
|
||||
#else
|
||||
#define UsbSerial MSerial0
|
||||
#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
|
||||
#define _MSERIAL(X) MSerial##X
|
||||
#define MSERIAL(X) _MSERIAL(X)
|
||||
|
||||
#if EITHER(STM32_HIGH_DENSITY, STM32_XL_DENSITY)
|
||||
#define NUM_UARTS 5
|
||||
#else
|
||||
#error "SERIAL_PORT must be from -1 to 5. Please update your configuration."
|
||||
#define NUM_UARTS 3
|
||||
#endif
|
||||
|
||||
#if SERIAL_PORT == -1
|
||||
#define MYSERIAL1 UsbSerial
|
||||
#elif WITHIN(SERIAL_PORT, 1, NUM_UARTS)
|
||||
#define MYSERIAL1 MSERIAL(SERIAL_PORT)
|
||||
#else
|
||||
#define MYSERIAL1 MSERIAL(1) // dummy port
|
||||
static_assert(false, "SERIAL_PORT must be from 1 to " STRINGIFY(NUM_UARTS) ". You can also use -1 if the board supports Native USB.")
|
||||
#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
|
||||
#if SERIAL_PORT_2 == -1
|
||||
#define MYSERIAL2 UsbSerial
|
||||
#elif WITHIN(SERIAL_PORT_2, 1, NUM_UARTS)
|
||||
#define MYSERIAL2 MSERIAL(SERIAL_PORT_2)
|
||||
#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."
|
||||
#define MYSERIAL2 MSERIAL(1) // dummy port
|
||||
static_assert(false, "SERIAL_PORT_2 must be from 1 to " STRINGIFY(NUM_UARTS) ". You can also use -1 if the board supports Native USB.")
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef SERIAL_PORT_3
|
||||
#if SERIAL_PORT_3 == -1
|
||||
#define MYSERIAL3 UsbSerial
|
||||
#elif WITHIN(SERIAL_PORT_3, 1, NUM_UARTS)
|
||||
#define MYSERIAL3 MSERIAL(SERIAL_PORT_3)
|
||||
#else
|
||||
#define MYSERIAL3 MSERIAL(1) // dummy port
|
||||
static_assert(false, "SERIAL_PORT_3 must be from 1 to " STRINGIFY(NUM_UARTS) ". You can also use -1 if the board supports Native USB.")
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef MMU2_SERIAL_PORT
|
||||
#if MMU2_SERIAL_PORT == -1
|
||||
#define MMU2_SERIAL UsbSerial
|
||||
#elif WITHIN(MMU2_SERIAL_PORT, 1, NUM_UARTS)
|
||||
#define MMU2_SERIAL MSERIAL(MMU2_SERIAL_PORT)
|
||||
#else
|
||||
#define MMU2_SERIAL MSERIAL(1) // dummy port
|
||||
static_assert(false, "MMU2_SERIAL_PORT must be from 1 to " STRINGIFY(NUM_UARTS) ". You can also use -1 if the board supports Native USB.")
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef LCD_SERIAL_PORT
|
||||
#if LCD_SERIAL_PORT == -1
|
||||
#define LCD_SERIAL UsbSerial
|
||||
#elif WITHIN(LCD_SERIAL_PORT, 1, NUM_UARTS)
|
||||
#define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT)
|
||||
#else
|
||||
#define LCD_SERIAL MSERIAL(1) // dummy port
|
||||
static_assert(false, "LCD_SERIAL_PORT must be from 1 to " STRINGIFY(NUM_UARTS) ". You can also use -1 if the board supports Native USB.")
|
||||
#endif
|
||||
#if HAS_DGUS_LCD
|
||||
#define SERIAL_GET_TX_BUFFER_FREE() LCD_SERIAL.availableForWrite()
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// Set interrupt grouping for this MCU
|
||||
void HAL_init();
|
||||
@@ -159,7 +154,7 @@ void HAL_idletask();
|
||||
#endif
|
||||
|
||||
#ifndef digitalPinHasPWM
|
||||
#define digitalPinHasPWM(P) (PIN_MAP[P].timer_device != nullptr)
|
||||
#define digitalPinHasPWM(P) !!PIN_MAP[P].timer_device
|
||||
#define NO_COMPILE_TIME_PWM
|
||||
#endif
|
||||
|
||||
@@ -172,14 +167,6 @@ void HAL_idletask();
|
||||
// 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
|
||||
@@ -220,6 +207,8 @@ void HAL_clear_reset_source();
|
||||
// Reset reason
|
||||
uint8_t HAL_get_reset_source();
|
||||
|
||||
void HAL_reboot();
|
||||
|
||||
void _delay_ms(const int delay);
|
||||
|
||||
#pragma GCC diagnostic push
|
||||
@@ -233,34 +222,13 @@ extern "C" {
|
||||
|
||||
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() {
|
||||
static inline int freeMemory() {
|
||||
volatile char top;
|
||||
return &top - reinterpret_cast<char*>(_sbrk(0));
|
||||
return &top - _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
|
||||
//
|
||||
@@ -269,8 +237,14 @@ void eeprom_update_block(const void *__src, void *__dst, size_t __n);
|
||||
|
||||
void HAL_adc_init();
|
||||
|
||||
#ifdef ADC_RESOLUTION
|
||||
#define HAL_ADC_RESOLUTION ADC_RESOLUTION
|
||||
#else
|
||||
#define HAL_ADC_RESOLUTION 12
|
||||
#endif
|
||||
|
||||
#define HAL_ADC_VREF 3.3
|
||||
#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
|
||||
|
||||
@@ -289,3 +263,20 @@ void analogWrite(pin_t pin, int pwm_val8); // PWM only! mul by 257 in maple!?
|
||||
|
||||
#define PLATFORM_M997_SUPPORT
|
||||
void flashFirmware(const int16_t);
|
||||
|
||||
#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment
|
||||
|
||||
/**
|
||||
* set_pwm_frequency
|
||||
* Set the frequency of the timer corresponding to the provided pin
|
||||
* All Timer PWM pins run at the same frequency
|
||||
*/
|
||||
void set_pwm_frequency(const pin_t pin, int f_desired);
|
||||
|
||||
/**
|
||||
* set_pwm_duty
|
||||
* Set the PWM duty cycle of the provided pin to the provided value
|
||||
* Optionally allows inverting the duty cycle [default = false]
|
||||
* Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255]
|
||||
*/
|
||||
void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false);
|
||||
|
118
Marlin/src/HAL/STM32F1/HAL_MinSerial.cpp
Normal file
118
Marlin/src/HAL/STM32F1/HAL_MinSerial.cpp
Normal file
@@ -0,0 +1,118 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2021 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 <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#ifdef __STM32F1__
|
||||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if ENABLED(POSTMORTEM_DEBUGGING)
|
||||
|
||||
#include "../shared/HAL_MinSerial.h"
|
||||
#include "watchdog.h"
|
||||
|
||||
#include <libmaple/usart.h>
|
||||
#include <libmaple/rcc.h>
|
||||
#include <libmaple/nvic.h>
|
||||
|
||||
/* Instruction Synchronization Barrier */
|
||||
#define isb() __asm__ __volatile__ ("isb" : : : "memory")
|
||||
|
||||
/* Data Synchronization Barrier */
|
||||
#define dsb() __asm__ __volatile__ ("dsb" : : : "memory")
|
||||
|
||||
static void TXBegin() {
|
||||
#if !WITHIN(SERIAL_PORT, 1, 6)
|
||||
#warning "Using POSTMORTEM_DEBUGGING requires a physical U(S)ART hardware in case of severe error."
|
||||
#warning "Disabling the severe error reporting feature currently because the used serial port is not a HW port."
|
||||
#else
|
||||
// We use MYSERIAL1 here, so we need to figure out how to get the linked register
|
||||
struct usart_dev* dev = MYSERIAL1.c_dev();
|
||||
|
||||
// Or use this if removing libmaple
|
||||
// int irq = dev->irq_num;
|
||||
// int nvicUART[] = { NVIC_USART1 /* = 37 */, NVIC_USART2 /* = 38 */, NVIC_USART3 /* = 39 */, NVIC_UART4 /* = 52 */, NVIC_UART5 /* = 53 */ };
|
||||
// Disabling irq means setting the bit in the NVIC ICER register located at
|
||||
// Disable UART interrupt in NVIC
|
||||
nvic_irq_disable(dev->irq_num);
|
||||
|
||||
// Use this if removing libmaple
|
||||
//SBI(NVIC_BASE->ICER[1], irq - 32);
|
||||
|
||||
// We NEED memory barriers to ensure Interrupts are actually disabled!
|
||||
// ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the )
|
||||
dsb();
|
||||
isb();
|
||||
|
||||
rcc_clk_disable(dev->clk_id);
|
||||
rcc_clk_enable(dev->clk_id);
|
||||
|
||||
usart_reg_map *regs = dev->regs;
|
||||
regs->CR1 = 0; // Reset the USART
|
||||
regs->CR2 = 0; // 1 stop bit
|
||||
|
||||
// If we don't touch the BRR (baudrate register), we don't need to recompute. Else we would need to call
|
||||
usart_set_baud_rate(dev, 0, BAUDRATE);
|
||||
|
||||
regs->CR1 = (USART_CR1_TE | USART_CR1_UE); // 8 bits, no parity, 1 stop bit
|
||||
#endif
|
||||
}
|
||||
|
||||
// A SW memory barrier, to ensure GCC does not overoptimize loops
|
||||
#define sw_barrier() __asm__ volatile("": : :"memory");
|
||||
static void TX(char c) {
|
||||
#if WITHIN(SERIAL_PORT, 1, 6)
|
||||
struct usart_dev* dev = MYSERIAL1.c_dev();
|
||||
while (!(dev->regs->SR & USART_SR_TXE)) {
|
||||
TERN_(USE_WATCHDOG, HAL_watchdog_refresh());
|
||||
sw_barrier();
|
||||
}
|
||||
dev->regs->DR = c;
|
||||
#endif
|
||||
}
|
||||
|
||||
void install_min_serial() {
|
||||
HAL_min_serial_init = &TXBegin;
|
||||
HAL_min_serial_out = &TX;
|
||||
}
|
||||
|
||||
#if DISABLED(DYNAMIC_VECTORTABLE) && DISABLED(STM32F0xx) // Cortex M0 can't branch to a symbol that's too far, so we have a specific hack for them
|
||||
extern "C" {
|
||||
__attribute__((naked)) void JumpHandler_ASM() {
|
||||
__asm__ __volatile__ (
|
||||
"b CommonHandler_ASM\n"
|
||||
);
|
||||
}
|
||||
void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) __exc_hardfault();
|
||||
void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) __exc_busfault();
|
||||
void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) __exc_usagefault();
|
||||
void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) __exc_memmanage();
|
||||
void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) __exc_nmi();
|
||||
void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) __stm32reservedexception7();
|
||||
void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) __stm32reservedexception8();
|
||||
void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) __stm32reservedexception9();
|
||||
void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) __stm32reservedexception10();
|
||||
void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) __stm32reservedexception13();
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // POSTMORTEM_DEBUGGING
|
||||
#endif // __STM32F1__
|
19
Marlin/src/HAL/STM32F1/HAL_SPI.cpp
Executable file → Normal file
19
Marlin/src/HAL/STM32F1/HAL_SPI.cpp
Executable file → Normal file
@@ -17,16 +17,13 @@
|
||||
* 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/>.
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* Software SPI functions originally from Arduino Sd2Card Library
|
||||
* Copyright (c) 2009 by William Greiman
|
||||
*/
|
||||
|
||||
/**
|
||||
* Adapted to the STM32F1 HAL
|
||||
*/
|
||||
|
||||
@@ -64,8 +61,8 @@
|
||||
* @details Only configures SS pin since libmaple creates and initialize the SPI object
|
||||
*/
|
||||
void spiBegin() {
|
||||
#if PIN_EXISTS(SS)
|
||||
OUT_WRITE(SS_PIN, HIGH);
|
||||
#if PIN_EXISTS(SD_SS)
|
||||
OUT_WRITE(SD_SS_PIN, HIGH);
|
||||
#endif
|
||||
}
|
||||
|
||||
@@ -113,7 +110,7 @@ void spiInit(uint8_t spiRate) {
|
||||
* @details
|
||||
*/
|
||||
uint8_t spiRec() {
|
||||
uint8_t returnByte = SPI.transfer(ff);
|
||||
uint8_t returnByte = SPI.transfer(0xFF);
|
||||
return returnByte;
|
||||
}
|
||||
|
||||
@@ -126,7 +123,7 @@ uint8_t spiRec() {
|
||||
*
|
||||
* @details Uses DMA
|
||||
*/
|
||||
void spiRead(uint8_t* buf, uint16_t nbyte) {
|
||||
void spiRead(uint8_t *buf, uint16_t nbyte) {
|
||||
SPI.dmaTransfer(0, const_cast<uint8_t*>(buf), nbyte);
|
||||
}
|
||||
|
||||
@@ -149,7 +146,7 @@ void spiSend(uint8_t b) {
|
||||
*
|
||||
* @details Use DMA
|
||||
*/
|
||||
void spiSendBlock(uint8_t token, const uint8_t* buf) {
|
||||
void spiSendBlock(uint8_t token, const uint8_t *buf) {
|
||||
SPI.send(token);
|
||||
SPI.dmaSend(const_cast<uint8_t*>(buf), 512);
|
||||
}
|
||||
@@ -157,13 +154,13 @@ void spiSendBlock(uint8_t token, const uint8_t* buf) {
|
||||
#if ENABLED(SPI_EEPROM)
|
||||
|
||||
// Read single byte from specified SPI channel
|
||||
uint8_t spiRec(uint32_t chan) { return SPI.transfer(ff); }
|
||||
uint8_t spiRec(uint32_t chan) { return SPI.transfer(0xFF); }
|
||||
|
||||
// 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) {
|
||||
void spiSend(uint32_t chan, const uint8_t *buf, size_t n) {
|
||||
for (size_t p = 0; p < n; p++) spiSend(chan, buf[p]);
|
||||
}
|
||||
|
||||
|
45
Marlin/src/HAL/STM32F1/MarlinSPI.h
Normal file
45
Marlin/src/HAL/STM32F1/MarlinSPI.h
Normal file
@@ -0,0 +1,45 @@
|
||||
/**
|
||||
* 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 <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include <SPI.h>
|
||||
|
||||
/**
|
||||
* Marlin currently requires 3 SPI classes:
|
||||
*
|
||||
* SPIClass:
|
||||
* This class is normally provided by frameworks and has a semi-default interface.
|
||||
* This is needed because some libraries reference it globally.
|
||||
*
|
||||
* SPISettings:
|
||||
* Container for SPI configs for SPIClass. As above, libraries may reference it globally.
|
||||
*
|
||||
* These two classes are often provided by frameworks so we cannot extend them to add
|
||||
* useful methods for Marlin.
|
||||
*
|
||||
* MarlinSPI:
|
||||
* Provides the default SPIClass interface plus some Marlin goodies such as a simplified
|
||||
* interface for SPI DMA transfer.
|
||||
*
|
||||
*/
|
||||
|
||||
using MarlinSPI = SPIClass;
|
204
Marlin/src/HAL/STM32F1/MarlinSerial.cpp
Normal file
204
Marlin/src/HAL/STM32F1/MarlinSerial.cpp
Normal file
@@ -0,0 +1,204 @@
|
||||
/**
|
||||
* 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 <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifdef __STM32F1__
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
#include "MarlinSerial.h"
|
||||
#include <libmaple/usart.h>
|
||||
|
||||
// Copied from ~/.platformio/packages/framework-arduinoststm32-maple/STM32F1/system/libmaple/usart_private.h
|
||||
// Changed to handle Emergency Parser
|
||||
static inline __always_inline void my_usart_irq(ring_buffer *rb, ring_buffer *wb, usart_reg_map *regs, MSerialT &serial) {
|
||||
/* Handle RXNEIE and TXEIE interrupts.
|
||||
* RXNE signifies availability of a byte in DR.
|
||||
*
|
||||
* See table 198 (sec 27.4, p809) in STM document RM0008 rev 15.
|
||||
* We enable RXNEIE.
|
||||
*/
|
||||
uint32_t srflags = regs->SR, cr1its = regs->CR1;
|
||||
|
||||
if ((cr1its & USART_CR1_RXNEIE) && (srflags & USART_SR_RXNE)) {
|
||||
if (srflags & USART_SR_FE || srflags & USART_SR_PE ) {
|
||||
// framing error or parity error
|
||||
regs->DR; // Read and throw away the data, which also clears FE and PE
|
||||
}
|
||||
else {
|
||||
uint8_t c = (uint8)regs->DR;
|
||||
#ifdef USART_SAFE_INSERT
|
||||
// If the buffer is full and the user defines USART_SAFE_INSERT,
|
||||
// ignore new bytes.
|
||||
rb_safe_insert(rb, c);
|
||||
#else
|
||||
// By default, push bytes around in the ring buffer.
|
||||
rb_push_insert(rb, c);
|
||||
#endif
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
if (serial.emergency_parser_enabled())
|
||||
emergency_parser.update(serial.emergency_state, c);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
else if (srflags & USART_SR_ORE) {
|
||||
// overrun and empty data, just do a dummy read to clear ORE
|
||||
// and prevent a raise condition where a continuous interrupt stream (due to ORE set) occurs
|
||||
// (see chapter "Overrun error" ) in STM32 reference manual
|
||||
regs->DR;
|
||||
}
|
||||
|
||||
// TXE signifies readiness to send a byte to DR.
|
||||
if ((cr1its & USART_CR1_TXEIE) && (srflags & USART_SR_TXE)) {
|
||||
if (!rb_is_empty(wb))
|
||||
regs->DR=rb_remove(wb);
|
||||
else
|
||||
regs->CR1 &= ~((uint32)USART_CR1_TXEIE); // disable TXEIE
|
||||
}
|
||||
}
|
||||
|
||||
// Not every MarlinSerial port should handle emergency parsing.
|
||||
// It would not make sense to parse GCode from TMC responses, for example.
|
||||
constexpr bool serial_handles_emergency(int port) {
|
||||
return false
|
||||
#ifdef SERIAL_PORT
|
||||
|| (SERIAL_PORT) == port
|
||||
#endif
|
||||
#ifdef SERIAL_PORT_2
|
||||
|| (SERIAL_PORT_2) == port
|
||||
#endif
|
||||
#ifdef LCD_SERIAL_PORT
|
||||
|| (LCD_SERIAL_PORT) == port
|
||||
#endif
|
||||
;
|
||||
}
|
||||
|
||||
#define DEFINE_HWSERIAL_MARLIN(name, n) \
|
||||
MSerialT name(serial_handles_emergency(n),\
|
||||
USART##n, \
|
||||
BOARD_USART##n##_TX_PIN, \
|
||||
BOARD_USART##n##_RX_PIN); \
|
||||
extern "C" void __irq_usart##n(void) { \
|
||||
my_usart_irq(USART##n->rb, USART##n->wb, USART##n##_BASE, MSerial##n); \
|
||||
}
|
||||
|
||||
#define DEFINE_HWSERIAL_UART_MARLIN(name, n) \
|
||||
MSerialT name(serial_handles_emergency(n), \
|
||||
UART##n, \
|
||||
BOARD_USART##n##_TX_PIN, \
|
||||
BOARD_USART##n##_RX_PIN); \
|
||||
extern "C" void __irq_usart##n(void) { \
|
||||
my_usart_irq(UART##n->rb, UART##n->wb, UART##n##_BASE, MSerial##n); \
|
||||
}
|
||||
|
||||
// Instantiate all UARTs even if they are not needed
|
||||
// This avoids a bunch of logic to figure out every serial
|
||||
// port which may be in use on the system.
|
||||
#if DISABLED(MKS_WIFI_MODULE)
|
||||
DEFINE_HWSERIAL_MARLIN(MSerial1, 1);
|
||||
#endif
|
||||
DEFINE_HWSERIAL_MARLIN(MSerial2, 2);
|
||||
DEFINE_HWSERIAL_MARLIN(MSerial3, 3);
|
||||
#if EITHER(STM32_HIGH_DENSITY, STM32_XL_DENSITY)
|
||||
DEFINE_HWSERIAL_UART_MARLIN(MSerial4, 4);
|
||||
DEFINE_HWSERIAL_UART_MARLIN(MSerial5, 5);
|
||||
#endif
|
||||
|
||||
// Check the type of each serial port by passing it to a template function.
|
||||
// HardwareSerial is known to sometimes hang the controller when an error occurs,
|
||||
// so this case will fail the static assert. All other classes are assumed to be ok.
|
||||
template <typename T>
|
||||
constexpr bool IsSerialClassAllowed(const T&) { return true; }
|
||||
constexpr bool IsSerialClassAllowed(const HardwareSerial&) { return false; }
|
||||
|
||||
#define CHECK_CFG_SERIAL(A) static_assert(IsSerialClassAllowed(A), STRINGIFY(A) " is defined incorrectly");
|
||||
#define CHECK_AXIS_SERIAL(A) static_assert(IsSerialClassAllowed(A##_HARDWARE_SERIAL), STRINGIFY(A) "_HARDWARE_SERIAL must be defined in the form MSerial1, rather than Serial1");
|
||||
|
||||
// If you encounter this error, replace SerialX with MSerialX, for example MSerial3.
|
||||
|
||||
// Non-TMC ports were already validated in HAL.h, so do not require verbose error messages.
|
||||
#ifdef MYSERIAL1
|
||||
CHECK_CFG_SERIAL(MYSERIAL1);
|
||||
#endif
|
||||
#ifdef MYSERIAL2
|
||||
CHECK_CFG_SERIAL(MYSERIAL2);
|
||||
#endif
|
||||
#ifdef LCD_SERIAL
|
||||
CHECK_CFG_SERIAL(LCD_SERIAL);
|
||||
#endif
|
||||
#if AXIS_HAS_HW_SERIAL(X)
|
||||
CHECK_AXIS_SERIAL(X);
|
||||
#endif
|
||||
#if AXIS_HAS_HW_SERIAL(X2)
|
||||
CHECK_AXIS_SERIAL(X2);
|
||||
#endif
|
||||
#if AXIS_HAS_HW_SERIAL(Y)
|
||||
CHECK_AXIS_SERIAL(Y);
|
||||
#endif
|
||||
#if AXIS_HAS_HW_SERIAL(Y2)
|
||||
CHECK_AXIS_SERIAL(Y2);
|
||||
#endif
|
||||
#if AXIS_HAS_HW_SERIAL(Z)
|
||||
CHECK_AXIS_SERIAL(Z);
|
||||
#endif
|
||||
#if AXIS_HAS_HW_SERIAL(Z2)
|
||||
CHECK_AXIS_SERIAL(Z2);
|
||||
#endif
|
||||
#if AXIS_HAS_HW_SERIAL(Z3)
|
||||
CHECK_AXIS_SERIAL(Z3);
|
||||
#endif
|
||||
#if AXIS_HAS_HW_SERIAL(Z4)
|
||||
CHECK_AXIS_SERIAL(Z4);
|
||||
#endif
|
||||
#if AXIS_HAS_HW_SERIAL(I)
|
||||
CHECK_AXIS_SERIAL(I);
|
||||
#endif
|
||||
#if AXIS_HAS_HW_SERIAL(J)
|
||||
CHECK_AXIS_SERIAL(J);
|
||||
#endif
|
||||
#if AXIS_HAS_HW_SERIAL(K)
|
||||
CHECK_AXIS_SERIAL(K);
|
||||
#endif
|
||||
#if AXIS_HAS_HW_SERIAL(E0)
|
||||
CHECK_AXIS_SERIAL(E0);
|
||||
#endif
|
||||
#if AXIS_HAS_HW_SERIAL(E1)
|
||||
CHECK_AXIS_SERIAL(E1);
|
||||
#endif
|
||||
#if AXIS_HAS_HW_SERIAL(E2)
|
||||
CHECK_AXIS_SERIAL(E2);
|
||||
#endif
|
||||
#if AXIS_HAS_HW_SERIAL(E3)
|
||||
CHECK_AXIS_SERIAL(E3);
|
||||
#endif
|
||||
#if AXIS_HAS_HW_SERIAL(E4)
|
||||
CHECK_AXIS_SERIAL(E4);
|
||||
#endif
|
||||
#if AXIS_HAS_HW_SERIAL(E5)
|
||||
CHECK_AXIS_SERIAL(E5);
|
||||
#endif
|
||||
#if AXIS_HAS_HW_SERIAL(E6)
|
||||
CHECK_AXIS_SERIAL(E6);
|
||||
#endif
|
||||
#if AXIS_HAS_HW_SERIAL(E7)
|
||||
CHECK_AXIS_SERIAL(E7);
|
||||
#endif
|
||||
|
||||
#endif // __STM32F1__
|
58
Marlin/src/HAL/STM32F1/MarlinSerial.h
Normal file
58
Marlin/src/HAL/STM32F1/MarlinSerial.h
Normal file
@@ -0,0 +1,58 @@
|
||||
/**
|
||||
* 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 <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include <HardwareSerial.h>
|
||||
#include <libmaple/usart.h>
|
||||
#include <WString.h>
|
||||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
#include "../../core/serial_hook.h"
|
||||
|
||||
// Increase priority of serial interrupts, to reduce overflow errors
|
||||
#define UART_IRQ_PRIO 1
|
||||
|
||||
struct MarlinSerial : public HardwareSerial {
|
||||
MarlinSerial(struct usart_dev *usart_device, uint8 tx_pin, uint8 rx_pin) : HardwareSerial(usart_device, tx_pin, rx_pin) { }
|
||||
|
||||
#ifdef UART_IRQ_PRIO
|
||||
// Shadow the parent methods to set IRQ priority after begin()
|
||||
void begin(uint32 baud) {
|
||||
MarlinSerial::begin(baud, SERIAL_8N1);
|
||||
}
|
||||
|
||||
void begin(uint32 baud, uint8_t config) {
|
||||
HardwareSerial::begin(baud, config);
|
||||
nvic_irq_set_priority(c_dev()->irq_num, UART_IRQ_PRIO);
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
typedef Serial1Class<MarlinSerial> MSerialT;
|
||||
|
||||
extern MSerialT MSerial1;
|
||||
extern MSerialT MSerial2;
|
||||
extern MSerialT MSerial3;
|
||||
#if EITHER(STM32_HIGH_DENSITY, STM32_XL_DENSITY)
|
||||
extern MSerialT MSerial4;
|
||||
extern MSerialT MSerial5;
|
||||
#endif
|
0
Marlin/src/HAL/STM32F1/README.md
Executable file → Normal file
0
Marlin/src/HAL/STM32F1/README.md
Executable file → Normal file
33
Marlin/src/HAL/STM32F1/SPI.cpp
Executable file → Normal file
33
Marlin/src/HAL/STM32F1/SPI.cpp
Executable file → Normal file
@@ -40,6 +40,9 @@
|
||||
#include <boards.h>
|
||||
#include <wirish.h>
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
#include "spi_pins.h"
|
||||
|
||||
/** Time in ms for DMA receive timeout */
|
||||
#define DMA_TIMEOUT 100
|
||||
|
||||
@@ -144,6 +147,18 @@ SPIClass::SPIClass(uint32_t spi_num) {
|
||||
_currentSetting->state = SPI_STATE_IDLE;
|
||||
}
|
||||
|
||||
SPIClass::SPIClass(int8_t mosi, int8_t miso, int8_t sclk, int8_t ssel) : SPIClass(1) {
|
||||
#if BOARD_NR_SPI >= 1
|
||||
if (mosi == BOARD_SPI1_MOSI_PIN) setModule(1);
|
||||
#endif
|
||||
#if BOARD_NR_SPI >= 2
|
||||
if (mosi == BOARD_SPI2_MOSI_PIN) setModule(2);
|
||||
#endif
|
||||
#if BOARD_NR_SPI >= 3
|
||||
if (mosi == BOARD_SPI3_MOSI_PIN) setModule(3);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* Set up/tear down
|
||||
*/
|
||||
@@ -216,7 +231,7 @@ 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
|
||||
* From the AVR doc https://www.atmel.com/images/doc2585.pdf section 2.4
|
||||
*
|
||||
* SPI Mode CPOL CPHA Shift SCK-edge Capture SCK-edge
|
||||
* 0 0 0 Falling Rising
|
||||
@@ -243,7 +258,7 @@ void SPIClass::setDataMode(uint8_t dataMode) {
|
||||
_currentSetting->spi_d->regs->CR1 = cr1 | (dataMode & (SPI_CR1_CPOL|SPI_CR1_CPHA));
|
||||
}
|
||||
|
||||
void SPIClass::beginTransaction(uint8_t pin, SPISettings settings) {
|
||||
void SPIClass::beginTransaction(uint8_t pin, const SPISettings &settings) {
|
||||
setBitOrder(settings.bitOrder);
|
||||
setDataMode(settings.dataMode);
|
||||
setDataSize(settings.dataSize);
|
||||
@@ -251,7 +266,7 @@ void SPIClass::beginTransaction(uint8_t pin, SPISettings settings) {
|
||||
begin();
|
||||
}
|
||||
|
||||
void SPIClass::beginTransactionSlave(SPISettings settings) {
|
||||
void SPIClass::beginTransactionSlave(const SPISettings &settings) {
|
||||
setBitOrder(settings.bitOrder);
|
||||
setDataMode(settings.dataMode);
|
||||
setDataSize(settings.dataSize);
|
||||
@@ -266,7 +281,7 @@ void SPIClass::endTransaction() { }
|
||||
|
||||
uint16_t SPIClass::read() {
|
||||
while (!spi_is_rx_nonempty(_currentSetting->spi_d)) { /* nada */ }
|
||||
return (uint16)spi_rx_reg(_currentSetting->spi_d);
|
||||
return (uint16_t)spi_rx_reg(_currentSetting->spi_d);
|
||||
}
|
||||
|
||||
void SPIClass::read(uint8_t *buf, uint32_t len) {
|
||||
@@ -277,7 +292,7 @@ void SPIClass::read(uint8_t *buf, uint32_t len) {
|
||||
regs->DR = 0x00FF; // write the first byte
|
||||
// main loop
|
||||
while (--len) {
|
||||
while(!(regs->SR & SPI_SR_TXE)) { /* nada */ } // wait for TXE flag
|
||||
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
|
||||
@@ -348,8 +363,8 @@ uint16_t SPIClass::transfer16(uint16_t data) const {
|
||||
/**
|
||||
* 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.
|
||||
* 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.
|
||||
*/
|
||||
void SPIClass::dmaTransferSet(const void *transmitBuf, void *receiveBuf) {
|
||||
@@ -653,7 +668,7 @@ static const spi_pins* dev_to_spi_pins(spi_dev *dev) {
|
||||
#if BOARD_NR_SPI >= 3
|
||||
case RCC_SPI3: return board_spi_pins + 2;
|
||||
#endif
|
||||
default: return NULL;
|
||||
default: return nullptr;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -710,6 +725,6 @@ static spi_baud_rate determine_baud_rate(spi_dev *dev, uint32_t freq) {
|
||||
return baud_rates[i];
|
||||
}
|
||||
|
||||
SPIClass SPI(1);
|
||||
SPIClass SPI(SPI_DEVICE);
|
||||
|
||||
#endif // __STM32F1__
|
||||
|
18
Marlin/src/HAL/STM32F1/SPI.h
Executable file → Normal file
18
Marlin/src/HAL/STM32F1/SPI.h
Executable file → Normal file
@@ -126,6 +126,7 @@ private:
|
||||
bitOrder = inBitOrder;
|
||||
dataMode = inDataMode;
|
||||
dataSize = inDataSize;
|
||||
//state = SPI_STATE_IDLE;
|
||||
}
|
||||
uint32_t clock;
|
||||
uint32_t dataSize;
|
||||
@@ -137,8 +138,8 @@ private:
|
||||
spi_dev *spi_d;
|
||||
dma_channel spiRxDmaChannel, spiTxDmaChannel;
|
||||
dma_dev* spiDmaDev;
|
||||
void (*receiveCallback)() = NULL;
|
||||
void (*transmitCallback)() = NULL;
|
||||
void (*receiveCallback)() = nullptr;
|
||||
void (*transmitCallback)() = nullptr;
|
||||
|
||||
friend class SPIClass;
|
||||
};
|
||||
@@ -162,6 +163,11 @@ public:
|
||||
*/
|
||||
SPIClass(uint32_t spiPortNumber);
|
||||
|
||||
/**
|
||||
* Init using pins
|
||||
*/
|
||||
SPIClass(int8_t mosi, int8_t miso, int8_t sclk, int8_t ssel=-1);
|
||||
|
||||
/**
|
||||
* @brief Equivalent to begin(SPI_1_125MHZ, MSBFIRST, 0).
|
||||
*/
|
||||
@@ -187,11 +193,11 @@ public:
|
||||
*/
|
||||
void end();
|
||||
|
||||
void beginTransaction(SPISettings settings) { beginTransaction(BOARD_SPI_DEFAULT_SS, settings); }
|
||||
void beginTransaction(uint8_t pin, SPISettings settings);
|
||||
void beginTransaction(const SPISettings &settings) { beginTransaction(BOARD_SPI_DEFAULT_SS, settings); }
|
||||
void beginTransaction(uint8_t pin, const SPISettings &settings);
|
||||
void endTransaction();
|
||||
|
||||
void beginTransactionSlave(SPISettings settings);
|
||||
void beginTransactionSlave(const SPISettings &settings);
|
||||
|
||||
void setClockDivider(uint32_t clockDivider);
|
||||
void setBitOrder(BitOrder bitOrder);
|
||||
@@ -207,6 +213,8 @@ public:
|
||||
*/
|
||||
void setDataSize(uint32_t ds);
|
||||
|
||||
uint32_t getDataSize() { return _currentSetting->dataSize; }
|
||||
|
||||
/* 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
|
||||
|
11
Marlin/src/HAL/STM32F1/Servo.cpp
Executable file → Normal file
11
Marlin/src/HAL/STM32F1/Servo.cpp
Executable file → Normal file
@@ -17,10 +17,9 @@
|
||||
* 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/>.
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifdef __STM32F1__
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
@@ -30,7 +29,6 @@
|
||||
uint8_t ServoCount = 0;
|
||||
|
||||
#include "Servo.h"
|
||||
#include "timers.h"
|
||||
|
||||
//#include "Servo.h"
|
||||
|
||||
@@ -47,7 +45,7 @@ uint8_t ServoCount = 0;
|
||||
*
|
||||
* This uses the smallest prescaler that allows an overflow < 2^16.
|
||||
*/
|
||||
#define MAX_OVERFLOW UINT16_MAX //((1 << 16) - 1)
|
||||
#define MAX_OVERFLOW UINT16_MAX // _BV(16) - 1
|
||||
#define CYC_MSEC (1000 * CYCLES_PER_MICROSECOND)
|
||||
#define TAU_MSEC 20
|
||||
#define TAU_USEC (TAU_MSEC * 1000)
|
||||
@@ -76,6 +74,7 @@ void libServo::servoWrite(uint8_t inPin, uint16_t duty_cycle) {
|
||||
|
||||
libServo::libServo() {
|
||||
servoIndex = ServoCount < MAX_SERVOS ? ServoCount++ : INVALID_SERVO;
|
||||
timer_set_interrupt_priority(SERVO0_TIMER_NUM, SERVO0_TIMER_IRQ_PRIO);
|
||||
}
|
||||
|
||||
bool libServo::attach(const int32_t inPin, const int32_t inMinAngle, const int32_t inMaxAngle) {
|
||||
@@ -138,9 +137,7 @@ void libServo::move(const int32_t value) {
|
||||
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
|
||||
TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach());
|
||||
}
|
||||
}
|
||||
|
||||
|
2
Marlin/src/HAL/STM32F1/Servo.h
Executable file → Normal file
2
Marlin/src/HAL/STM32F1/Servo.h
Executable file → Normal file
@@ -17,7 +17,7 @@
|
||||
* 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/>.
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
@@ -1,60 +0,0 @@
|
||||
/**
|
||||
* 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__
|
@@ -1,44 +0,0 @@
|
||||
/**
|
||||
* 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;
|
||||
};
|
@@ -3,7 +3,7 @@ import sys
|
||||
|
||||
#dynamic build flags for generic compile options
|
||||
if __name__ == "__main__":
|
||||
args = " ".join([ "-std=gnu11",
|
||||
args = " ".join([ "-std=gnu++14",
|
||||
"-Os",
|
||||
"-mcpu=cortex-m3",
|
||||
"-mthumb",
|
||||
@@ -11,6 +11,7 @@ if __name__ == "__main__":
|
||||
"-fsigned-char",
|
||||
"-fno-move-loop-invariants",
|
||||
"-fno-strict-aliasing",
|
||||
"-fsingle-precision-constant",
|
||||
|
||||
"--specs=nano.specs",
|
||||
"--specs=nosys.specs",
|
||||
|
25
Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp
Executable file → Normal file
25
Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp
Executable file → Normal file
@@ -2,6 +2,9 @@
|
||||
* 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
|
||||
@@ -13,23 +16,25 @@
|
||||
* 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/>.
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifdef __STM32F1__
|
||||
|
||||
#include "../../../inc/MarlinConfig.h"
|
||||
|
||||
#if HAS_GRAPHICAL_LCD && ENABLED(FORCE_SOFT_SPI)
|
||||
#if BOTH(HAS_MARLINUI_U8GLIB, FORCE_SOFT_SPI)
|
||||
|
||||
#include "../HAL.h"
|
||||
#include <U8glib.h>
|
||||
#include <U8glib-HAL.h>
|
||||
#include "../../shared/HAL_SPI.h"
|
||||
|
||||
#undef SPI_SPEED
|
||||
#define SPI_SPEED 0 // Fastest
|
||||
//#define SPI_SPEED 2 // Slower
|
||||
#ifndef LCD_SPI_SPEED
|
||||
#define LCD_SPI_SPEED SPI_FULL_SPEED // Fastest
|
||||
//#define LCD_SPI_SPEED SPI_QUARTER_SPEED // Slower
|
||||
#endif
|
||||
|
||||
static uint8_t SPI_speed = SPI_SPEED;
|
||||
static uint8_t SPI_speed = LCD_SPI_SPEED;
|
||||
|
||||
static inline uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, const pin_t miso_pin=-1) {
|
||||
LOOP_L_N(i, 8) {
|
||||
@@ -105,7 +110,7 @@ static uint8_t swSpiInit(const uint8_t 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);
|
||||
SPI_speed = swSpiInit(LCD_SPI_SPEED);
|
||||
break;
|
||||
|
||||
case U8G_COM_MSG_STOP:
|
||||
@@ -161,5 +166,5 @@ uint8_t u8g_com_HAL_STM32F1_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val,
|
||||
return 1;
|
||||
}
|
||||
|
||||
#endif // HAS_GRAPHICAL_LCD
|
||||
#endif // HAS_MARLINUI_U8GLIB && FORCE_SOFT_SPI
|
||||
#endif // STM32F1
|
||||
|
82
Marlin/src/HAL/STM32F1/eeprom_bl24cxx.cpp
Normal file
82
Marlin/src/HAL/STM32F1/eeprom_bl24cxx.cpp
Normal file
@@ -0,0 +1,82 @@
|
||||
/**
|
||||
* 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 <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#ifdef __STM32F1__
|
||||
|
||||
/**
|
||||
* PersistentStore for Arduino-style EEPROM interface
|
||||
* with simple implementations supplied by Marlin.
|
||||
*/
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#if ENABLED(IIC_BL24CXX_EEPROM)
|
||||
|
||||
#include "../shared/eeprom_if.h"
|
||||
#include "../shared/eeprom_api.h"
|
||||
|
||||
//
|
||||
// PersistentStore
|
||||
//
|
||||
|
||||
#ifndef MARLIN_EEPROM_SIZE
|
||||
#error "MARLIN_EEPROM_SIZE is required for IIC_BL24CXX_EEPROM."
|
||||
#endif
|
||||
|
||||
size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
|
||||
|
||||
bool PersistentStore::access_start() { eeprom_init(); return true; }
|
||||
bool PersistentStore::access_finish() { return true; }
|
||||
|
||||
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
|
||||
uint16_t written = 0;
|
||||
while (size--) {
|
||||
uint8_t v = *value;
|
||||
uint8_t * const p = (uint8_t * const)pos;
|
||||
if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed!
|
||||
eeprom_write_byte(p, v);
|
||||
if (++written & 0x7F) delay(2); else safe_delay(2); // Avoid triggering watchdog during long EEPROM writes
|
||||
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 * const p = (uint8_t * const)pos;
|
||||
uint8_t c = eeprom_read_byte(p);
|
||||
if (writing) *value = c;
|
||||
crc16(crc, &c, 1);
|
||||
pos++;
|
||||
value++;
|
||||
} while (--size);
|
||||
return false;
|
||||
}
|
||||
|
||||
#endif // IIC_BL24CXX_EEPROM
|
||||
#endif // __STM32F1__
|
26
Marlin/src/HAL/STM32F1/eeprom_flash.cpp
Executable file → Normal file
26
Marlin/src/HAL/STM32F1/eeprom_flash.cpp
Executable file → Normal file
@@ -17,7 +17,7 @@
|
||||
* 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/>.
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
@@ -39,18 +39,20 @@
|
||||
#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)
|
||||
#ifndef MARLIN_EEPROM_SIZE
|
||||
#define MARLIN_EEPROM_SIZE ((EEPROM_PAGE_SIZE) * 2)
|
||||
#endif
|
||||
size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
|
||||
|
||||
static uint8_t ram_eeprom[EEPROM_SIZE] __attribute__((aligned(4))) = {0};
|
||||
static uint8_t ram_eeprom[MARLIN_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);
|
||||
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;
|
||||
static_assert(0 == (MARLIN_EEPROM_SIZE) % 4, "MARLIN_EEPROM_SIZE is corrupted. (Must be a multiple of 4.)"); // Ensure copying as uint32_t is safe
|
||||
constexpr size_t eeprom_size_u32 = (MARLIN_EEPROM_SIZE) / 4;
|
||||
|
||||
for (size_t i = 0; i < eeprom_size_u32; ++i, ++destination, ++source)
|
||||
*destination = *source;
|
||||
@@ -72,13 +74,15 @@ bool PersistentStore::access_finish() {
|
||||
// page changes...either way, something to look at later.
|
||||
FLASH_Unlock();
|
||||
|
||||
#define ACCESS_FINISHED(TF) { FLASH_Lock(); eeprom_dirty = false; return TF; }
|
||||
|
||||
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) {
|
||||
for (size_t i = 0; i < MARLIN_EEPROM_SIZE; i += 2, ++source) {
|
||||
if (FLASH_ProgramHalfWord(EEPROM_PAGE0_BASE + i, *source) != FLASH_COMPLETE)
|
||||
ACCESS_FINISHED(false);
|
||||
}
|
||||
@@ -97,7 +101,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui
|
||||
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*/) {
|
||||
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);
|
||||
@@ -105,7 +109,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, const size_t size, uin
|
||||
return false; // return true for any error
|
||||
}
|
||||
|
||||
size_t PersistentStore::capacity() { return EEPROM_SIZE; }
|
||||
|
||||
#endif // FLASH_EEPROM_EMULATION
|
||||
#endif // __STM32F1__
|
||||
|
54
Marlin/src/HAL/STM32F1/eeprom_if_iic.cpp
Normal file
54
Marlin/src/HAL/STM32F1/eeprom_if_iic.cpp
Normal file
@@ -0,0 +1,54 @@
|
||||
/**
|
||||
* 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 <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* Platform-independent Arduino functions for I2C EEPROM.
|
||||
* Enable USE_SHARED_EEPROM if not supplied by the framework.
|
||||
*/
|
||||
|
||||
#ifdef __STM32F1__
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#if ENABLED(IIC_BL24CXX_EEPROM)
|
||||
|
||||
#include "../../libs/BL24CXX.h"
|
||||
#include "../shared/eeprom_if.h"
|
||||
|
||||
void eeprom_init() { BL24CXX::init(); }
|
||||
|
||||
// ------------------------
|
||||
// Public functions
|
||||
// ------------------------
|
||||
|
||||
void eeprom_write_byte(uint8_t *pos, uint8_t value) {
|
||||
const unsigned eeprom_address = (unsigned)pos;
|
||||
return BL24CXX::writeOneByte(eeprom_address, value);
|
||||
}
|
||||
|
||||
uint8_t eeprom_read_byte(uint8_t *pos) {
|
||||
const unsigned eeprom_address = (unsigned)pos;
|
||||
return BL24CXX::readOneByte(eeprom_address);
|
||||
}
|
||||
|
||||
#endif // IIC_BL24CXX_EEPROM
|
||||
#endif // __STM32F1__
|
69
Marlin/src/HAL/STM32F1/eeprom_sdcard.cpp
Executable file → Normal file
69
Marlin/src/HAL/STM32F1/eeprom_sdcard.cpp
Executable file → Normal file
@@ -16,7 +16,7 @@
|
||||
* 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/>.
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
@@ -32,53 +32,44 @@
|
||||
#if ENABLED(SDCARD_EEPROM_EMULATION)
|
||||
|
||||
#include "../shared/eeprom_api.h"
|
||||
#include "../../sd/cardreader.h"
|
||||
|
||||
#ifndef E2END
|
||||
#define E2END 0xFFF // 4KB
|
||||
#define EEPROM_FILENAME "eeprom.dat"
|
||||
|
||||
#ifndef MARLIN_EEPROM_SIZE
|
||||
#define MARLIN_EEPROM_SIZE 0x1000 // 4KB
|
||||
#endif
|
||||
#define HAL_EEPROM_SIZE (E2END + 1)
|
||||
size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
|
||||
|
||||
#define _ALIGN(x) __attribute__ ((aligned(x))) // SDIO uint32_t* compat.
|
||||
static char _ALIGN(4) HAL_eeprom_data[HAL_EEPROM_SIZE];
|
||||
static char _ALIGN(4) HAL_eeprom_data[MARLIN_EEPROM_SIZE];
|
||||
|
||||
#if ENABLED(SDSUPPORT)
|
||||
bool PersistentStore::access_start() {
|
||||
if (!card.isMounted()) return false;
|
||||
|
||||
#include "../../sd/cardreader.h"
|
||||
SdFile file, root = card.getroot();
|
||||
if (!file.open(&root, EEPROM_FILENAME, O_RDONLY))
|
||||
return true; // false aborts the save
|
||||
|
||||
#define EEPROM_FILENAME "eeprom.dat"
|
||||
int bytes_read = file.read(HAL_eeprom_data, MARLIN_EEPROM_SIZE);
|
||||
if (bytes_read < 0) return false;
|
||||
for (; bytes_read < MARLIN_EEPROM_SIZE; bytes_read++)
|
||||
HAL_eeprom_data[bytes_read] = 0xFF;
|
||||
file.close();
|
||||
return true;
|
||||
}
|
||||
|
||||
bool PersistentStore::access_start() {
|
||||
if (!card.isMounted()) return false;
|
||||
bool PersistentStore::access_finish() {
|
||||
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;
|
||||
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, MARLIN_EEPROM_SIZE);
|
||||
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
|
||||
return (bytes_written == MARLIN_EEPROM_SIZE);
|
||||
}
|
||||
|
||||
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
|
||||
for (size_t i = 0; i < size; i++)
|
||||
@@ -88,7 +79,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui
|
||||
return false;
|
||||
}
|
||||
|
||||
bool PersistentStore::read_data(int &pos, uint8_t* value, const size_t size, uint16_t *crc, const bool writing/*=true*/) {
|
||||
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;
|
||||
@@ -98,7 +89,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, const size_t size, uin
|
||||
return false;
|
||||
}
|
||||
|
||||
size_t PersistentStore::capacity() { return HAL_EEPROM_SIZE; }
|
||||
|
||||
#endif // SDCARD_EEPROM_EMULATION
|
||||
#endif // __STM32F1__
|
||||
|
34
Marlin/src/HAL/STM32F1/eeprom.cpp → Marlin/src/HAL/STM32F1/eeprom_wired.cpp
Executable file → Normal file
34
Marlin/src/HAL/STM32F1/eeprom.cpp → Marlin/src/HAL/STM32F1/eeprom_wired.cpp
Executable file → Normal file
@@ -1,8 +1,10 @@
|
||||
/**
|
||||
* 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
|
||||
@@ -14,40 +16,52 @@
|
||||
* 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/>.
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* HAL PersistentStore for STM32F1
|
||||
*/
|
||||
|
||||
#ifdef __STM32F1__
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#if USE_WIRED_EEPROM
|
||||
|
||||
#include "../shared/eeprom_if.h"
|
||||
#include "../shared/eeprom_api.h"
|
||||
|
||||
#ifndef MARLIN_EEPROM_SIZE
|
||||
#error "MARLIN_EEPROM_SIZE is required for I2C / SPI EEPROM."
|
||||
#endif
|
||||
size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
|
||||
|
||||
bool PersistentStore::access_finish() { return true; }
|
||||
|
||||
bool PersistentStore::access_start() {
|
||||
eeprom_init();
|
||||
#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);
|
||||
SET_OUTPUT(SPI_EEPROM1_CS_PIN);
|
||||
#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) {
|
||||
uint16_t written = 0;
|
||||
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)) {
|
||||
if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed!
|
||||
eeprom_write_byte(p, v);
|
||||
if (++written & 0x7F) delay(2); else safe_delay(2); // Avoid triggering watchdog during long EEPROM writes
|
||||
if (eeprom_read_byte(p) != v) {
|
||||
SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE);
|
||||
return true;
|
||||
@@ -56,11 +70,11 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui
|
||||
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*/) {
|
||||
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;
|
||||
@@ -71,7 +85,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t
|
||||
return false;
|
||||
}
|
||||
|
||||
size_t PersistentStore::capacity() { return E2END + 1; }
|
||||
|
||||
#endif // USE_WIRED_EEPROM
|
||||
#endif // __STM32F1__
|
65
Marlin/src/HAL/STM32F1/endstop_interrupts.h
Executable file → Normal file
65
Marlin/src/HAL/STM32F1/endstop_interrupts.h
Executable file → Normal file
@@ -17,7 +17,7 @@
|
||||
* 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/>.
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
@@ -53,43 +53,28 @@
|
||||
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
|
||||
#define _ATTACH(P) attachInterrupt(P, endstop_ISR, CHANGE)
|
||||
TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN));
|
||||
TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN));
|
||||
TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN));
|
||||
TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN));
|
||||
TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN));
|
||||
TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN));
|
||||
TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN));
|
||||
TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN));
|
||||
TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN));
|
||||
TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN));
|
||||
TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN));
|
||||
TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN));
|
||||
TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN));
|
||||
TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN));
|
||||
TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
|
||||
TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
|
||||
TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
|
||||
TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN));
|
||||
TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN));
|
||||
TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN));
|
||||
TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN));
|
||||
TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN));
|
||||
TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN));
|
||||
}
|
||||
|
68
Marlin/src/HAL/STM32F1/fast_pwm.cpp
Normal file
68
Marlin/src/HAL/STM32F1/fast_pwm.cpp
Normal file
@@ -0,0 +1,68 @@
|
||||
/**
|
||||
* 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 <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#ifdef __STM32F1__
|
||||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if NEEDS_HARDWARE_PWM
|
||||
|
||||
#include <pwm.h>
|
||||
#include "HAL.h"
|
||||
#include "timers.h"
|
||||
|
||||
void set_pwm_frequency(const pin_t pin, int f_desired) {
|
||||
if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer
|
||||
|
||||
timer_dev *timer = PIN_MAP[pin].timer_device;
|
||||
uint8_t channel = PIN_MAP[pin].timer_channel;
|
||||
|
||||
// Protect used timers
|
||||
if (timer == get_timer_dev(TEMP_TIMER_NUM)) return;
|
||||
if (timer == get_timer_dev(STEP_TIMER_NUM)) return;
|
||||
#if PULSE_TIMER_NUM != STEP_TIMER_NUM
|
||||
if (timer == get_timer_dev(PULSE_TIMER_NUM)) return;
|
||||
#endif
|
||||
|
||||
if (!(timer->regs.bas->SR & TIMER_CR1_CEN)) // Ensure the timer is enabled
|
||||
timer_init(timer);
|
||||
|
||||
timer_set_mode(timer, channel, TIMER_PWM);
|
||||
uint16_t preload = 255; // Lock 255 PWM resolution for high frequencies
|
||||
int32_t prescaler = (HAL_TIMER_RATE) / (preload + 1) / f_desired - 1;
|
||||
if (prescaler > 65535) { // For low frequencies increase prescaler
|
||||
prescaler = 65535;
|
||||
preload = (HAL_TIMER_RATE) / (prescaler + 1) / f_desired - 1;
|
||||
}
|
||||
if (prescaler < 0) return; // Too high frequency
|
||||
timer_set_reload(timer, preload);
|
||||
timer_set_prescaler(timer, prescaler);
|
||||
}
|
||||
|
||||
void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) {
|
||||
timer_dev *timer = PIN_MAP[pin].timer_device;
|
||||
uint16_t max_val = timer->regs.bas->ARR * v / v_size;
|
||||
if (invert) max_val = v_size - max_val;
|
||||
pwmWrite(pin, max_val);
|
||||
}
|
||||
|
||||
#endif // NEEDS_HARDWARE_PWM
|
||||
#endif // __STM32F1__
|
10
Marlin/src/HAL/STM32F1/fastio.h
Executable file → Normal file
10
Marlin/src/HAL/STM32F1/fastio.h
Executable file → Normal file
@@ -17,7 +17,7 @@
|
||||
* 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/>.
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
@@ -29,9 +29,9 @@
|
||||
|
||||
#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 READ(IO) (PIN_MAP[IO].gpio_device->regs->IDR & _BV32(PIN_MAP[IO].gpio_bit) ? HIGH : LOW)
|
||||
#define WRITE(IO,V) (PIN_MAP[IO].gpio_device->regs->BSRR = _BV32(PIN_MAP[IO].gpio_bit) << ((V) ? 0 : 16))
|
||||
#define TOGGLE(IO) TBI32(PIN_MAP[IO].gpio_device->regs->ODR, 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)
|
||||
@@ -51,7 +51,7 @@
|
||||
#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)
|
||||
#define PWM_PIN(IO) !!PIN_MAP[IO].timer_device
|
||||
|
||||
// digitalRead/Write wrappers
|
||||
#define extDigitalRead(IO) digitalRead(IO)
|
||||
|
2
Marlin/src/HAL/STM32F1/inc/Conditionals_LCD.h
Executable file → Normal file
2
Marlin/src/HAL/STM32F1/inc/Conditionals_LCD.h
Executable file → Normal file
@@ -16,7 +16,7 @@
|
||||
* 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/>.
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
10
Marlin/src/HAL/STM32F1/inc/Conditionals_adv.h
Executable file → Normal file
10
Marlin/src/HAL/STM32F1/inc/Conditionals_adv.h
Executable file → Normal file
@@ -16,7 +16,15 @@
|
||||
* 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/>.
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#ifdef USE_USB_COMPOSITE
|
||||
//#warning "SD_CHECK_AND_RETRY isn't needed with USE_USB_COMPOSITE."
|
||||
#undef SD_CHECK_AND_RETRY
|
||||
#if DISABLED(NO_SD_HOST_DRIVE)
|
||||
#define HAS_SD_HOST_DRIVE 1
|
||||
#endif
|
||||
#endif
|
||||
|
14
Marlin/src/HAL/STM32F1/inc/Conditionals_post.h
Executable file → Normal file
14
Marlin/src/HAL/STM32F1/inc/Conditionals_post.h
Executable file → Normal file
@@ -16,7 +16,19 @@
|
||||
* 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/>.
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
// If no real EEPROM, Flash emulation, or SRAM emulation is available fall back to SD emulation
|
||||
#if USE_FALLBACK_EEPROM
|
||||
#define SDCARD_EEPROM_EMULATION
|
||||
#elif EITHER(I2C_EEPROM, SPI_EEPROM)
|
||||
#define USE_SHARED_EEPROM 1
|
||||
#endif
|
||||
|
||||
// Allow SDSUPPORT to be disabled
|
||||
#if DISABLED(SDSUPPORT)
|
||||
#undef SDIO_SUPPORT
|
||||
#endif
|
||||
|
28
Marlin/src/HAL/STM32F1/inc/SanityCheck.h
Executable file → Normal file
28
Marlin/src/HAL/STM32F1/inc/SanityCheck.h
Executable file → Normal file
@@ -16,7 +16,7 @@
|
||||
* 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/>.
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
@@ -25,19 +25,27 @@
|
||||
* 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."
|
||||
#if ENABLED(SDCARD_EEPROM_EMULATION) && DISABLED(SDSUPPORT)
|
||||
#undef SDCARD_EEPROM_EMULATION // Avoid additional error noise
|
||||
#if USE_FALLBACK_EEPROM
|
||||
#warning "EEPROM type not specified. Fallback is SDCARD_EEPROM_EMULATION."
|
||||
#endif
|
||||
#error "SDCARD_EEPROM_EMULATION requires SDSUPPORT. Enable SDSUPPORT or choose another EEPROM emulation."
|
||||
#endif
|
||||
|
||||
#if ENABLED(SDIO_SUPPORT) && DISABLED(SDSUPPORT)
|
||||
#error "SDIO_SUPPORT requires SDSUPPORT. Enable SDSUPPORT to continue."
|
||||
#if ENABLED(SERIAL_STATS_MAX_RX_QUEUED)
|
||||
#error "SERIAL_STATS_MAX_RX_QUEUED is not supported on the STM32F1 platform."
|
||||
#elif ENABLED(SERIAL_STATS_DROPPED_RX)
|
||||
#error "SERIAL_STATS_DROPPED_RX is not supported on the STM32F1 platform."
|
||||
#endif
|
||||
|
||||
#if ENABLED(FAST_PWM_FAN)
|
||||
#error "FAST_PWM_FAN is not yet implemented for this platform."
|
||||
#if ENABLED(NEOPIXEL_LED) && DISABLED(MKS_MINI_12864_V3)
|
||||
#error "NEOPIXEL_LED (Adafruit NeoPixel) is not supported for HAL/STM32F1. Comment out this line to proceed at your own risk!"
|
||||
#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."
|
||||
// Emergency Parser needs at least one serial with HardwareSerial or USBComposite.
|
||||
// The USBSerial maple don't allow any hook to implement EMERGENCY_PARSER.
|
||||
// And copy all USBSerial code to marlin space to support EMERGENCY_PARSER, when we have another options, don't worth it.
|
||||
#if ENABLED(EMERGENCY_PARSER) && !defined(USE_USB_COMPOSITE) && ((SERIAL_PORT == -1 && !defined(SERIAL_PORT_2)) || (SERIAL_PORT_2 == -1 && !defined(SERIAL_PORT)))
|
||||
#error "EMERGENCY_PARSER is only supported by HardwareSerial or USBComposite in HAL/STM32F1."
|
||||
#endif
|
||||
|
0
Marlin/src/HAL/STM32F1/maple_win_usb_driver/maple_serial.inf
Executable file → Normal file
0
Marlin/src/HAL/STM32F1/maple_win_usb_driver/maple_serial.inf
Executable file → Normal file
46
Marlin/src/HAL/STM32F1/msc_sd.cpp
Executable file → Normal file
46
Marlin/src/HAL/STM32F1/msc_sd.cpp
Executable file → Normal file
@@ -10,22 +10,27 @@
|
||||
* (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/>.
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#ifdef USE_USB_COMPOSITE
|
||||
#ifdef __STM32F1__
|
||||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if HAS_SD_HOST_DRIVE
|
||||
|
||||
#include "msc_sd.h"
|
||||
#include "SPI.h"
|
||||
#include "usb_reg_map.h"
|
||||
|
||||
#define PRODUCT_ID 0x29
|
||||
|
||||
USBMassStorage MarlinMSC;
|
||||
USBCompositeSerial MarlinCompositeSerial;
|
||||
Serial1Class<USBCompositeSerial> MarlinCompositeSerial(true);
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#ifdef HAS_ONBOARD_SD
|
||||
#if SD_CONNECTION_IS(ONBOARD)
|
||||
|
||||
#include "onboard_sd.h"
|
||||
|
||||
@@ -38,6 +43,31 @@ USBCompositeSerial MarlinCompositeSerial;
|
||||
|
||||
#endif
|
||||
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
|
||||
// The original callback is not called (no way to retrieve address).
|
||||
// That callback detects a special STM32 reset sequence: this functionality is not essential
|
||||
// as M997 achieves the same.
|
||||
void my_rx_callback(unsigned int, void*) {
|
||||
// max length of 16 is enough to contain all emergency commands
|
||||
uint8 buf[16];
|
||||
|
||||
//rx is usbSerialPart.endpoints[2]
|
||||
uint16 len = usb_get_ep_rx_count(usbSerialPart.endpoints[2].address);
|
||||
uint32 total = composite_cdcacm_data_available();
|
||||
|
||||
if (len == 0 || total == 0 || !WITHIN(total, len, COUNT(buf)))
|
||||
return;
|
||||
|
||||
// cannot get character by character due to bug in composite_cdcacm_peek_ex
|
||||
len = composite_cdcacm_peek(buf, total);
|
||||
|
||||
for (uint32 i = 0; i < len; i++)
|
||||
emergency_parser.update(MarlinCompositeSerial.emergency_state, buf[i+total-len]);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
void MSC_SD_init() {
|
||||
USBComposite.setProductId(PRODUCT_ID);
|
||||
// Just set MarlinCompositeSerial enabled to true
|
||||
@@ -47,7 +77,7 @@ void MSC_SD_init() {
|
||||
USBComposite.end();
|
||||
USBComposite.clear();
|
||||
// Set api and register mass storage
|
||||
#ifdef HAS_ONBOARD_SD
|
||||
#if SD_CONNECTION_IS(ONBOARD)
|
||||
uint32_t cardSize;
|
||||
if (disk_initialize(0) == RES_OK) {
|
||||
if (disk_ioctl(0, GET_SECTOR_COUNT, (void *)(&cardSize)) == RES_OK) {
|
||||
@@ -59,6 +89,10 @@ void MSC_SD_init() {
|
||||
// Register composite Serial
|
||||
MarlinCompositeSerial.registerComponent();
|
||||
USBComposite.begin();
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
composite_cdcacm_set_hooks(USBHID_CDCACM_HOOK_RX, my_rx_callback);
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif // USE_USB_COMPOSITE
|
||||
#endif // HAS_SD_HOST_DRIVE
|
||||
#endif // __STM32F1__
|
||||
|
7
Marlin/src/HAL/STM32F1/msc_sd.h
Executable file → Normal file
7
Marlin/src/HAL/STM32F1/msc_sd.h
Executable file → Normal file
@@ -10,14 +10,17 @@
|
||||
* (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/>.
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include <USBComposite.h>
|
||||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
#include "../../core/serial_hook.h"
|
||||
|
||||
extern USBMassStorage MarlinMSC;
|
||||
extern USBCompositeSerial MarlinCompositeSerial;
|
||||
extern Serial1Class<USBCompositeSerial> MarlinCompositeSerial;
|
||||
|
||||
void MSC_SD_init();
|
||||
|
386
Marlin/src/HAL/STM32F1/onboard_sd.cpp
Executable file → Normal file
386
Marlin/src/HAL/STM32F1/onboard_sd.cpp
Executable file → Normal file
@@ -9,35 +9,37 @@
|
||||
* 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.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifdef __STM32F1__
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#ifdef HAS_ONBOARD_SD
|
||||
#if SD_CONNECTION_IS(ONBOARD)
|
||||
|
||||
#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
|
||||
#ifndef ONBOARD_SPI_DEVICE
|
||||
#define ONBOARD_SPI_DEVICE SPI_DEVICE
|
||||
#endif
|
||||
|
||||
#if ON_BOARD_SPI_DEVICE == 1
|
||||
#if HAS_SD_HOST_DRIVE
|
||||
#define ONBOARD_SD_SPI SPI
|
||||
#else
|
||||
SPIClass OnboardSPI(ONBOARD_SPI_DEVICE);
|
||||
#define ONBOARD_SD_SPI OnboardSPI
|
||||
#endif
|
||||
|
||||
#if ONBOARD_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 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)
|
||||
@@ -47,32 +49,32 @@
|
||||
---------------------------------------------------------------------------*/
|
||||
|
||||
/* 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 */
|
||||
#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 DSTATUS Stat = STA_NOINIT; // Physical drive status
|
||||
static volatile UINT timeout;
|
||||
static BYTE CardType; /* Card type flags */
|
||||
static BYTE CardType; // Card type flags
|
||||
|
||||
/*-----------------------------------------------------------------------*/
|
||||
/* Send/Receive data to the MMC (Platform dependent) */
|
||||
@@ -80,7 +82,7 @@ static BYTE CardType; /* Card type flags */
|
||||
|
||||
/* Exchange a byte */
|
||||
static BYTE xchg_spi (
|
||||
BYTE dat /* Data to send */
|
||||
BYTE dat // Data to send
|
||||
) {
|
||||
BYTE returnByte = ONBOARD_SD_SPI.transfer(dat);
|
||||
return returnByte;
|
||||
@@ -88,18 +90,18 @@ static BYTE xchg_spi (
|
||||
|
||||
/* 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) */
|
||||
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 */
|
||||
// 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) */
|
||||
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);
|
||||
}
|
||||
@@ -110,16 +112,15 @@ static void rcvr_spi_multi (
|
||||
/* Wait for card ready */
|
||||
/*-----------------------------------------------------------------------*/
|
||||
|
||||
static int wait_ready ( /* 1:Ready, 0:Timeout */
|
||||
UINT wt /* Timeout [ms] */
|
||||
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 */
|
||||
// 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;
|
||||
}
|
||||
@@ -129,21 +130,21 @@ static int wait_ready ( /* 1:Ready, 0:Timeout */
|
||||
/*-----------------------------------------------------------------------*/
|
||||
|
||||
static void deselect() {
|
||||
CS_HIGH(); /* CS = H */
|
||||
xchg_spi(0xFF); /* Dummy clock (force DO hi-z for multiple slave SPI) */
|
||||
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) */
|
||||
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 */
|
||||
if (wait_ready(500)) return 1; // Leading busy check: Wait for card ready
|
||||
|
||||
deselect(); /* Timeout */
|
||||
deselect(); // Timeout
|
||||
return 0;
|
||||
}
|
||||
|
||||
@@ -151,16 +152,18 @@ static int select() { /* 1:OK, 0:Timeout */
|
||||
/* 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);
|
||||
// Enable SSP module and attach it to I/O pads
|
||||
static void sd_power_on() {
|
||||
ONBOARD_SD_SPI.setModule(ONBOARD_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 */
|
||||
CS_HIGH();
|
||||
}
|
||||
|
||||
static void power_off() { /* Disable SPI function */
|
||||
select(); /* Wait for card ready */
|
||||
// Disable SPI function
|
||||
static void sd_power_off() {
|
||||
select(); // Wait for card ready
|
||||
deselect();
|
||||
}
|
||||
|
||||
@@ -168,23 +171,23 @@ static void power_off() { /* Disable SPI function */
|
||||
/* 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) */
|
||||
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 */
|
||||
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. */
|
||||
// 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 */
|
||||
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 */
|
||||
rcvr_spi_multi(buff, btr); // Store trailing data to the buffer
|
||||
xchg_spi(0xFF); xchg_spi(0xFF); // Discard CRC
|
||||
|
||||
return 1; /* Function succeeded */
|
||||
return 1; // Function succeeded
|
||||
}
|
||||
|
||||
/*-----------------------------------------------------------------------*/
|
||||
@@ -193,25 +196,25 @@ static int rcvr_datablock ( /* 1:OK, 0:Error */
|
||||
|
||||
#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 */
|
||||
static int xmit_datablock( // 1:OK, 0:Failed
|
||||
const BYTE *buff, // Pointer 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 */
|
||||
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 */
|
||||
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 */
|
||||
xmit_spi_multi(buff, 512); // Data
|
||||
xchg_spi(0xFF); xchg_spi(0xFF); // Dummy CRC
|
||||
|
||||
resp = xchg_spi(0xFF); /* Receive data resp */
|
||||
resp = xchg_spi(0xFF); // Receive data resp
|
||||
|
||||
return (resp & 0x1F) == 0x05 ? 1 : 0; /* Data was accepted or not */
|
||||
return (resp & 0x1F) == 0x05 ? 1 : 0; // Data was accepted or not
|
||||
|
||||
/* Busy check is done at next transmission */
|
||||
// Busy check is done at next transmission
|
||||
}
|
||||
|
||||
#endif // _DISKIO_WRITE
|
||||
@@ -220,43 +223,43 @@ static int rcvr_datablock ( /* 1:OK, 0:Error */
|
||||
/* 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 */
|
||||
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> */
|
||||
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 */
|
||||
// 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) */
|
||||
// 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) */
|
||||
// Receive command response
|
||||
if (cmd == CMD12) xchg_spi(0xFF); // Discard the following 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 */
|
||||
return res; // Return received response
|
||||
}
|
||||
|
||||
/*--------------------------------------------------------------------------
|
||||
@@ -268,49 +271,52 @@ static BYTE send_cmd ( /* Return value: R1 resp (bit7==1:Failed to send) */
|
||||
/*-----------------------------------------------------------------------*/
|
||||
|
||||
DSTATUS disk_initialize (
|
||||
BYTE drv /* Physical drive number (0) */
|
||||
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 (drv) return STA_NOINIT; // Supports only drive 0
|
||||
sd_power_on(); // Initialize SPI
|
||||
|
||||
if (Stat & STA_NODISK) return Stat; /* Is a card existing in the soket? */
|
||||
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 */
|
||||
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 */
|
||||
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 */
|
||||
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)) */
|
||||
}
|
||||
else { // Not an SDv2 card
|
||||
if (send_cmd(ACMD41, 0) <= 1) { // SDv1 or MMCv3?
|
||||
ty = CT_SD1; cmd = ACMD41; // SDv1 (ACMD41(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 */
|
||||
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 */
|
||||
CardType = ty; // Card type
|
||||
deselect();
|
||||
|
||||
if (ty) { /* OK */
|
||||
FCLK_FAST(); /* Set fast clock */
|
||||
Stat &= ~STA_NOINIT; /* Clear STA_NOINIT flag */
|
||||
} else { /* Failed */
|
||||
power_off();
|
||||
if (ty) { // OK
|
||||
FCLK_FAST(); // Set fast clock
|
||||
Stat &= ~STA_NOINIT; // Clear STA_NOINIT flag
|
||||
}
|
||||
else { // Failed
|
||||
sd_power_off();
|
||||
Stat = STA_NOINIT;
|
||||
}
|
||||
|
||||
@@ -322,10 +328,10 @@ DSTATUS disk_initialize (
|
||||
/*-----------------------------------------------------------------------*/
|
||||
|
||||
DSTATUS disk_status (
|
||||
BYTE drv /* Physical drive number (0) */
|
||||
BYTE drv // Physical drive number (0)
|
||||
) {
|
||||
if (drv) return STA_NOINIT; /* Supports only drive 0 */
|
||||
return Stat; /* Return disk status */
|
||||
if (drv) return STA_NOINIT; // Supports only drive 0
|
||||
return Stat; // Return disk status
|
||||
}
|
||||
|
||||
/*-----------------------------------------------------------------------*/
|
||||
@@ -333,28 +339,28 @@ DSTATUS disk_status (
|
||||
/*-----------------------------------------------------------------------*/
|
||||
|
||||
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 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) */
|
||||
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 */
|
||||
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 */
|
||||
if (cmd == CMD18) send_cmd(CMD12, 0); // STOP_TRANSMISSION
|
||||
}
|
||||
deselect();
|
||||
|
||||
return count ? RES_ERROR : RES_OK; /* Return result */
|
||||
return count ? RES_ERROR : RES_OK; // Return result
|
||||
}
|
||||
|
||||
/*-----------------------------------------------------------------------*/
|
||||
@@ -364,36 +370,36 @@ DRESULT disk_read (
|
||||
#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) */
|
||||
BYTE drv, // Physical drive number (0)
|
||||
const BYTE *buff, // Pointer 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 */
|
||||
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 (!(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 */
|
||||
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 */
|
||||
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 */
|
||||
if (!xmit_datablock(0, 0xFD)) count = 1; // STOP_TRAN token
|
||||
}
|
||||
}
|
||||
deselect();
|
||||
|
||||
return count ? RES_ERROR : RES_OK; /* Return result */
|
||||
return count ? RES_ERROR : RES_OK; // Return result
|
||||
}
|
||||
|
||||
#endif // _DISKIO_WRITE
|
||||
@@ -405,9 +411,9 @@ DRESULT disk_read (
|
||||
#if _DISKIO_IOCTL
|
||||
|
||||
DRESULT disk_ioctl (
|
||||
BYTE drv, /* Physical drive number (0) */
|
||||
BYTE cmd, /* Control command code */
|
||||
void *buff /* Pointer to the conrtol data */
|
||||
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;
|
||||
@@ -418,22 +424,23 @@ DRESULT disk_read (
|
||||
UINT dc;
|
||||
#endif
|
||||
|
||||
if (drv) return RES_PARERR; /* Check parameter */
|
||||
if (Stat & STA_NOINIT) return RES_NOTRDY; /* Check if drive is ready */
|
||||
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 */
|
||||
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) */
|
||||
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 */
|
||||
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 */
|
||||
}
|
||||
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);
|
||||
@@ -442,21 +449,23 @@ DRESULT disk_read (
|
||||
}
|
||||
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 */
|
||||
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 */
|
||||
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 */
|
||||
}
|
||||
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 */
|
||||
}
|
||||
else { // MMC
|
||||
*(DWORD*)buff = ((WORD)((csd[10] & 124) >> 2) + 1) * (((csd[11] & 3) << 3) + ((csd[11] & 224) >> 5) + 1);
|
||||
}
|
||||
res = RES_OK;
|
||||
@@ -464,47 +473,47 @@ DRESULT disk_read (
|
||||
}
|
||||
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 */
|
||||
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 */
|
||||
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 */
|
||||
// The following commands are never used by FatFs module
|
||||
|
||||
case MMC_GET_TYPE: /* Get MMC/SDC type (BYTE) */
|
||||
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 */
|
||||
case MMC_GET_CSD: // Read CSD (16 bytes)
|
||||
if (send_cmd(CMD9, 0) == 0 && rcvr_datablock(ptr, 16)) {
|
||||
res = RES_OK;
|
||||
}
|
||||
break;
|
||||
|
||||
case MMC_GET_CID: /* Read CID (16 bytes) */
|
||||
if (send_cmd(CMD10, 0) == 0 && rcvr_datablock(ptr, 16)) { /* READ_CID */
|
||||
case MMC_GET_CID: // Read CID (16 bytes)
|
||||
if (send_cmd(CMD10, 0) == 0 && rcvr_datablock(ptr, 16)) {
|
||||
res = RES_OK;
|
||||
}
|
||||
break;
|
||||
|
||||
case MMC_GET_OCR: /* Read OCR (4 bytes) */
|
||||
if (send_cmd(CMD58, 0) == 0) { /* READ_OCR */
|
||||
case MMC_GET_OCR: // Read OCR (4 bytes)
|
||||
if (send_cmd(CMD58, 0) == 0) {
|
||||
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 */
|
||||
case MMC_GET_SDSTAT: // Read SD status (64 bytes)
|
||||
if (send_cmd(ACMD13, 0) == 0) {
|
||||
xchg_spi(0xFF);
|
||||
if (rcvr_datablock(ptr, 64)) res = RES_OK;
|
||||
}
|
||||
@@ -553,4 +562,5 @@ DRESULT disk_read (
|
||||
|
||||
#endif // _DISKIO_IOCTL
|
||||
|
||||
#endif // HAS_ONBOARD_SD
|
||||
#endif // SD_CONNECTION_IS(ONBOARD)
|
||||
#endif // __STM32F1__
|
||||
|
8
Marlin/src/HAL/STM32F1/onboard_sd.h
Executable file → Normal file
8
Marlin/src/HAL/STM32F1/onboard_sd.h
Executable file → Normal file
@@ -7,8 +7,8 @@
|
||||
#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 */
|
||||
#define _DISKIO_IOCTL 1 /* 1: Enable disk_ioctl function */
|
||||
#define _DISKIO_ISDIO 0 /* 1: Enable iSDIO control function */
|
||||
|
||||
typedef unsigned char BYTE;
|
||||
typedef unsigned short WORD;
|
||||
@@ -48,7 +48,7 @@ DRESULT disk_read(BYTE pdrv, BYTE* buff, DWORD sector, UINT count);
|
||||
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);
|
||||
DRESULT disk_ioctl(BYTE pdrv, BYTE cmd, void *buff);
|
||||
#endif
|
||||
|
||||
/* Disk Status Bits (DSTATUS) */
|
||||
@@ -56,7 +56,7 @@ DRESULT disk_read(BYTE pdrv, BYTE* buff, DWORD sector, UINT count);
|
||||
#define STA_NODISK 0x02 /* No medium in the drive */
|
||||
#define STA_PROTECT 0x04 /* Write protected */
|
||||
|
||||
/* Command code for disk_ioctrl fucntion */
|
||||
/* Command code for disk_ioctrl function */
|
||||
|
||||
/* Generic command (Used by FatFs) */
|
||||
#define CTRL_SYNC 0 /* Complete pending write process (needed at _FS_READONLY == 0) */
|
||||
|
110
Marlin/src/HAL/STM32F1/pinsDebug.h
Executable file → Normal file
110
Marlin/src/HAL/STM32F1/pinsDebug.h
Executable file → Normal file
@@ -2,6 +2,9 @@
|
||||
* 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
|
||||
@@ -13,15 +16,108 @@
|
||||
* 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/>.
|
||||
* along with this program. If not, see <https://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"
|
||||
/**
|
||||
* Support routines for MAPLE_STM32F1
|
||||
*/
|
||||
|
||||
/**
|
||||
* Translation of routines & variables used by pinsDebug.h
|
||||
*/
|
||||
|
||||
#ifndef BOARD_NR_GPIO_PINS // Only in MAPLE_STM32F1
|
||||
#error "Expected BOARD_NR_GPIO_PINS not found"
|
||||
#endif
|
||||
|
||||
#include "fastio.h"
|
||||
|
||||
extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS];
|
||||
|
||||
#define NUM_DIGITAL_PINS BOARD_NR_GPIO_PINS
|
||||
#define NUMBER_PINS_TOTAL BOARD_NR_GPIO_PINS
|
||||
#define VALID_PIN(pin) (pin >= 0 && pin < BOARD_NR_GPIO_PINS)
|
||||
#define GET_ARRAY_PIN(p) pin_t(pin_array[p].pin)
|
||||
#define pwm_status(pin) PWM_PIN(pin)
|
||||
#define digitalRead_mod(p) extDigitalRead(p)
|
||||
#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%3hd "), int16_t(p)); SERIAL_ECHO(buffer); }while(0)
|
||||
#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0)
|
||||
#define PRINT_PORT(p) print_port(p)
|
||||
#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
|
||||
#define MULTI_NAME_PAD 21 // space needed to be pretty if not first name assigned to a pin
|
||||
|
||||
// pins that will cause hang/reset/disconnect in M43 Toggle and Watch utilities
|
||||
#ifndef M43_NEVER_TOUCH
|
||||
#define M43_NEVER_TOUCH(Q) (Q >= 9 && Q <= 12) // SERIAL/USB pins PA9(TX) PA10(RX)
|
||||
#endif
|
||||
|
||||
static inline int8_t get_pin_mode(pin_t pin) {
|
||||
return VALID_PIN(pin) ? _GET_MODE(pin) : -1;
|
||||
}
|
||||
|
||||
static inline pin_t DIGITAL_PIN_TO_ANALOG_PIN(pin_t pin) {
|
||||
if (!VALID_PIN(pin)) return -1;
|
||||
int8_t adc_channel = int8_t(PIN_MAP[pin].adc_channel);
|
||||
#ifdef NUM_ANALOG_INPUTS
|
||||
if (adc_channel >= NUM_ANALOG_INPUTS) adc_channel = ADCx;
|
||||
#endif
|
||||
return pin_t(adc_channel);
|
||||
}
|
||||
|
||||
static inline bool IS_ANALOG(pin_t pin) {
|
||||
if (!VALID_PIN(pin)) return false;
|
||||
if (PIN_MAP[pin].adc_channel != ADCx) {
|
||||
#ifdef NUM_ANALOG_INPUTS
|
||||
if (PIN_MAP[pin].adc_channel >= NUM_ANALOG_INPUTS) return false;
|
||||
#endif
|
||||
return _GET_MODE(pin) == GPIO_INPUT_ANALOG && !M43_NEVER_TOUCH(pin);
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
static inline bool GET_PINMODE(const pin_t pin) {
|
||||
return VALID_PIN(pin) && !IS_INPUT(pin);
|
||||
}
|
||||
|
||||
static inline bool GET_ARRAY_IS_DIGITAL(const int16_t array_pin) {
|
||||
const pin_t pin = GET_ARRAY_PIN(array_pin);
|
||||
return (!IS_ANALOG(pin)
|
||||
#ifdef NUM_ANALOG_INPUTS
|
||||
|| PIN_MAP[pin].adc_channel >= NUM_ANALOG_INPUTS
|
||||
#endif
|
||||
);
|
||||
}
|
||||
|
||||
#include "../../inc/MarlinConfig.h" // Allow pins/pins.h to set density
|
||||
|
||||
static inline void pwm_details(const pin_t pin) {
|
||||
if (PWM_PIN(pin)) {
|
||||
timer_dev * const tdev = PIN_MAP[pin].timer_device;
|
||||
const uint8_t channel = PIN_MAP[pin].timer_channel;
|
||||
const char num = (
|
||||
#if EITHER(STM32_HIGH_DENSITY, STM32_XL_DENSITY)
|
||||
tdev == &timer8 ? '8' :
|
||||
tdev == &timer5 ? '5' :
|
||||
#endif
|
||||
tdev == &timer4 ? '4' :
|
||||
tdev == &timer3 ? '3' :
|
||||
tdev == &timer2 ? '2' :
|
||||
tdev == &timer1 ? '1' : '?'
|
||||
);
|
||||
char buffer[10];
|
||||
sprintf_P(buffer, PSTR(" TIM%c CH%c"), num, ('0' + channel));
|
||||
SERIAL_ECHO(buffer);
|
||||
}
|
||||
}
|
||||
|
||||
static inline void print_port(pin_t pin) {
|
||||
const char port = 'A' + char(pin >> 4); // pin div 16
|
||||
const int16_t gbit = PIN_MAP[pin].gpio_bit;
|
||||
char buffer[8];
|
||||
sprintf_P(buffer, PSTR("P%c%hd "), port, gbit);
|
||||
if (gbit < 10) SERIAL_CHAR(' ');
|
||||
SERIAL_ECHO(buffer);
|
||||
}
|
||||
|
31
Marlin/src/HAL/STM32F1/sdio.cpp
Executable file → Normal file
31
Marlin/src/HAL/STM32F1/sdio.cpp
Executable file → Normal file
@@ -17,17 +17,16 @@
|
||||
* 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/>.
|
||||
* along with this program. If not, see <https://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)
|
||||
#if EITHER(STM32_HIGH_DENSITY, STM32_XL_DENSITY)
|
||||
|
||||
#include "sdio.h"
|
||||
|
||||
@@ -102,7 +101,23 @@ bool SDIO_ReadBlock_DMA(uint32_t blockAddress, uint8_t *data) {
|
||||
return false;
|
||||
}
|
||||
|
||||
while (!SDIO_GET_FLAG(SDIO_STA_DATAEND | SDIO_STA_TRX_ERROR_FLAGS)) {}
|
||||
while (!SDIO_GET_FLAG(SDIO_STA_DATAEND | SDIO_STA_TRX_ERROR_FLAGS)) { /* wait */ }
|
||||
|
||||
//If there were SDIO errors, do not wait DMA.
|
||||
if (SDIO->STA & SDIO_STA_TRX_ERROR_FLAGS) {
|
||||
SDIO_CLEAR_FLAG(SDIO_ICR_CMD_FLAGS | SDIO_ICR_DATA_FLAGS);
|
||||
dma_disable(SDIO_DMA_DEV, SDIO_DMA_CHANNEL);
|
||||
return false;
|
||||
}
|
||||
|
||||
//Wait for DMA transaction to complete
|
||||
while ((DMA2_BASE->ISR & (DMA_ISR_TEIF4|DMA_ISR_TCIF4)) == 0 ) { /* wait */ }
|
||||
|
||||
if (DMA2_BASE->ISR & DMA_ISR_TEIF4) {
|
||||
dma_disable(SDIO_DMA_DEV, SDIO_DMA_CHANNEL);
|
||||
SDIO_CLEAR_FLAG(SDIO_ICR_CMD_FLAGS | SDIO_ICR_DATA_FLAGS);
|
||||
return false;
|
||||
}
|
||||
|
||||
dma_disable(SDIO_DMA_DEV, SDIO_DMA_CHANNEL);
|
||||
|
||||
@@ -121,7 +136,7 @@ bool SDIO_ReadBlock_DMA(uint32_t blockAddress, uint8_t *data) {
|
||||
}
|
||||
|
||||
bool SDIO_ReadBlock(uint32_t blockAddress, uint8_t *data) {
|
||||
uint32_t retries = 3;
|
||||
uint32_t retries = SDIO_READ_RETRIES;
|
||||
while (retries--) if (SDIO_ReadBlock_DMA(blockAddress, data)) return true;
|
||||
return false;
|
||||
}
|
||||
@@ -147,7 +162,7 @@ bool SDIO_WriteBlock(uint32_t blockAddress, const uint8_t *data) {
|
||||
|
||||
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)) {}
|
||||
while (!SDIO_GET_FLAG(SDIO_STA_DATAEND | SDIO_STA_TRX_ERROR_FLAGS)) { /* wait */ }
|
||||
|
||||
dma_disable(SDIO_DMA_DEV, SDIO_DMA_CHANNEL);
|
||||
|
||||
@@ -169,6 +184,10 @@ bool SDIO_WriteBlock(uint32_t blockAddress, const uint8_t *data) {
|
||||
|
||||
inline uint32_t SDIO_GetCardState() { return SDIO_CmdSendStatus(SdCard.RelCardAdd << 16U) ? (SDIO_GetResponse(SDIO_RESP1) >> 9U) & 0x0FU : SDIO_CARD_ERROR; }
|
||||
|
||||
// No F1 board with SDIO + MSC using Maple, that I aware of...
|
||||
bool SDIO_IsReady() { return true; }
|
||||
uint32_t SDIO_GetCardSize() { return 0; }
|
||||
|
||||
// ------------------------
|
||||
// SD Commands and Responses
|
||||
// ------------------------
|
||||
|
12
Marlin/src/HAL/STM32F1/sdio.h
Executable file → Normal file
12
Marlin/src/HAL/STM32F1/sdio.h
Executable file → Normal file
@@ -16,12 +16,12 @@
|
||||
* 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/>.
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include "../shared/Marduino.h"
|
||||
#include "../../inc/MarlinConfig.h" // Allow pins/pins.h to override SDIO clock / retries
|
||||
|
||||
#include <libmaple/sdio.h>
|
||||
#include <libmaple/dma.h>
|
||||
@@ -100,7 +100,13 @@
|
||||
#define SDIO_DATA_TIMEOUT 100U /* Read data transfer timeout */
|
||||
#define SDIO_WRITE_TIMEOUT 200U /* Write data transfer timeout */
|
||||
|
||||
#define SDIO_CLOCK 18000000 /* 18 MHz */
|
||||
#ifndef SDIO_CLOCK
|
||||
#define SDIO_CLOCK 18000000 /* 18 MHz */
|
||||
#endif
|
||||
|
||||
#ifndef SDIO_READ_RETRIES
|
||||
#define SDIO_READ_RETRIES 3
|
||||
#endif
|
||||
|
||||
// ------------------------
|
||||
// Types
|
||||
|
31
Marlin/src/HAL/STM32F1/spi_pins.h
Executable file → Normal file
31
Marlin/src/HAL/STM32F1/spi_pins.h
Executable file → Normal file
@@ -2,6 +2,9 @@
|
||||
* 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
|
||||
@@ -13,7 +16,7 @@
|
||||
* 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/>.
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
@@ -31,28 +34,24 @@
|
||||
* SPI2 | PB12 PB13 PB14 PB15 |
|
||||
* SPI3 | PA15 PB3 PB4 PB5 |
|
||||
* +-----------------------------+
|
||||
* Any pin can be used for Chip Select (SS_PIN)
|
||||
* Any pin can be used for Chip Select (SD_SS_PIN)
|
||||
* SPI1 is enabled by default
|
||||
*/
|
||||
#ifndef SCK_PIN
|
||||
#define SCK_PIN PA5
|
||||
#ifndef SD_SCK_PIN
|
||||
#define SD_SCK_PIN PA5
|
||||
#endif
|
||||
#ifndef MISO_PIN
|
||||
#define MISO_PIN PA6
|
||||
#ifndef SD_MISO_PIN
|
||||
#define SD_MISO_PIN PA6
|
||||
#endif
|
||||
#ifndef MOSI_PIN
|
||||
#define MOSI_PIN PA7
|
||||
#ifndef SD_MOSI_PIN
|
||||
#define SD_MOSI_PIN PA7
|
||||
#endif
|
||||
#ifndef SS_PIN
|
||||
#define SS_PIN PA4
|
||||
#ifndef SD_SS_PIN
|
||||
#define SD_SS_PIN PA4
|
||||
#endif
|
||||
#undef SDSS
|
||||
#define SDSS SS_PIN
|
||||
#define SDSS SD_SS_PIN
|
||||
|
||||
#if ENABLED(ENABLE_SPI3)
|
||||
#define SPI_DEVICE 3
|
||||
#elif ENABLED(ENABLE_SPI2)
|
||||
#define SPI_DEVICE 2
|
||||
#else
|
||||
#ifndef SPI_DEVICE
|
||||
#define SPI_DEVICE 1
|
||||
#endif
|
||||
|
216
Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_fsmc.cpp → Marlin/src/HAL/STM32F1/tft/tft_fsmc.cpp
Executable file → Normal file
216
Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_fsmc.cpp → Marlin/src/HAL/STM32F1/tft/tft_fsmc.cpp
Executable file → Normal file
@@ -16,100 +16,20 @@
|
||||
* 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/>.
|
||||
* along with this program. If not, see <https://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_FSMC_TFT
|
||||
|
||||
#if HAS_GRAPHICAL_LCD
|
||||
|
||||
#include <U8glib.h>
|
||||
#include "tft_fsmc.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;
|
||||
}
|
||||
LCD_CONTROLLER_TypeDef *TFT_FSMC::LCD;
|
||||
|
||||
/**
|
||||
* FSMC LCD IO
|
||||
@@ -160,27 +80,32 @@ __attribute__((always_inline)) __STATIC_INLINE void __DSB() {
|
||||
#define FSMC_RS_A25 PG14
|
||||
#endif
|
||||
|
||||
/* Timing configuration */
|
||||
#define FSMC_ADDRESS_SETUP_TIME 15 // AddressSetupTime
|
||||
#define FSMC_DATA_SETUP_TIME 15 // DataSetupTime
|
||||
|
||||
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) {
|
||||
void TFT_FSMC::Init() {
|
||||
uint8_t cs = FSMC_CS_PIN, rs = FSMC_RS_PIN;
|
||||
uint32_t controllerAddress;
|
||||
|
||||
#if ENABLED(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
|
||||
|
||||
struct fsmc_nor_psram_reg_map* fsmcPsramRegion;
|
||||
|
||||
if (fsmcInit) return;
|
||||
fsmcInit = 1;
|
||||
|
||||
switch (cs) {
|
||||
case FSMC_CS_NE1: controllerAddress = (uint32_t)FSMC_NOR_PSRAM_REGION1; break;
|
||||
case FSMC_CS_NE1: controllerAddress = (uint32_t)FSMC_NOR_PSRAM_REGION1; fsmcPsramRegion = FSMC_NOR_PSRAM1_BASE; 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;
|
||||
case FSMC_CS_NE2: controllerAddress = (uint32_t)FSMC_NOR_PSRAM_REGION2; fsmcPsramRegion = FSMC_NOR_PSRAM2_BASE; break;
|
||||
case FSMC_CS_NE3: controllerAddress = (uint32_t)FSMC_NOR_PSRAM_REGION3; fsmcPsramRegion = FSMC_NOR_PSRAM3_BASE; break;
|
||||
case FSMC_CS_NE4: controllerAddress = (uint32_t)FSMC_NOR_PSRAM_REGION4; fsmcPsramRegion = FSMC_NOR_PSRAM4_BASE; break;
|
||||
#endif
|
||||
default: return;
|
||||
}
|
||||
@@ -246,90 +171,67 @@ void LCD_IO_Init(uint8_t cs, uint8_t rs) {
|
||||
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
|
||||
fsmcPsramRegion->BCR = FSMC_BCR_WREN | FSMC_BCR_MTYP_SRAM | FSMC_BCR_MWID_16BITS | FSMC_BCR_MBKEN;
|
||||
fsmcPsramRegion->BTR = (FSMC_DATA_SETUP_TIME << 8) | FSMC_ADDRESS_SETUP_TIME;
|
||||
|
||||
afio_remap(AFIO_REMAP_FSMC_NADV);
|
||||
|
||||
LCD = (LCD_CONTROLLER_TypeDef*)controllerAddress;
|
||||
}
|
||||
|
||||
void LCD_IO_WriteData(uint16_t RegValue) {
|
||||
LCD->RAM = RegValue;
|
||||
void TFT_FSMC::Transmit(uint16_t Data) {
|
||||
LCD->RAM = Data;
|
||||
__DSB();
|
||||
}
|
||||
|
||||
void LCD_IO_WriteReg(uint16_t Reg) {
|
||||
void TFT_FSMC::WriteReg(uint16_t Reg) {
|
||||
LCD->REG = Reg;
|
||||
__DSB();
|
||||
}
|
||||
|
||||
uint16_t LCD_IO_ReadData(uint16_t RegValue) {
|
||||
LCD->REG = RegValue;
|
||||
__DSB();
|
||||
uint32_t TFT_FSMC::GetID() {
|
||||
uint32_t id;
|
||||
WriteReg(0x0000);
|
||||
id = LCD->RAM;
|
||||
|
||||
return LCD->RAM;
|
||||
if (id == 0)
|
||||
id = ReadID(LCD_READ_ID);
|
||||
if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF)
|
||||
id = ReadID(LCD_READ_ID4);
|
||||
if ((id & 0xFF00) == 0 && (id & 0xFF) != 0)
|
||||
id = ReadID(LCD_READ_ID4);
|
||||
return id;
|
||||
}
|
||||
|
||||
uint32_t LCD_IO_ReadData(uint16_t RegValue, uint8_t ReadSize) {
|
||||
volatile uint32_t data;
|
||||
LCD->REG = RegValue;
|
||||
__DSB();
|
||||
uint32_t TFT_FSMC::ReadID(uint16_t Reg) {
|
||||
uint32_t id;
|
||||
WriteReg(Reg);
|
||||
id = LCD->RAM; // dummy read
|
||||
id = Reg << 24;
|
||||
id |= (LCD->RAM & 0x00FF) << 16;
|
||||
id |= (LCD->RAM & 0x00FF) << 8;
|
||||
id |= LCD->RAM & 0x00FF;
|
||||
return id;
|
||||
}
|
||||
|
||||
data = LCD->RAM; // dummy read
|
||||
data = LCD->RAM & 0x00FF;
|
||||
|
||||
while (--ReadSize) {
|
||||
data <<= 8;
|
||||
data |= (LCD->RAM & 0x00FF);
|
||||
}
|
||||
return uint32_t(data);
|
||||
bool TFT_FSMC::isBusy() {
|
||||
return false;
|
||||
}
|
||||
|
||||
#if ENABLED(LCD_USE_DMA_FSMC)
|
||||
void TFT_FSMC::Abort() {
|
||||
|
||||
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);
|
||||
}
|
||||
|
||||
void TFT_FSMC::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) {
|
||||
#if defined(FSMC_DMA_DEV) && defined(FSMC_DMA_CHANNEL)
|
||||
dma_setup_transfer(FSMC_DMA_DEV, FSMC_DMA_CHANNEL, Data, DMA_SIZE_16BITS, &LCD->RAM, DMA_SIZE_16BITS, DMA_MEM_2_MEM | MemoryIncrease);
|
||||
dma_set_num_transfers(FSMC_DMA_DEV, FSMC_DMA_CHANNEL, 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;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
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
|
||||
#endif // HAS_FSMC_TFT
|
71
Marlin/src/HAL/STM32F1/tft/tft_fsmc.h
Normal file
71
Marlin/src/HAL/STM32F1/tft/tft_fsmc.h
Normal file
@@ -0,0 +1,71 @@
|
||||
/**
|
||||
* 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 <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#ifndef LCD_READ_ID
|
||||
#define LCD_READ_ID 0x04 // Read display identification information (0xD3 on ILI9341)
|
||||
#endif
|
||||
#ifndef LCD_READ_ID4
|
||||
#define LCD_READ_ID4 0xD3 // Read display identification information (0xD3 on ILI9341)
|
||||
#endif
|
||||
|
||||
#include <libmaple/dma.h>
|
||||
|
||||
#define DATASIZE_8BIT DMA_SIZE_8BITS
|
||||
#define DATASIZE_16BIT DMA_SIZE_16BITS
|
||||
#define TFT_IO_DRIVER TFT_FSMC
|
||||
|
||||
typedef struct {
|
||||
__IO uint16_t REG;
|
||||
__IO uint16_t RAM;
|
||||
} LCD_CONTROLLER_TypeDef;
|
||||
|
||||
class TFT_FSMC {
|
||||
private:
|
||||
static LCD_CONTROLLER_TypeDef *LCD;
|
||||
|
||||
static uint32_t ReadID(uint16_t Reg);
|
||||
static void Transmit(uint16_t Data);
|
||||
static void TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count);
|
||||
|
||||
public:
|
||||
static void Init();
|
||||
static uint32_t GetID();
|
||||
static bool isBusy();
|
||||
static void Abort();
|
||||
|
||||
static void DataTransferBegin(uint16_t DataWidth = DATASIZE_16BIT) {};
|
||||
static void DataTransferEnd() {};
|
||||
|
||||
static void WriteData(uint16_t Data) { Transmit(Data); }
|
||||
static void WriteReg(uint16_t Reg);
|
||||
|
||||
static void WriteSequence(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_PINC_MODE, Data, Count); }
|
||||
static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_CIRC_MODE, &Data, Count); }
|
||||
static void WriteMultiple(uint16_t Color, uint32_t Count) {
|
||||
static uint16_t Data; Data = Color;
|
||||
while (Count > 0) {
|
||||
TransmitDMA(DMA_CIRC_MODE, &Data, Count > 0xFFFF ? 0xFFFF : Count);
|
||||
Count = Count > 0xFFFF ? Count - 0xFFFF : 0;
|
||||
}
|
||||
}
|
||||
};
|
129
Marlin/src/HAL/STM32F1/tft/tft_spi.cpp
Normal file
129
Marlin/src/HAL/STM32F1/tft/tft_spi.cpp
Normal file
@@ -0,0 +1,129 @@
|
||||
/**
|
||||
* 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 <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#include "../../../inc/MarlinConfig.h"
|
||||
|
||||
#if HAS_SPI_TFT
|
||||
|
||||
#include "tft_spi.h"
|
||||
|
||||
SPIClass TFT_SPI::SPIx(1);
|
||||
|
||||
void TFT_SPI::Init() {
|
||||
#if PIN_EXISTS(TFT_RESET)
|
||||
OUT_WRITE(TFT_RST_PIN, HIGH);
|
||||
delay(100);
|
||||
#endif
|
||||
|
||||
#if PIN_EXISTS(TFT_BACKLIGHT)
|
||||
OUT_WRITE(TFT_BACKLIGHT_PIN, HIGH);
|
||||
#endif
|
||||
|
||||
OUT_WRITE(TFT_DC_PIN, HIGH);
|
||||
OUT_WRITE(TFT_CS_PIN, HIGH);
|
||||
|
||||
/**
|
||||
* 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;
|
||||
uint8_t spiRate = SPI_FULL_SPEED;
|
||||
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
|
||||
}
|
||||
SPIx.setModule(1);
|
||||
SPIx.setClockDivider(clock);
|
||||
SPIx.setBitOrder(MSBFIRST);
|
||||
SPIx.setDataMode(SPI_MODE0);
|
||||
}
|
||||
|
||||
void TFT_SPI::DataTransferBegin(uint16_t DataSize) {
|
||||
SPIx.setDataSize(DataSize);
|
||||
SPIx.begin();
|
||||
OUT_WRITE(TFT_CS_PIN, LOW);
|
||||
}
|
||||
|
||||
#ifdef TFT_DEFAULT_DRIVER
|
||||
#include "../../../lcd/tft_io/tft_ids.h"
|
||||
#endif
|
||||
|
||||
uint32_t TFT_SPI::GetID() {
|
||||
uint32_t id;
|
||||
id = ReadID(LCD_READ_ID);
|
||||
if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) {
|
||||
id = ReadID(LCD_READ_ID4);
|
||||
#ifdef TFT_DEFAULT_DRIVER
|
||||
if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF)
|
||||
id = TFT_DEFAULT_DRIVER;
|
||||
#endif
|
||||
}
|
||||
return id;
|
||||
}
|
||||
|
||||
uint32_t TFT_SPI::ReadID(uint16_t Reg) {
|
||||
#if !PIN_EXISTS(TFT_MISO)
|
||||
return 0;
|
||||
#else
|
||||
uint8_t d = 0;
|
||||
uint32_t data = 0;
|
||||
SPIx.setClockDivider(SPI_CLOCK_DIV16);
|
||||
DataTransferBegin(DATASIZE_8BIT);
|
||||
WriteReg(Reg);
|
||||
|
||||
LOOP_L_N(i, 4) {
|
||||
SPIx.read((uint8_t*)&d, 1);
|
||||
data = (data << 8) | d;
|
||||
}
|
||||
|
||||
DataTransferEnd();
|
||||
SPIx.setClockDivider(SPI_CLOCK_MAX);
|
||||
|
||||
return data >> 7;
|
||||
#endif
|
||||
}
|
||||
|
||||
bool TFT_SPI::isBusy() { return false; }
|
||||
|
||||
void TFT_SPI::Abort() { DataTransferEnd(); }
|
||||
|
||||
void TFT_SPI::Transmit(uint16_t Data) { SPIx.send(Data); }
|
||||
|
||||
void TFT_SPI::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) {
|
||||
DataTransferBegin();
|
||||
OUT_WRITE(TFT_DC_PIN, HIGH);
|
||||
SPIx.dmaSend(Data, Count, MemoryIncrease == DMA_MINC_ENABLE);
|
||||
DataTransferEnd();
|
||||
}
|
||||
|
||||
#endif // HAS_SPI_TFT
|
72
Marlin/src/HAL/STM32F1/tft/tft_spi.h
Normal file
72
Marlin/src/HAL/STM32F1/tft/tft_spi.h
Normal file
@@ -0,0 +1,72 @@
|
||||
/**
|
||||
* 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 <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include "../../../inc/MarlinConfig.h"
|
||||
|
||||
#include <SPI.h>
|
||||
|
||||
#ifndef LCD_READ_ID
|
||||
#define LCD_READ_ID 0x04 // Read display identification information (0xD3 on ILI9341)
|
||||
#endif
|
||||
#ifndef LCD_READ_ID4
|
||||
#define LCD_READ_ID4 0xD3 // Read display identification information (0xD3 on ILI9341)
|
||||
#endif
|
||||
|
||||
#define DATASIZE_8BIT DATA_SIZE_8BIT
|
||||
#define DATASIZE_16BIT DATA_SIZE_16BIT
|
||||
#define TFT_IO_DRIVER TFT_SPI
|
||||
|
||||
#define DMA_MINC_ENABLE 1
|
||||
#define DMA_MINC_DISABLE 0
|
||||
|
||||
class TFT_SPI {
|
||||
private:
|
||||
static uint32_t ReadID(uint16_t Reg);
|
||||
static void Transmit(uint16_t Data);
|
||||
static void TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count);
|
||||
|
||||
public:
|
||||
static SPIClass SPIx;
|
||||
|
||||
static void Init();
|
||||
static uint32_t GetID();
|
||||
static bool isBusy();
|
||||
static void Abort();
|
||||
|
||||
static void DataTransferBegin(uint16_t DataWidth = DATA_SIZE_16BIT);
|
||||
static void DataTransferEnd() { WRITE(TFT_CS_PIN, HIGH); SPIx.end(); };
|
||||
static void DataTransferAbort();
|
||||
|
||||
static void WriteData(uint16_t Data) { Transmit(Data); }
|
||||
static void WriteReg(uint16_t Reg) { WRITE(TFT_A0_PIN, LOW); Transmit(Reg); WRITE(TFT_A0_PIN, HIGH); }
|
||||
|
||||
static void WriteSequence(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_MINC_ENABLE, Data, Count); }
|
||||
static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_MINC_DISABLE, &Data, Count); }
|
||||
static void WriteMultiple(uint16_t Color, uint32_t Count) {
|
||||
static uint16_t Data; Data = Color;
|
||||
while (Count > 0) {
|
||||
TransmitDMA(DMA_MINC_DISABLE, &Data, Count > 0xFFFF ? 0xFFFF : Count);
|
||||
Count = Count > 0xFFFF ? Count - 0xFFFF : 0;
|
||||
}
|
||||
}
|
||||
};
|
144
Marlin/src/HAL/STM32F1/tft/xpt2046.cpp
Normal file
144
Marlin/src/HAL/STM32F1/tft/xpt2046.cpp
Normal file
@@ -0,0 +1,144 @@
|
||||
/**
|
||||
* 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 <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#include "../../../inc/MarlinConfig.h"
|
||||
|
||||
#if HAS_TFT_XPT2046 || HAS_RES_TOUCH_BUTTONS
|
||||
|
||||
#include "xpt2046.h"
|
||||
#include <SPI.h>
|
||||
|
||||
uint16_t delta(uint16_t a, uint16_t b) { return a > b ? a - b : b - a; }
|
||||
|
||||
#if ENABLED(TOUCH_BUTTONS_HW_SPI)
|
||||
#include <SPI.h>
|
||||
|
||||
SPIClass XPT2046::SPIx(TOUCH_BUTTONS_HW_SPI_DEVICE);
|
||||
|
||||
static void touch_spi_init(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
|
||||
*/
|
||||
uint8_t clock;
|
||||
switch (spiRate) {
|
||||
case SPI_FULL_SPEED: clock = SPI_CLOCK_DIV4; 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
|
||||
}
|
||||
XPT2046::SPIx.setModule(TOUCH_BUTTONS_HW_SPI_DEVICE);
|
||||
XPT2046::SPIx.setClockDivider(clock);
|
||||
XPT2046::SPIx.setBitOrder(MSBFIRST);
|
||||
XPT2046::SPIx.setDataMode(SPI_MODE0);
|
||||
}
|
||||
#endif // TOUCH_BUTTONS_HW_SPI
|
||||
|
||||
void XPT2046::Init() {
|
||||
SET_INPUT(TOUCH_MISO_PIN);
|
||||
SET_OUTPUT(TOUCH_MOSI_PIN);
|
||||
SET_OUTPUT(TOUCH_SCK_PIN);
|
||||
OUT_WRITE(TOUCH_CS_PIN, HIGH);
|
||||
|
||||
#if PIN_EXISTS(TOUCH_INT)
|
||||
// Optional Pendrive interrupt pin
|
||||
SET_INPUT(TOUCH_INT_PIN);
|
||||
#endif
|
||||
|
||||
TERN_(TOUCH_BUTTONS_HW_SPI, touch_spi_init(SPI_SPEED_6));
|
||||
|
||||
// Read once to enable pendrive status pin
|
||||
getRawData(XPT2046_X);
|
||||
}
|
||||
|
||||
bool XPT2046::isTouched() {
|
||||
return isBusy() ? false : (
|
||||
#if PIN_EXISTS(TOUCH_INT)
|
||||
READ(TOUCH_INT_PIN) != HIGH
|
||||
#else
|
||||
getRawData(XPT2046_Z1) >= XPT2046_Z1_THRESHOLD
|
||||
#endif
|
||||
);
|
||||
}
|
||||
|
||||
bool XPT2046::getRawPoint(int16_t *x, int16_t *y) {
|
||||
if (isBusy()) return false;
|
||||
if (!isTouched()) return false;
|
||||
*x = getRawData(XPT2046_X);
|
||||
*y = getRawData(XPT2046_Y);
|
||||
return isTouched();
|
||||
}
|
||||
|
||||
uint16_t XPT2046::getRawData(const XPTCoordinate coordinate) {
|
||||
uint16_t data[3];
|
||||
|
||||
DataTransferBegin();
|
||||
TERN_(TOUCH_BUTTONS_HW_SPI, SPIx.begin());
|
||||
|
||||
for (uint16_t i = 0; i < 3 ; i++) {
|
||||
IO(coordinate);
|
||||
data[i] = (IO() << 4) | (IO() >> 4);
|
||||
}
|
||||
|
||||
TERN_(TOUCH_BUTTONS_HW_SPI, SPIx.end());
|
||||
DataTransferEnd();
|
||||
|
||||
uint16_t delta01 = delta(data[0], data[1]),
|
||||
delta02 = delta(data[0], data[2]),
|
||||
delta12 = delta(data[1], data[2]);
|
||||
|
||||
if (delta01 > delta02 || delta01 > delta12)
|
||||
data[delta02 > delta12 ? 0 : 1] = data[2];
|
||||
|
||||
return (data[0] + data[1]) >> 1;
|
||||
}
|
||||
|
||||
uint16_t XPT2046::IO(uint16_t data) {
|
||||
return TERN(TOUCH_BUTTONS_HW_SPI, HardwareIO, SoftwareIO)(data);
|
||||
}
|
||||
|
||||
#if ENABLED(TOUCH_BUTTONS_HW_SPI)
|
||||
uint16_t XPT2046::HardwareIO(uint16_t data) {
|
||||
uint16_t result = SPIx.transfer(data);
|
||||
return result;
|
||||
}
|
||||
#endif
|
||||
|
||||
uint16_t XPT2046::SoftwareIO(uint16_t data) {
|
||||
uint16_t result = 0;
|
||||
|
||||
for (uint8_t j = 0x80; j; j >>= 1) {
|
||||
WRITE(TOUCH_SCK_PIN, LOW);
|
||||
WRITE(TOUCH_MOSI_PIN, data & j ? HIGH : LOW);
|
||||
if (READ(TOUCH_MISO_PIN)) result |= j;
|
||||
WRITE(TOUCH_SCK_PIN, HIGH);
|
||||
}
|
||||
WRITE(TOUCH_SCK_PIN, LOW);
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
#endif // HAS_TFT_XPT2046
|
83
Marlin/src/HAL/STM32F1/tft/xpt2046.h
Normal file
83
Marlin/src/HAL/STM32F1/tft/xpt2046.h
Normal file
@@ -0,0 +1,83 @@
|
||||
/**
|
||||
* 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 <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include "../../../inc/MarlinConfig.h"
|
||||
|
||||
#if ENABLED(TOUCH_BUTTONS_HW_SPI)
|
||||
#include <SPI.h>
|
||||
#endif
|
||||
|
||||
#ifndef TOUCH_MISO_PIN
|
||||
#define TOUCH_MISO_PIN SD_MISO_PIN
|
||||
#endif
|
||||
#ifndef TOUCH_MOSI_PIN
|
||||
#define TOUCH_MOSI_PIN SD_MOSI_PIN
|
||||
#endif
|
||||
#ifndef TOUCH_SCK_PIN
|
||||
#define TOUCH_SCK_PIN SD_SCK_PIN
|
||||
#endif
|
||||
#ifndef TOUCH_CS_PIN
|
||||
#define TOUCH_CS_PIN SD_SS_PIN
|
||||
#endif
|
||||
#ifndef TOUCH_INT_PIN
|
||||
#define TOUCH_INT_PIN -1
|
||||
#endif
|
||||
|
||||
#define XPT2046_DFR_MODE 0x00
|
||||
#define XPT2046_SER_MODE 0x04
|
||||
#define XPT2046_CONTROL 0x80
|
||||
|
||||
enum XPTCoordinate : uint8_t {
|
||||
XPT2046_X = 0x10 | XPT2046_CONTROL | XPT2046_DFR_MODE,
|
||||
XPT2046_Y = 0x50 | XPT2046_CONTROL | XPT2046_DFR_MODE,
|
||||
XPT2046_Z1 = 0x30 | XPT2046_CONTROL | XPT2046_DFR_MODE,
|
||||
XPT2046_Z2 = 0x40 | XPT2046_CONTROL | XPT2046_DFR_MODE,
|
||||
};
|
||||
|
||||
#ifndef XPT2046_Z1_THRESHOLD
|
||||
#define XPT2046_Z1_THRESHOLD 10
|
||||
#endif
|
||||
|
||||
class XPT2046 {
|
||||
private:
|
||||
static bool isBusy() { return false; }
|
||||
|
||||
static uint16_t getRawData(const XPTCoordinate coordinate);
|
||||
static bool isTouched();
|
||||
|
||||
static inline void DataTransferBegin() { WRITE(TOUCH_CS_PIN, LOW); };
|
||||
static inline void DataTransferEnd() { WRITE(TOUCH_CS_PIN, HIGH); };
|
||||
#if ENABLED(TOUCH_BUTTONS_HW_SPI)
|
||||
static uint16_t HardwareIO(uint16_t data);
|
||||
#endif
|
||||
static uint16_t SoftwareIO(uint16_t data);
|
||||
static uint16_t IO(uint16_t data = 0);
|
||||
|
||||
public:
|
||||
#if ENABLED(TOUCH_BUTTONS_HW_SPI)
|
||||
static SPIClass SPIx;
|
||||
#endif
|
||||
|
||||
static void Init();
|
||||
static bool getRawPoint(int16_t *x, int16_t *y);
|
||||
};
|
20
Marlin/src/HAL/STM32F1/timers.cpp
Executable file → Normal file
20
Marlin/src/HAL/STM32F1/timers.cpp
Executable file → Normal file
@@ -16,7 +16,7 @@
|
||||
* 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/>.
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
@@ -27,8 +27,6 @@
|
||||
#ifdef __STM32F1__
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
#include "HAL.h"
|
||||
#include "timers.h"
|
||||
|
||||
// ------------------------
|
||||
// Local defines
|
||||
@@ -49,7 +47,10 @@
|
||||
* 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) {
|
||||
|
||||
|
||||
|
||||
void timer_set_interrupt_priority(uint_fast8_t timer_num, uint_fast8_t priority) {
|
||||
nvic_irq_num irq_num;
|
||||
switch (timer_num) {
|
||||
case 1: irq_num = NVIC_TIMER1_CC; break;
|
||||
@@ -66,9 +67,14 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
|
||||
* This should never happen. Add a Sanitycheck for timer number.
|
||||
* Should be a general timer since basic timers have no CC channels.
|
||||
*/
|
||||
break;
|
||||
return;
|
||||
}
|
||||
|
||||
nvic_irq_set_priority(irq_num, priority);
|
||||
}
|
||||
|
||||
|
||||
void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
|
||||
/**
|
||||
* Give the Stepper ISR a higher priority (lower number)
|
||||
* so it automatically preempts the Temperature ISR.
|
||||
@@ -85,7 +91,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
|
||||
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_set_interrupt_priority(STEP_TIMER_NUM, STEP_TIMER_IRQ_PRIO);
|
||||
timer_generate_update(STEP_TIMER_DEV);
|
||||
timer_resume(STEP_TIMER_DEV);
|
||||
break;
|
||||
@@ -97,7 +103,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
|
||||
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_set_interrupt_priority(TEMP_TIMER_NUM, TEMP_TIMER_IRQ_PRIO);
|
||||
timer_generate_update(TEMP_TIMER_DEV);
|
||||
timer_resume(TEMP_TIMER_DEV);
|
||||
break;
|
||||
|
61
Marlin/src/HAL/STM32F1/timers.h
Executable file → Normal file
61
Marlin/src/HAL/STM32F1/timers.h
Executable file → Normal file
@@ -16,7 +16,7 @@
|
||||
* 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/>.
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
@@ -25,9 +25,10 @@
|
||||
* HAL for stm32duino.com based on Libmaple and compatible (STM32F1)
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
#include "HAL.h"
|
||||
|
||||
#include <libmaple/timer.h>
|
||||
#include "../../core/boards.h"
|
||||
|
||||
// ------------------------
|
||||
// Defines
|
||||
@@ -37,15 +38,18 @@
|
||||
* 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
|
||||
#ifndef STEP_TIMER_CHAN
|
||||
#define STEP_TIMER_CHAN 1 // Channel of the timer to use for compare and interrupts
|
||||
#endif
|
||||
#ifndef TEMP_TIMER_CHAN
|
||||
#define TEMP_TIMER_CHAN 1 // Channel of the timer to use for compare and interrupts
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Note: Timers may be used by platforms and libraries
|
||||
@@ -61,16 +65,22 @@ typedef uint16_t hal_timer_t;
|
||||
* - 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.
|
||||
#ifndef STEP_TIMER_NUM
|
||||
#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
|
||||
#endif
|
||||
#ifndef PULSE_TIMER_NUM
|
||||
#define PULSE_TIMER_NUM STEP_TIMER_NUM
|
||||
#endif
|
||||
#ifndef TEMP_TIMER_NUM
|
||||
#define TEMP_TIMER_NUM 2 // Timer Index for Temperature
|
||||
//#define TEMP_TIMER_NUM 4 // 2->4, Timer 2 for Stepper Current PWM
|
||||
#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)
|
||||
#if MB(BTT_SKR_MINI_E3_V1_0, BTT_SKR_E3_DIP, BTT_SKR_MINI_E3_V1_2, MKS_ROBIN_LITE, MKS_ROBIN_E3D, MKS_ROBIN_E3)
|
||||
// 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
|
||||
@@ -81,8 +91,9 @@ typedef uint16_t hal_timer_t;
|
||||
#define SERVO0_TIMER_NUM 1 // SERVO0 or BLTOUCH
|
||||
#endif
|
||||
|
||||
#define STEP_TIMER_IRQ_PRIO 1
|
||||
#define TEMP_TIMER_IRQ_PRIO 2
|
||||
#define STEP_TIMER_IRQ_PRIO 2
|
||||
#define TEMP_TIMER_IRQ_PRIO 3
|
||||
#define SERVO0_TIMER_IRQ_PRIO 1
|
||||
|
||||
#define TEMP_TIMER_PRESCALE 1000 // prescaler for setting Temp timer, 72Khz
|
||||
#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency
|
||||
@@ -111,11 +122,17 @@ timer_dev* get_timer_dev(int number);
|
||||
|
||||
// TODO change this
|
||||
|
||||
#define HAL_TEMP_TIMER_ISR() extern "C" void tempTC_Handler()
|
||||
#define HAL_STEP_TIMER_ISR() extern "C" void stepTC_Handler()
|
||||
#ifndef HAL_TEMP_TIMER_ISR
|
||||
#define HAL_TEMP_TIMER_ISR() extern "C" void tempTC_Handler()
|
||||
#endif
|
||||
#ifndef HAL_STEP_TIMER_ISR
|
||||
#define HAL_STEP_TIMER_ISR() extern "C" void stepTC_Handler()
|
||||
#endif
|
||||
|
||||
extern "C" void tempTC_Handler();
|
||||
extern "C" void stepTC_Handler();
|
||||
extern "C" {
|
||||
void tempTC_Handler();
|
||||
void stepTC_Handler();
|
||||
}
|
||||
|
||||
// ------------------------
|
||||
// Public Variables
|
||||
@@ -149,7 +166,7 @@ FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const ha
|
||||
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
|
||||
// will result in exactly the same effect, ie triggering 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:
|
||||
@@ -179,4 +196,6 @@ 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);
|
||||
}
|
||||
|
||||
void timer_set_interrupt_priority(uint_fast8_t timer_num, uint_fast8_t priority);
|
||||
|
||||
#define TIMER_OC_NO_PRELOAD 0 // Need to disable preload also on compare registers.
|
||||
|
13
Marlin/src/HAL/STM32F1/watchdog.cpp
Executable file → Normal file
13
Marlin/src/HAL/STM32F1/watchdog.cpp
Executable file → Normal file
@@ -16,7 +16,7 @@
|
||||
* 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/>.
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
@@ -33,6 +33,11 @@
|
||||
#include <libmaple/iwdg.h>
|
||||
#include "watchdog.h"
|
||||
|
||||
/**
|
||||
* The watchdog clock is 40Khz. So for a 4s or 8s interval use a /256 preescaler and 625 or 1250 reload value (counts down to 0).
|
||||
*/
|
||||
#define STM32F1_WD_RELOAD TERN(WATCHDOG_DURATION_8S, 1250, 625) // 4 or 8 second timeout
|
||||
|
||||
void HAL_watchdog_refresh() {
|
||||
#if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED)
|
||||
TOGGLE(LED_PIN); // heartbeat indicator
|
||||
@@ -49,10 +54,12 @@ void watchdogSetup() {
|
||||
*
|
||||
* @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)
|
||||
* @details The watchdog clock is 40Khz. So for a 4s or 8s interval use a /256 preescaler and 625 or 1250 reload value (counts down to 0).
|
||||
*/
|
||||
void watchdog_init() {
|
||||
//iwdg_init(IWDG_PRE_256, STM32F1_WD_RELOAD);
|
||||
#if DISABLED(DISABLE_WATCHDOG_INIT)
|
||||
iwdg_init(IWDG_PRE_256, STM32F1_WD_RELOAD);
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif // USE_WATCHDOG
|
||||
|
17
Marlin/src/HAL/STM32F1/watchdog.h
Executable file → Normal file
17
Marlin/src/HAL/STM32F1/watchdog.h
Executable file → Normal file
@@ -16,7 +16,7 @@
|
||||
* 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/>.
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
@@ -27,18 +27,9 @@
|
||||
|
||||
#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
|
||||
// Initialize watchdog with a 4 or 8 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.
|
||||
// Reset watchdog. MUST be called every 4 or 8 seconds after the
|
||||
// first watchdog_init or the STM32F1 will reset.
|
||||
void HAL_watchdog_refresh();
|
||||
|
Reference in New Issue
Block a user