1
0
mirror of https://github.com/MarlinFirmware/Marlin.git synced 2024-11-29 23:07:42 +00:00

🔥 Drop STM L64** drivers, STEVAL_3DP001V1 (#24427)

This commit is contained in:
Bob Kuhn 2022-07-13 22:16:22 -05:00 committed by GitHub
parent 2dc543c4f5
commit 3f4e4a4d89
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
38 changed files with 55 additions and 5881 deletions

View File

@ -81,7 +81,6 @@ jobs:
- STM32F401RC_creality
- STM32F103VE_longer
- STM32F407VE_black
- STM32F401VE_STEVAL
- BIGTREE_BTT002
- BIGTREE_SKR_PRO
- BIGTREE_GTR_V1_0

View File

@ -148,13 +148,12 @@
*
* Use TMC2208/TMC2208_STANDALONE for TMC2225 drivers and TMC2209/TMC2209_STANDALONE for TMC2226 drivers.
*
* Options: A4988, A5984, DRV8825, LV8729, L6470, L6474, POWERSTEP01,
* TB6560, TB6600, TMC2100,
* Options: A4988, A5984, DRV8825, LV8729, TB6560, TB6600, TMC2100,
* TMC2130, TMC2130_STANDALONE, TMC2160, TMC2160_STANDALONE,
* TMC2208, TMC2208_STANDALONE, TMC2209, TMC2209_STANDALONE,
* TMC26X, TMC26X_STANDALONE, TMC2660, TMC2660_STANDALONE,
* TMC5130, TMC5130_STANDALONE, TMC5160, TMC5160_STANDALONE
* :['A4988', 'A5984', 'DRV8825', 'LV8729', 'L6470', 'L6474', 'POWERSTEP01', 'TB6560', 'TB6600', 'TMC2100', 'TMC2130', 'TMC2130_STANDALONE', 'TMC2160', 'TMC2160_STANDALONE', 'TMC2208', 'TMC2208_STANDALONE', 'TMC2209', 'TMC2209_STANDALONE', 'TMC26X', 'TMC26X_STANDALONE', 'TMC2660', 'TMC2660_STANDALONE', 'TMC5130', 'TMC5130_STANDALONE', 'TMC5160', 'TMC5160_STANDALONE']
* :['A4988', 'A5984', 'DRV8825', 'LV8729', 'TB6560', 'TB6600', 'TMC2100', 'TMC2130', 'TMC2130_STANDALONE', 'TMC2160', 'TMC2160_STANDALONE', 'TMC2208', 'TMC2208_STANDALONE', 'TMC2209', 'TMC2209_STANDALONE', 'TMC26X', 'TMC26X_STANDALONE', 'TMC2660', 'TMC2660_STANDALONE', 'TMC5130', 'TMC5130_STANDALONE', 'TMC5160', 'TMC5160_STANDALONE']
*/
#define X_DRIVER_TYPE A4988
#define Y_DRIVER_TYPE A4988

View File

@ -3239,253 +3239,6 @@
#endif // HAS_TRINAMIC_CONFIG
// @section L64XX
/**
* L64XX Stepper Driver options
*
* Arduino-L6470 library (0.8.0 or higher) is required.
* https://github.com/ameyer/Arduino-L6470
*
* Requires the following to be defined in your pins_YOUR_BOARD file
* L6470_CHAIN_SCK_PIN
* L6470_CHAIN_MISO_PIN
* L6470_CHAIN_MOSI_PIN
* L6470_CHAIN_SS_PIN
* ENABLE_RESET_L64XX_CHIPS(Q) where Q is 1 to enable and 0 to reset
*/
#if HAS_L64XX
//#define L6470_CHITCHAT // Display additional status info
#if AXIS_IS_L64XX(X)
#define X_MICROSTEPS 128 // Number of microsteps (VALID: 1, 2, 4, 8, 16, 32, 128) - L6474 max is 16
#define X_OVERCURRENT 2000 // (mA) Current where the driver detects an over current
// L6470 & L6474 - VALID: 375 x (1 - 16) - 6A max - rounds down
// POWERSTEP01: VALID: 1000 x (1 - 32) - 32A max - rounds down
#define X_STALLCURRENT 1500 // (mA) Current where the driver detects a stall (VALID: 31.25 * (1-128) - 4A max - rounds down)
// L6470 & L6474 - VALID: 31.25 * (1-128) - 4A max - rounds down
// POWERSTEP01: VALID: 200 x (1 - 32) - 6.4A max - rounds down
// L6474 - STALLCURRENT setting is used to set the nominal (TVAL) current
#define X_MAX_VOLTAGE 127 // 0-255, Maximum effective voltage seen by stepper - not used by L6474
#define X_CHAIN_POS -1 // Position in SPI chain, 0=Not in chain, 1=Nearest MOSI
#define X_SLEW_RATE 1 // 0-3, Slew 0 is slowest, 3 is fastest
#endif
#if AXIS_IS_L64XX(X2)
#define X2_MICROSTEPS X_MICROSTEPS
#define X2_OVERCURRENT 2000
#define X2_STALLCURRENT 1500
#define X2_MAX_VOLTAGE 127
#define X2_CHAIN_POS -1
#define X2_SLEW_RATE 1
#endif
#if AXIS_IS_L64XX(Y)
#define Y_MICROSTEPS 128
#define Y_OVERCURRENT 2000
#define Y_STALLCURRENT 1500
#define Y_MAX_VOLTAGE 127
#define Y_CHAIN_POS -1
#define Y_SLEW_RATE 1
#endif
#if AXIS_IS_L64XX(Y2)
#define Y2_MICROSTEPS Y_MICROSTEPS
#define Y2_OVERCURRENT 2000
#define Y2_STALLCURRENT 1500
#define Y2_MAX_VOLTAGE 127
#define Y2_CHAIN_POS -1
#define Y2_SLEW_RATE 1
#endif
#if AXIS_IS_L64XX(Z)
#define Z_MICROSTEPS 128
#define Z_OVERCURRENT 2000
#define Z_STALLCURRENT 1500
#define Z_MAX_VOLTAGE 127
#define Z_CHAIN_POS -1
#define Z_SLEW_RATE 1
#endif
#if AXIS_IS_L64XX(Z2)
#define Z2_MICROSTEPS Z_MICROSTEPS
#define Z2_OVERCURRENT 2000
#define Z2_STALLCURRENT 1500
#define Z2_MAX_VOLTAGE 127
#define Z2_CHAIN_POS -1
#define Z2_SLEW_RATE 1
#endif
#if AXIS_IS_L64XX(Z3)
#define Z3_MICROSTEPS Z_MICROSTEPS
#define Z3_OVERCURRENT 2000
#define Z3_STALLCURRENT 1500
#define Z3_MAX_VOLTAGE 127
#define Z3_CHAIN_POS -1
#define Z3_SLEW_RATE 1
#endif
#if AXIS_IS_L64XX(Z4)
#define Z4_MICROSTEPS Z_MICROSTEPS
#define Z4_OVERCURRENT 2000
#define Z4_STALLCURRENT 1500
#define Z4_MAX_VOLTAGE 127
#define Z4_CHAIN_POS -1
#define Z4_SLEW_RATE 1
#endif
#if AXIS_IS_L64XX(I)
#define I_MICROSTEPS 128
#define I_OVERCURRENT 2000
#define I_STALLCURRENT 1500
#define I_MAX_VOLTAGE 127
#define I_CHAIN_POS -1
#define I_SLEW_RATE 1
#endif
#if AXIS_IS_L64XX(J)
#define J_MICROSTEPS 128
#define J_OVERCURRENT 2000
#define J_STALLCURRENT 1500
#define J_MAX_VOLTAGE 127
#define J_CHAIN_POS -1
#define J_SLEW_RATE 1
#endif
#if AXIS_IS_L64XX(K)
#define K_MICROSTEPS 128
#define K_OVERCURRENT 2000
#define K_STALLCURRENT 1500
#define K_MAX_VOLTAGE 127
#define K_CHAIN_POS -1
#define K_SLEW_RATE 1
#endif
#if AXIS_IS_L64XX(U)
#define U_MICROSTEPS 128
#define U_OVERCURRENT 2000
#define U_STALLCURRENT 1500
#define U_MAX_VOLTAGE 127
#define U_CHAIN_POS -1
#define U_SLEW_RATE 1
#endif
#if AXIS_IS_L64XX(V)
#define V_MICROSTEPS 128
#define V_OVERCURRENT 2000
#define V_STALLCURRENT 1500
#define V_MAX_VOLTAGE 127
#define V_CHAIN_POS -1
#define V_SLEW_RATE 1
#endif
#if AXIS_IS_L64XX(W)
#define W_MICROSTEPS 128
#define W_OVERCURRENT 2000
#define W_STALLCURRENT 1500
#define W_MAX_VOLTAGE 127
#define W_CHAIN_POS -1
#define W_SLEW_RATE 1
#endif
#if AXIS_IS_L64XX(E0)
#define E0_MICROSTEPS 128
#define E0_OVERCURRENT 2000
#define E0_STALLCURRENT 1500
#define E0_MAX_VOLTAGE 127
#define E0_CHAIN_POS -1
#define E0_SLEW_RATE 1
#endif
#if AXIS_IS_L64XX(E1)
#define E1_MICROSTEPS E0_MICROSTEPS
#define E1_OVERCURRENT 2000
#define E1_STALLCURRENT 1500
#define E1_MAX_VOLTAGE 127
#define E1_CHAIN_POS -1
#define E1_SLEW_RATE 1
#endif
#if AXIS_IS_L64XX(E2)
#define E2_MICROSTEPS E0_MICROSTEPS
#define E2_OVERCURRENT 2000
#define E2_STALLCURRENT 1500
#define E2_MAX_VOLTAGE 127
#define E2_CHAIN_POS -1
#define E2_SLEW_RATE 1
#endif
#if AXIS_IS_L64XX(E3)
#define E3_MICROSTEPS E0_MICROSTEPS
#define E3_OVERCURRENT 2000
#define E3_STALLCURRENT 1500
#define E3_MAX_VOLTAGE 127
#define E3_CHAIN_POS -1
#define E3_SLEW_RATE 1
#endif
#if AXIS_IS_L64XX(E4)
#define E4_MICROSTEPS E0_MICROSTEPS
#define E4_OVERCURRENT 2000
#define E4_STALLCURRENT 1500
#define E4_MAX_VOLTAGE 127
#define E4_CHAIN_POS -1
#define E4_SLEW_RATE 1
#endif
#if AXIS_IS_L64XX(E5)
#define E5_MICROSTEPS E0_MICROSTEPS
#define E5_OVERCURRENT 2000
#define E5_STALLCURRENT 1500
#define E5_MAX_VOLTAGE 127
#define E5_CHAIN_POS -1
#define E5_SLEW_RATE 1
#endif
#if AXIS_IS_L64XX(E6)
#define E6_MICROSTEPS E0_MICROSTEPS
#define E6_OVERCURRENT 2000
#define E6_STALLCURRENT 1500
#define E6_MAX_VOLTAGE 127
#define E6_CHAIN_POS -1
#define E6_SLEW_RATE 1
#endif
#if AXIS_IS_L64XX(E7)
#define E7_MICROSTEPS E0_MICROSTEPS
#define E7_OVERCURRENT 2000
#define E7_STALLCURRENT 1500
#define E7_MAX_VOLTAGE 127
#define E7_CHAIN_POS -1
#define E7_SLEW_RATE 1
#endif
/**
* Monitor L6470 drivers for error conditions like over temperature and over current.
* In the case of over temperature Marlin can decrease the drive until the error condition clears.
* Other detected conditions can be used to stop the current print.
* Relevant G-codes:
* M906 - I1/2/3/4/5 Set or get motor drive level using axis codes X, Y, Z, E. Report values if no axis codes given.
* I not present or I0 or I1 - X, Y, Z or E0
* I2 - X2, Y2, Z2 or E1
* I3 - Z3 or E3
* I4 - Z4 or E4
* I5 - E5
* M916 - Increase drive level until get thermal warning
* M917 - Find minimum current thresholds
* M918 - Increase speed until max or error
* M122 S0/1 - Report driver parameters
*/
//#define MONITOR_L6470_DRIVER_STATUS
#if ENABLED(MONITOR_L6470_DRIVER_STATUS)
#define KVAL_HOLD_STEP_DOWN 1
//#define L6470_STOP_ON_ERROR
#endif
#endif // HAS_L64XX
// @section i2cbus

View File

@ -1,139 +0,0 @@
/**
* 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/>.
*
*/
/**
* Software L6470 SPI functions originally from Arduino Sd2Card Library
* Copyright (c) 2009 by William Greiman
*/
#include "../../inc/MarlinConfig.h"
#if HAS_L64XX
#include "Delay.h"
#include "../../core/serial.h"
#include "../../libs/L64XX/L64XX_Marlin.h"
// Make sure GCC optimizes this file.
// Note that this line triggers a bug in GCC which is fixed by casting.
// See the note below.
#pragma GCC optimize (3)
// run at ~4Mhz
inline uint8_t L6470_SpiTransfer_Mode_0(uint8_t b) { // using Mode 0
for (uint8_t bits = 8; bits--;) {
WRITE(L6470_CHAIN_MOSI_PIN, b & 0x80);
b <<= 1; // little setup time
WRITE(L6470_CHAIN_SCK_PIN, HIGH);
DELAY_NS(125); // 10 cycles @ 84mhz
b |= (READ(L6470_CHAIN_MISO_PIN) != 0);
WRITE(L6470_CHAIN_SCK_PIN, LOW);
DELAY_NS(125); // 10 cycles @ 84mhz
}
return b;
}
inline uint8_t L6470_SpiTransfer_Mode_3(uint8_t b) { // using Mode 3
for (uint8_t bits = 8; bits--;) {
WRITE(L6470_CHAIN_SCK_PIN, LOW);
WRITE(L6470_CHAIN_MOSI_PIN, b & 0x80);
DELAY_NS(125); // 10 cycles @ 84mhz
WRITE(L6470_CHAIN_SCK_PIN, HIGH);
DELAY_NS(125); // Need more delay for fast CPUs
b <<= 1; // little setup time
b |= (READ(L6470_CHAIN_MISO_PIN) != 0);
}
DELAY_NS(125); // 10 cycles @ 84mhz
return b;
}
/**
* L64XX methods for SPI init and transfer
*/
void L64XX_Marlin::spi_init() {
OUT_WRITE(L6470_CHAIN_SS_PIN, HIGH);
OUT_WRITE(L6470_CHAIN_SCK_PIN, HIGH);
OUT_WRITE(L6470_CHAIN_MOSI_PIN, HIGH);
SET_INPUT(L6470_CHAIN_MISO_PIN);
#if PIN_EXISTS(L6470_BUSY)
SET_INPUT(L6470_BUSY_PIN);
#endif
OUT_WRITE(L6470_CHAIN_MOSI_PIN, HIGH);
}
uint8_t L64XX_Marlin::transfer_single(uint8_t data, int16_t ss_pin) {
// First device in chain has data sent last
extDigitalWrite(ss_pin, LOW);
hal.isr_off(); // Disable interrupts during SPI transfer (can't allow partial command to chips)
const uint8_t data_out = L6470_SpiTransfer_Mode_3(data);
hal.isr_on(); // Enable interrupts
extDigitalWrite(ss_pin, HIGH);
return data_out;
}
uint8_t L64XX_Marlin::transfer_chain(uint8_t data, int16_t ss_pin, uint8_t chain_position) {
uint8_t data_out = 0;
// first device in chain has data sent last
extDigitalWrite(ss_pin, LOW);
for (uint8_t i = L64XX::chain[0]; !L64xxManager.spi_abort && i >= 1; i--) { // Send data unless aborted
hal.isr_off(); // Disable interrupts during SPI transfer (can't allow partial command to chips)
const uint8_t temp = L6470_SpiTransfer_Mode_3(uint8_t(i == chain_position ? data : dSPIN_NOP));
hal.isr_on(); // Enable interrupts
if (i == chain_position) data_out = temp;
}
extDigitalWrite(ss_pin, HIGH);
return data_out;
}
/**
* Platform-supplied L6470 buffer transfer method
*/
void L64XX_Marlin::transfer(uint8_t L6470_buf[], const uint8_t length) {
// First device in chain has its data sent last
if (spi_active) { // Interrupted SPI transfer so need to
WRITE(L6470_CHAIN_SS_PIN, HIGH); // guarantee min high of 650ns
DELAY_US(1);
}
WRITE(L6470_CHAIN_SS_PIN, LOW);
for (uint8_t i = length; i >= 1; i--)
L6470_SpiTransfer_Mode_3(uint8_t(L6470_buf[i]));
WRITE(L6470_CHAIN_SS_PIN, HIGH);
}
#pragma GCC reset_options
#endif // HAS_L64XX

View File

@ -226,10 +226,6 @@
#include "feature/mmu/mmu2.h"
#endif
#if HAS_L64XX
#include "libs/L64XX/L64XX_Marlin.h"
#endif
#if ENABLED(PASSWORD_FEATURE)
#include "feature/password/password.h"
#endif
@ -432,7 +428,7 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) {
if (!has_blocks && !do_reset_timeout && gcode.stepper_inactive_timeout()) {
if (!already_shutdown_steppers) {
already_shutdown_steppers = true; // L6470 SPI will consume 99% of free time without this
already_shutdown_steppers = true;
// Individual axes will be disabled if configured
TERN_(DISABLE_INACTIVE_X, stepper.disable_axis(X_AXIS));
@ -731,8 +727,6 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) {
TERN_(MONITOR_DRIVER_STATUS, monitor_tmc_drivers());
TERN_(MONITOR_L6470_DRIVER_STATUS, L64xxManager.monitor_driver());
// Limit check_axes_activity frequency to 10Hz
static millis_t next_check_axes_ms = 0;
if (ELAPSED(ms, next_check_axes_ms)) {
@ -1062,7 +1056,6 @@ inline void tmc_standby_setup() {
* TMC220x Stepper Drivers (Serial)
* PSU control
* Power-loss Recovery
* L64XX Stepper Drivers (SPI)
* Stepper Driver Reset: DISABLE
* TMC Stepper Drivers (SPI)
* Run hal.init_board() for additional pins setup
@ -1251,10 +1244,6 @@ void setup() {
SETUP_RUN(tmc_init_cs_pins());
#endif
#if HAS_L64XX
SETUP_RUN(L64xxManager.init()); // Set up SPI, init drivers
#endif
#if ENABLED(PSU_CONTROL)
SETUP_LOG("PSU_CONTROL");
powerManager.init();

View File

@ -385,7 +385,6 @@
#define BOARD_RUMBA32_BTT 4204 // RUMBA32 STM32F446VE based controller from BIGTREETECH
#define BOARD_BLACK_STM32F407VE 4205 // BLACK_STM32F407VE
#define BOARD_BLACK_STM32F407ZE 4206 // BLACK_STM32F407ZE
#define BOARD_STEVAL_3DP001V1 4207 // STEVAL-3DP001V1 3D PRINTER BOARD
#define BOARD_BTT_SKR_PRO_V1_1 4208 // BigTreeTech SKR Pro v1.1 (STM32F407ZG)
#define BOARD_BTT_SKR_PRO_V1_2 4209 // BigTreeTech SKR Pro v1.2 (STM32F407ZG)
#define BOARD_BTT_BTT002_V1_0 4210 // BigTreeTech BTT002 v1.0 (STM32F407VG)

View File

@ -30,10 +30,6 @@
#define _A5984 0x5984
#define _DRV8825 0x8825
#define _LV8729 0x8729
#define _L6470 0x6470
#define _L6474 0x6474
#define _L6480 0x6480
#define _POWERSTEP01 0xF00D
#define _TB6560 0x6560
#define _TB6600 0x6600
#define _TMC2100 0x2100
@ -193,16 +189,3 @@
#if HAS_DRIVER(TMC26X)
#define HAS_TMC26X 1
#endif
//
// L64XX Stepper Drivers
//
#if HAS_DRIVER(L6470) || HAS_DRIVER(L6474) || HAS_DRIVER(L6480) || HAS_DRIVER(POWERSTEP01)
#define HAS_L64XX 1
#endif
#if HAS_L64XX && !HAS_DRIVER(L6474)
#define HAS_L64XX_NOT_L6474 1
#endif
#define AXIS_IS_L64XX(A) (AXIS_DRIVER_TYPE_##A(L6470) || AXIS_DRIVER_TYPE_##A(L6474) || AXIS_DRIVER_TYPE_##A(L6480) || AXIS_DRIVER_TYPE_##A(POWERSTEP01))

View File

@ -55,10 +55,6 @@
#include "../../lcd/e3v2/proui/dwin.h"
#endif
#if HAS_L64XX // set L6470 absolute position registers to counts
#include "../../libs/L64XX/L64XX_Marlin.h"
#endif
#if ENABLED(LASER_FEATURE)
#include "../../feature/spindle_laser.h"
#endif
@ -601,20 +597,4 @@ void GcodeSuite::G28() {
TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(old_grblstate));
#if HAS_L64XX
// Set L6470 absolute position registers to counts
// constexpr *might* move this to PROGMEM.
// If not, this will need a PROGMEM directive and an accessor.
#define _EN_ITEM(N) , E_AXIS
static constexpr AxisEnum L64XX_axis_xref[MAX_L64XX] = {
NUM_AXIS_LIST(X_AXIS, Y_AXIS, Z_AXIS, I_AXIS, J_AXIS, K_AXIS, U_AXIS, V_AXIS, W_AXIS),
X_AXIS, Y_AXIS, Z_AXIS, Z_AXIS, Z_AXIS
REPEAT(E_STEPPERS, _EN_ITEM)
};
#undef _EN_ITEM
for (uint8_t j = 1; j <= L64XX::chain[0]; j++) {
const uint8_t cv = L64XX::chain[j];
L64xxManager.set_param((L64XX_axis_t)cv, L6470_ABS_POS, stepper.position(L64XX_axis_xref[cv]));
}
#endif
}

View File

@ -1,151 +0,0 @@
/**
* 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_L64XX
#include "../../gcode.h"
#include "../../../libs/L64XX/L64XX_Marlin.h"
#include "../../../module/stepper/indirection.h"
void echo_yes_no(const bool yes);
inline void L6470_say_status(const L64XX_axis_t axis) {
if (L64xxManager.spi_abort) return;
const L64XX_Marlin::L64XX_shadow_t &sh = L64xxManager.shadow;
L64xxManager.get_status(axis);
L64xxManager.say_axis(axis);
#if ENABLED(L6470_CHITCHAT)
char temp_buf[20];
sprintf_P(temp_buf, PSTR(" status: %4x "), sh.STATUS_AXIS_RAW);
SERIAL_ECHO(temp_buf);
print_bin(sh.STATUS_AXIS_RAW);
switch (sh.STATUS_AXIS_LAYOUT) {
case L6470_STATUS_LAYOUT: SERIAL_ECHOPGM(" L6470"); break;
case L6474_STATUS_LAYOUT: SERIAL_ECHOPGM(" L6474"); break;
case L6480_STATUS_LAYOUT: SERIAL_ECHOPGM(" L6480/powerSTEP01"); break;
}
#endif
SERIAL_ECHOPGM("\n...OUTPUT: ");
SERIAL_ECHOF(sh.STATUS_AXIS & STATUS_HIZ ? F("OFF") : F("ON "));
SERIAL_ECHOPGM(" BUSY: "); echo_yes_no((sh.STATUS_AXIS & STATUS_BUSY) == 0);
SERIAL_ECHOPGM(" DIR: ");
SERIAL_ECHOF((((sh.STATUS_AXIS & STATUS_DIR) >> 4) ^ L64xxManager.index_to_dir[axis]) ? F("FORWARD") : F("REVERSE"));
if (sh.STATUS_AXIS_LAYOUT == L6480_STATUS_LAYOUT) {
SERIAL_ECHOPGM(" Last Command: ");
if (sh.STATUS_AXIS & sh.STATUS_AXIS_WRONG_CMD) SERIAL_ECHOPGM("VALID");
else SERIAL_ECHOPGM("ERROR");
SERIAL_ECHOPGM("\n...THERMAL: ");
switch ((sh.STATUS_AXIS & (sh.STATUS_AXIS_TH_SD | sh.STATUS_AXIS_TH_WRN)) >> 11) {
case 0: SERIAL_ECHOPGM("DEVICE SHUTDOWN"); break;
case 1: SERIAL_ECHOPGM("BRIDGE SHUTDOWN"); break;
case 2: SERIAL_ECHOPGM("WARNING "); break;
case 3: SERIAL_ECHOPGM("OK "); break;
}
}
else {
SERIAL_ECHOPGM(" Last Command: ");
if (!(sh.STATUS_AXIS & sh.STATUS_AXIS_WRONG_CMD)) SERIAL_ECHOPGM("IN");
SERIAL_ECHOPGM("VALID ");
SERIAL_ECHOF(sh.STATUS_AXIS & sh.STATUS_AXIS_NOTPERF_CMD ? F("COMPLETED ") : F("Not PERFORMED"));
SERIAL_ECHOPGM("\n...THERMAL: ", !(sh.STATUS_AXIS & sh.STATUS_AXIS_TH_SD) ? "SHUTDOWN " : !(sh.STATUS_AXIS & sh.STATUS_AXIS_TH_WRN) ? "WARNING " : "OK ");
}
SERIAL_ECHOPGM(" OVERCURRENT:"); echo_yes_no((sh.STATUS_AXIS & sh.STATUS_AXIS_OCD) == 0);
if (sh.STATUS_AXIS_LAYOUT != L6474_STATUS_LAYOUT) {
SERIAL_ECHOPGM(" STALL:"); echo_yes_no((sh.STATUS_AXIS & sh.STATUS_AXIS_STEP_LOSS_A) == 0 || (sh.STATUS_AXIS & sh.STATUS_AXIS_STEP_LOSS_B) == 0);
SERIAL_ECHOPGM(" STEP-CLOCK MODE:"); echo_yes_no((sh.STATUS_AXIS & sh.STATUS_AXIS_SCK_MOD) != 0);
}
else {
SERIAL_ECHOPGM(" STALL: NA "
" STEP-CLOCK MODE: NA"
" UNDER VOLTAGE LOCKOUT: "); echo_yes_no((sh.STATUS_AXIS & sh.STATUS_AXIS_UVLO) == 0);
}
SERIAL_EOL();
}
/**
* M122: Debug L6470 drivers
*/
void GcodeSuite::M122() {
L64xxManager.pause_monitor(true); // Keep monitor_driver() from stealing status
L64xxManager.spi_active = true; // Tell set_directions() a series of SPI transfers is underway
//if (parser.seen('S'))
// tmc_set_report_interval(parser.value_bool());
//else
#if AXIS_IS_L64XX(X)
L6470_say_status(X);
#endif
#if AXIS_IS_L64XX(X2)
L6470_say_status(X2);
#endif
#if AXIS_IS_L64XX(Y)
L6470_say_status(Y);
#endif
#if AXIS_IS_L64XX(Y2)
L6470_say_status(Y2);
#endif
#if AXIS_IS_L64XX(Z)
L6470_say_status(Z);
#endif
#if AXIS_IS_L64XX(Z2)
L6470_say_status(Z2);
#endif
#if AXIS_IS_L64XX(Z3)
L6470_say_status(Z3);
#endif
#if AXIS_IS_L64XX(Z4)
L6470_say_status(Z4);
#endif
#if AXIS_IS_L64XX(E0)
L6470_say_status(E0);
#endif
#if AXIS_IS_L64XX(E1)
L6470_say_status(E1);
#endif
#if AXIS_IS_L64XX(E2)
L6470_say_status(E2);
#endif
#if AXIS_IS_L64XX(E3)
L6470_say_status(E3);
#endif
#if AXIS_IS_L64XX(E4)
L6470_say_status(E4);
#endif
#if AXIS_IS_L64XX(E5)
L6470_say_status(E5);
#endif
#if AXIS_IS_L64XX(E6)
L6470_say_status(E6);
#endif
#if AXIS_IS_L64XX(E7)
L6470_say_status(E7);
#endif
L64xxManager.spi_active = false; // done with all SPI transfers - clear handshake flags
L64xxManager.spi_abort = false;
L64xxManager.pause_monitor(false);
}
#endif // HAS_L64XX

View File

@ -1,417 +0,0 @@
/**
* 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_L64XX
#if AXIS_COLLISION('I')
#error "M906 parameter 'I' collision with axis name."
#endif
#include "../../gcode.h"
#include "../../../libs/L64XX/L64XX_Marlin.h"
#include "../../../module/stepper/indirection.h"
#include "../../../module/planner.h"
#define DEBUG_OUT ENABLED(L6470_CHITCHAT)
#include "../../../core/debug_out.h"
/**
* MACRO to fetch information on the items associated with current limiting
* and maximum voltage output.
*
* L6470 can be setup to shutdown if either current threshold is exceeded.
*
* L6470 output current can not be set directly. It is set indirectly by
* setting the maximum effective output voltage.
*
* Effective output voltage is set by PWM duty cycle.
*
* Maximum effective output voltage is affected by MANY variables. The main ones are:
* KVAL_HOLD
* KVAL_RUN
* KVAL_ACC
* KVAL_DEC
* Vs compensation (if enabled)
*/
void L64XX_report_current(L64XX &motor, const L64XX_axis_t axis) {
if (L64xxManager.spi_abort) return; // don't do anything if set_directions() has occurred
const L64XX_Marlin::L64XX_shadow_t &sh = L64xxManager.shadow;
const uint16_t status = L64xxManager.get_status(axis); //also populates shadow structure
const uint8_t OverCurrent_Threshold = uint8_t(motor.GetParam(L6470_OCD_TH));
auto say_axis_status = [](const L64XX_axis_t axis, const uint16_t status) {
L64xxManager.say_axis(axis);
#if ENABLED(L6470_CHITCHAT)
char tmp[10];
sprintf_P(tmp, PSTR("%4x "), status);
DEBUG_ECHOPGM(" status: ", tmp);
print_bin(status);
#else
UNUSED(status);
#endif
SERIAL_EOL();
};
char temp_buf[10];
switch (sh.STATUS_AXIS_LAYOUT) {
case L6470_STATUS_LAYOUT: // L6470
case L6480_STATUS_LAYOUT: { // L6480 & powerstep01
const uint16_t Stall_Threshold = (uint8_t)motor.GetParam(L6470_STALL_TH),
motor_status = (status & (STATUS_MOT_STATUS)) >> 5,
L6470_ADC_out = motor.GetParam(L6470_ADC_OUT),
L6470_ADC_out_limited = constrain(L6470_ADC_out, 8, 24);
const float comp_coef = 1600.0f / L6470_ADC_out_limited;
const uint16_t MicroSteps = _BV(motor.GetParam(L6470_STEP_MODE) & 0x07);
say_axis_status(axis, sh.STATUS_AXIS_RAW);
SERIAL_ECHOPGM("...OverCurrent Threshold: ");
sprintf_P(temp_buf, PSTR("%2d ("), OverCurrent_Threshold);
SERIAL_ECHO(temp_buf);
SERIAL_ECHO((OverCurrent_Threshold + 1) * motor.OCD_CURRENT_CONSTANT_INV);
SERIAL_ECHOPGM(" mA)");
SERIAL_ECHOPGM(" Stall Threshold: ");
sprintf_P(temp_buf, PSTR("%2d ("), Stall_Threshold);
SERIAL_ECHO(temp_buf);
SERIAL_ECHO((Stall_Threshold + 1) * motor.STALL_CURRENT_CONSTANT_INV);
SERIAL_ECHOPGM(" mA)");
SERIAL_ECHOPGM(" Motor Status: ");
switch (motor_status) {
case 0: SERIAL_ECHOPGM("stopped"); break;
case 1: SERIAL_ECHOPGM("accelerating"); break;
case 2: SERIAL_ECHOPGM("decelerating"); break;
case 3: SERIAL_ECHOPGM("at constant speed"); break;
}
SERIAL_EOL();
SERIAL_ECHOPGM("...MicroSteps: ", MicroSteps,
" ADC_OUT: ", L6470_ADC_out);
SERIAL_ECHOPGM(" Vs_compensation: ");
SERIAL_ECHOF((motor.GetParam(sh.L6470_AXIS_CONFIG) & CONFIG_EN_VSCOMP) ? F("ENABLED ") : F("DISABLED"));
SERIAL_ECHOLNPGM(" Compensation coefficient: ~", comp_coef * 0.01f);
SERIAL_ECHOPGM("...KVAL_HOLD: ", motor.GetParam(L6470_KVAL_HOLD),
" KVAL_RUN : ", motor.GetParam(L6470_KVAL_RUN),
" KVAL_ACC: ", motor.GetParam(L6470_KVAL_ACC),
" KVAL_DEC: ", motor.GetParam(L6470_KVAL_DEC),
" V motor max = ");
switch (motor_status) {
case 0: SERIAL_ECHO(motor.GetParam(L6470_KVAL_HOLD) * 100 / 256); SERIAL_ECHOPGM("% (KVAL_HOLD)"); break;
case 1: SERIAL_ECHO(motor.GetParam(L6470_KVAL_RUN) * 100 / 256); SERIAL_ECHOPGM("% (KVAL_RUN)"); break;
case 2: SERIAL_ECHO(motor.GetParam(L6470_KVAL_ACC) * 100 / 256); SERIAL_ECHOPGM("% (KVAL_ACC)"); break;
case 3: SERIAL_ECHO(motor.GetParam(L6470_KVAL_DEC) * 100 / 256); SERIAL_ECHOPGM("% (KVAL_HOLD)"); break;
}
SERIAL_EOL();
#if ENABLED(L6470_CHITCHAT)
DEBUG_ECHOPGM("...SLEW RATE: ");
switch (sh.STATUS_AXIS_LAYOUT) {
case L6470_STATUS_LAYOUT: {
switch ((motor.GetParam(sh.L6470_AXIS_CONFIG) & CONFIG_POW_SR) >> CONFIG_POW_SR_BIT) {
case 0: { DEBUG_ECHOLNPGM("320V/uS") ; break; }
case 1: { DEBUG_ECHOLNPGM("75V/uS") ; break; }
case 2: { DEBUG_ECHOLNPGM("110V/uS") ; break; }
case 3: { DEBUG_ECHOLNPGM("260V/uS") ; break; }
}
break;
}
case L6480_STATUS_LAYOUT: {
switch (motor.GetParam(L6470_GATECFG1) & CONFIG1_SR ) {
case CONFIG1_SR_220V_us: { DEBUG_ECHOLNPGM("220V/uS") ; break; }
case CONFIG1_SR_400V_us: { DEBUG_ECHOLNPGM("400V/uS") ; break; }
case CONFIG1_SR_520V_us: { DEBUG_ECHOLNPGM("520V/uS") ; break; }
case CONFIG1_SR_980V_us: { DEBUG_ECHOLNPGM("980V/uS") ; break; }
default: { DEBUG_ECHOLNPGM("unknown") ; break; }
}
}
}
#endif
SERIAL_EOL();
break;
}
case L6474_STATUS_LAYOUT: { // L6474
const uint16_t L6470_ADC_out = motor.GetParam(L6470_ADC_OUT) & 0x1F,
L6474_TVAL_val = motor.GetParam(L6474_TVAL) & 0x7F;
say_axis_status(axis, sh.STATUS_AXIS_RAW);
SERIAL_ECHOPGM("...OverCurrent Threshold: ");
sprintf_P(temp_buf, PSTR("%2d ("), OverCurrent_Threshold);
SERIAL_ECHO(temp_buf);
SERIAL_ECHO((OverCurrent_Threshold + 1) * motor.OCD_CURRENT_CONSTANT_INV);
SERIAL_ECHOPGM(" mA)");
SERIAL_ECHOPGM(" TVAL: ");
sprintf_P(temp_buf, PSTR("%2d ("), L6474_TVAL_val);
SERIAL_ECHO(temp_buf);
SERIAL_ECHO((L6474_TVAL_val + 1) * motor.STALL_CURRENT_CONSTANT_INV);
SERIAL_ECHOLNPGM(" mA) Motor Status: NA");
const uint16_t MicroSteps = _BV(motor.GetParam(L6470_STEP_MODE) & 0x07); //NOMORE(MicroSteps, 16);
SERIAL_ECHOPGM("...MicroSteps: ", MicroSteps,
" ADC_OUT: ", L6470_ADC_out);
SERIAL_ECHOLNPGM(" Vs_compensation: NA\n");
SERIAL_ECHOLNPGM("...KVAL_HOLD: NA"
" KVAL_RUN : NA"
" KVAL_ACC: NA"
" KVAL_DEC: NA"
" V motor max = NA");
#if ENABLED(L6470_CHITCHAT)
DEBUG_ECHOPGM("...SLEW RATE: ");
switch ((motor.GetParam(sh.L6470_AXIS_CONFIG) & CONFIG_POW_SR) >> CONFIG_POW_SR_BIT) {
case 0: DEBUG_ECHOLNPGM("320V/uS") ; break;
case 1: DEBUG_ECHOLNPGM("75V/uS") ; break;
case 2: DEBUG_ECHOLNPGM("110V/uS") ; break;
case 3: DEBUG_ECHOLNPGM("260V/uS") ; break;
default: DEBUG_ECHOLNPGM("slew rate: ", (motor.GetParam(sh.L6470_AXIS_CONFIG) & CONFIG_POW_SR) >> CONFIG_POW_SR_BIT); break;
}
#endif
SERIAL_EOL();
SERIAL_EOL();
break;
}
}
}
/**
* M906: report or set KVAL_HOLD which sets the maximum effective voltage provided by the
* PWMs to the steppers
*
* On L6474 this sets the TVAL register (same address).
*
* I - select which driver(s) to change on multi-driver axis
* (default) all drivers on the axis
* 0 - monitor only the first XYZ... driver
* 1 - monitor only X2, Y2, Z2
* 2 - monitor only Z3
* 3 - monitor only Z4
* Xxxx, Yxxx, Zxxx, Axxx, Bxxx, Cxxx, Uxxx, Vxxx, Wxxx, Exxx - axis to change (optional)
* L6474 - current in mA (4A max)
* All others - 0-255
*
* Sets KVAL_HOLD which affects the current being driven through the stepper.
*
* L6470 is used in the STEP-CLOCK mode. KVAL_HOLD is the only KVAL_xxx
* that affects the effective voltage seen by the stepper.
*/
void GcodeSuite::M906() {
L64xxManager.pause_monitor(true); // Keep monitor_driver() from stealing status
#define L6470_SET_KVAL_HOLD(Q) (AXIS_IS_L64XX(Q) ? stepper##Q.setTVALCurrent(value) : stepper##Q.SetParam(L6470_KVAL_HOLD, uint8_t(value)))
DEBUG_ECHOLNPGM("M906");
uint8_t report_current = true;
#if AXIS_IS_L64XX(X2) || AXIS_IS_L64XX(Y2) || AXIS_IS_L64XX(Z2) || AXIS_IS_L64XX(Z3) || AXIS_IS_L64XX(Z4)
const int8_t index = parser.byteval('I', -1);
#else
constexpr int8_t index = -1;
#endif
LOOP_LOGICAL_AXES(i) if (uint16_t value = parser.intval(AXIS_CHAR(i))) {
report_current = false;
if (planner.has_blocks_queued() || planner.cleaning_buffer_counter) {
SERIAL_ECHOLNPGM("Test aborted. Can't set KVAL_HOLD while steppers are moving.");
return;
}
switch (i) {
#if AXIS_IS_L64XX(X) || AXIS_IS_L64XX(X2)
case X_AXIS:
#if AXIS_IS_L64XX(X)
if (index < 0 || index == 0) L6470_SET_KVAL_HOLD(X);
#endif
#if AXIS_IS_L64XX(X2)
if (index < 0 || index == 1) L6470_SET_KVAL_HOLD(X2);
#endif
break;
#endif
#if AXIS_IS_L64XX(Y) || AXIS_IS_L64XX(Y2)
case Y_AXIS:
#if AXIS_IS_L64XX(Y)
if (index < 0 || index == 0) L6470_SET_KVAL_HOLD(Y);
#endif
#if AXIS_IS_L64XX(Y2)
if (index < 0 || index == 1) L6470_SET_KVAL_HOLD(Y2);
#endif
break;
#endif
#if AXIS_IS_L64XX(Z) || AXIS_IS_L64XX(Z2) || AXIS_IS_L64XX(Z3) || AXIS_IS_L64XX(Z4)
case Z_AXIS:
#if AXIS_IS_L64XX(Z)
if (index < 0 || index == 0) L6470_SET_KVAL_HOLD(Z);
#endif
#if AXIS_IS_L64XX(Z2)
if (index < 0 || index == 1) L6470_SET_KVAL_HOLD(Z2);
#endif
#if AXIS_IS_L64XX(Z3)
if (index < 0 || index == 2) L6470_SET_KVAL_HOLD(Z3);
#endif
#if AXIS_IS_L64XX(Z4)
if (index < 0 || index == 3) L6470_SET_KVAL_HOLD(Z4);
#endif
break;
#endif
#if AXIS_IS_L64XX(I)
case I_AXIS: L6470_SET_KVAL_HOLD(I); break;
#endif
#if AXIS_IS_L64XX(J)
case J_AXIS: L6470_SET_KVAL_HOLD(J); break;
#endif
#if AXIS_IS_L64XX(K)
case K_AXIS: L6470_SET_KVAL_HOLD(K); break;
#endif
#if AXIS_IS_L64XX(U)
case U_AXIS: L6470_SET_KVAL_HOLD(U); break;
#endif
#if AXIS_IS_L64XX(V)
case V_AXIS: L6470_SET_KVAL_HOLD(V); break;
#endif
#if AXIS_IS_L64XX(W)
case W_AXIS: L6470_SET_KVAL_HOLD(W); break;
#endif
#if AXIS_IS_L64XX(E0) || AXIS_IS_L64XX(E1) || AXIS_IS_L64XX(E2) || AXIS_IS_L64XX(E3) || AXIS_IS_L64XX(E4) || AXIS_IS_L64XX(E5) || AXIS_IS_L64XX(E6) || AXIS_IS_L64XX(E7)
case E_AXIS: {
const int8_t eindex = get_target_e_stepper_from_command(-2);
#if AXIS_IS_L64XX(E0)
if (eindex < 0 || eindex == 0) L6470_SET_KVAL_HOLD(E0);
#endif
#if AXIS_IS_L64XX(E1)
if (eindex < 0 || eindex == 1) L6470_SET_KVAL_HOLD(E1);
#endif
#if AXIS_IS_L64XX(E2)
if (eindex < 0 || eindex == 2) L6470_SET_KVAL_HOLD(E2);
#endif
#if AXIS_IS_L64XX(E3)
if (eindex < 0 || eindex == 3) L6470_SET_KVAL_HOLD(E3);
#endif
#if AXIS_IS_L64XX(E4)
if (eindex < 0 || eindex == 4) L6470_SET_KVAL_HOLD(E4);
#endif
#if AXIS_IS_L64XX(E5)
if (eindex < 0 || eindex == 5) L6470_SET_KVAL_HOLD(E5);
#endif
#if AXIS_IS_L64XX(E6)
if (eindex < 0 || eindex == 6) L6470_SET_KVAL_HOLD(E6);
#endif
#if AXIS_IS_L64XX(E7)
if (eindex < 0 || eindex == 7) L6470_SET_KVAL_HOLD(E7);
#endif
} break;
#endif
}
}
if (report_current) {
#define L64XX_REPORT_CURRENT(Q) L64XX_report_current(stepper##Q, Q)
L64xxManager.spi_active = true; // Tell set_directions() a series of SPI transfers is underway
#if AXIS_IS_L64XX(X)
L64XX_REPORT_CURRENT(X);
#endif
#if AXIS_IS_L64XX(X2)
L64XX_REPORT_CURRENT(X2);
#endif
#if AXIS_IS_L64XX(Y)
L64XX_REPORT_CURRENT(Y);
#endif
#if AXIS_IS_L64XX(Y2)
L64XX_REPORT_CURRENT(Y2);
#endif
#if AXIS_IS_L64XX(Z)
L64XX_REPORT_CURRENT(Z);
#endif
#if AXIS_IS_L64XX(Z2)
L64XX_REPORT_CURRENT(Z2);
#endif
#if AXIS_IS_L64XX(Z3)
L64XX_REPORT_CURRENT(Z3);
#endif
#if AXIS_IS_L64XX(Z4)
L64XX_REPORT_CURRENT(Z4);
#endif
#if AXIS_IS_L64XX(I)
L64XX_REPORT_CURRENT(I);
#endif
#if AXIS_IS_L64XX(J)
L64XX_REPORT_CURRENT(J);
#endif
#if AXIS_IS_L64XX(K)
L64XX_REPORT_CURRENT(K);
#endif
#if AXIS_IS_L64XX(U)
L64XX_REPORT_CURRENT(U);
#endif
#if AXIS_IS_L64XX(V)
L64XX_REPORT_CURRENT(V);
#endif
#if AXIS_IS_L64XX(W)
L64XX_REPORT_CURRENT(W);
#endif
#if AXIS_IS_L64XX(E0)
L64XX_REPORT_CURRENT(E0);
#endif
#if AXIS_IS_L64XX(E1)
L64XX_REPORT_CURRENT(E1);
#endif
#if AXIS_IS_L64XX(E2)
L64XX_REPORT_CURRENT(E2);
#endif
#if AXIS_IS_L64XX(E3)
L64XX_REPORT_CURRENT(E3);
#endif
#if AXIS_IS_L64XX(E4)
L64XX_REPORT_CURRENT(E4);
#endif
#if AXIS_IS_L64XX(E5)
L64XX_REPORT_CURRENT(E5);
#endif
#if AXIS_IS_L64XX(E6)
L64XX_REPORT_CURRENT(E6);
#endif
#if AXIS_IS_L64XX(E7)
L64XX_REPORT_CURRENT(E7);
#endif
L64xxManager.spi_active = false; // done with all SPI transfers - clear handshake flags
L64xxManager.spi_abort = false;
L64xxManager.pause_monitor(false);
}
}
#endif // HAS_L64XX

View File

@ -1,650 +0,0 @@
/**
* 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/>.
*
*/
//
// NOTE: All tests assume each axis uses matching driver chips.
//
#include "../../../inc/MarlinConfig.h"
#if HAS_L64XX
#include "../../gcode.h"
#include "../../../module/stepper/indirection.h"
#include "../../../module/planner.h"
#include "../../../libs/L64XX/L64XX_Marlin.h"
#define DEBUG_OUT ENABLED(L6470_CHITCHAT)
#include "../../../core/debug_out.h"
/**
* M916: increase KVAL_HOLD until get thermal warning
* NOTE - on L6474 it is TVAL that is used
*
* J - select which driver(s) to monitor on multi-driver axis
* 0 - (default) monitor all drivers on the axis or E0
* 1 - monitor only X, Y, Z, E1
* 2 - monitor only X2, Y2, Z2, E2
* 3 - monitor only Z3, E3
* 4 - monitor only Z4, E4
*
* Xxxx, Yxxx, Zxxx, Exxx - axis to be monitored with displacement
* xxx (1-255) is distance moved on either side of current position
*
* F - feedrate
* optional - will use default max feedrate from configuration.h if not specified
*
* T - current (mA) setting for TVAL (0 - 4A in 31.25mA increments, rounds down) - L6474 only
* optional - will report current value from driver if not specified
*
* K - value for KVAL_HOLD (0 - 255) (ignored for L6474)
* optional - will report current value from driver if not specified
*
* D - time (in seconds) to run each setting of KVAL_HOLD/TVAL
* optional - defaults to zero (runs each setting once)
*/
/**
* This routine is also useful for determining the approximate KVAL_HOLD
* where the stepper stops losing steps. The sound will get noticeably quieter
* as it stops losing steps.
*/
void GcodeSuite::M916() {
DEBUG_ECHOLNPGM("M916");
L64xxManager.pause_monitor(true); // Keep monitor_driver() from stealing status
// Variables used by L64xxManager.get_user_input function - some may not be used
char axis_mon[3][3] = { {" "}, {" "}, {" "} }; // list of Axes to be monitored
L64XX_axis_t axis_index[3];
uint16_t axis_status[3];
uint8_t driver_count = 1;
float position_max;
float position_min;
float final_feedrate;
uint8_t kval_hold;
uint8_t OCD_TH_val = 0;
uint8_t STALL_TH_val = 0;
uint16_t over_current_threshold;
constexpr uint8_t over_current_flag = false; // M916 doesn't play with the overcurrent thresholds
#define DRIVER_TYPE_L6474(Q) AXIS_DRIVER_TYPE_##Q(L6474)
uint8_t j; // general purpose counter
if (L64xxManager.get_user_input(driver_count, axis_index, axis_mon, position_max, position_min, final_feedrate, kval_hold, over_current_flag, OCD_TH_val, STALL_TH_val, over_current_threshold))
return; // quit if invalid user input
DEBUG_ECHOLNPGM("feedrate = ", final_feedrate);
planner.synchronize(); // wait for all current movement commands to complete
const L64XX_Marlin::L64XX_shadow_t &sh = L64xxManager.shadow;
for (j = 0; j < driver_count; j++)
L64xxManager.get_status(axis_index[j]); // clear out any pre-existing error flags
char temp_axis_string[] = " ";
temp_axis_string[0] = axis_mon[0][0]; // need to have a string for use within sprintf format section
char gcode_string[80];
uint16_t status_composite = 0;
uint16_t M91x_counter = kval_hold;
uint16_t M91x_counter_max;
if (sh.STATUS_AXIS_LAYOUT == L6474_STATUS_LAYOUT) {
M91x_counter_max = 128; // TVAL is 7 bits
LIMIT(M91x_counter, 0U, 127U);
}
else
M91x_counter_max = 256; // KVAL_HOLD is 8 bits
uint8_t M91x_delay_s = parser.byteval('D'); // get delay in seconds
millis_t M91x_delay_ms = SEC_TO_MS(M91x_delay_s * 60);
millis_t M91x_delay_end;
DEBUG_ECHOLNPGM(".\n.");
do {
if (sh.STATUS_AXIS_LAYOUT == L6474_STATUS_LAYOUT)
DEBUG_ECHOLNPGM("TVAL current (mA) = ", (M91x_counter + 1) * sh.AXIS_STALL_CURRENT_CONSTANT_INV); // report TVAL current for this run
else
DEBUG_ECHOLNPGM("kval_hold = ", M91x_counter); // report KVAL_HOLD for this run
for (j = 0; j < driver_count; j++)
L64xxManager.set_param(axis_index[j], L6470_KVAL_HOLD, M91x_counter); //set KVAL_HOLD or TVAL (same register address)
M91x_delay_end = millis() + M91x_delay_ms;
do {
// turn the motor(s) both directions
sprintf_P(gcode_string, PSTR("G0 %s%03d F%03d"), temp_axis_string, uint16_t(position_min), uint16_t(final_feedrate));
process_subcommands_now(gcode_string);
sprintf_P(gcode_string, PSTR("G0 %s%03d F%03d"), temp_axis_string, uint16_t(position_max), uint16_t(final_feedrate));
process_subcommands_now(gcode_string);
// get the status after the motors have stopped
planner.synchronize();
status_composite = 0; // clear out the old bits
for (j = 0; j < driver_count; j++) {
axis_status[j] = (~L64xxManager.get_status(axis_index[j])) & sh.L6470_ERROR_MASK; // bits of interest are all active low
status_composite |= axis_status[j] ;
}
if (status_composite) break;
} while (millis() < M91x_delay_end);
if (status_composite) break;
M91x_counter++;
} while (!(status_composite & (sh.STATUS_AXIS_TH_WRN | sh.STATUS_AXIS_TH_SD)) && (M91x_counter < M91x_counter_max));
DEBUG_ECHOLNPGM(".");
#if ENABLED(L6470_CHITCHAT)
if (status_composite) {
L64xxManager.error_status_decode(status_composite, axis_index[0],
sh.STATUS_AXIS_TH_SD, sh.STATUS_AXIS_TH_WRN,
sh.STATUS_AXIS_STEP_LOSS_A, sh.STATUS_AXIS_STEP_LOSS_B,
sh.STATUS_AXIS_OCD, sh.STATUS_AXIS_LAYOUT);
DEBUG_ECHOLNPGM(".");
}
#endif
if ((status_composite & (sh.STATUS_AXIS_TH_WRN | sh.STATUS_AXIS_TH_SD)))
DEBUG_ECHOLNPGM(".\n.\nTest completed normally - Thermal warning/shutdown has occurred");
else if (status_composite)
DEBUG_ECHOLNPGM(".\n.\nTest completed abnormally - non-thermal error has occurred");
else
DEBUG_ECHOLNPGM(".\n.\nTest completed normally - Unable to get to thermal warning/shutdown");
L64xxManager.pause_monitor(false);
}
/**
* M917: Find minimum current thresholds
*
* Decrease OCD current until overcurrent error
* Increase OCD until overcurrent error goes away
* Decrease stall threshold until stall (not done on L6474)
* Increase stall until stall error goes away (not done on L6474)
*
* J - select which driver(s) to monitor on multi-driver axis
* 0 - (default) monitor all drivers on the axis or E0
* 1 - monitor only X, Y, Z, E1
* 2 - monitor only X2, Y2, Z2, E2
* Xxxx, Yxxx, Zxxx, Exxx - axis to be monitored with displacement
* xxx (1-255) is distance moved on either side of current position
*
* F - feedrate
* optional - will use default max feedrate from Configuration.h if not specified
*
* I - starting over-current threshold
* optional - will report current value from driver if not specified
* if there are multiple drivers on the axis then all will be set the same
*
* T - current (mA) setting for TVAL (0 - 4A in 31.25mA increments, rounds down) - L6474 only
* optional - will report current value from driver if not specified
*
* K - value for KVAL_HOLD (0 - 255) (ignored for L6474)
* optional - will report current value from driver if not specified
*/
void GcodeSuite::M917() {
DEBUG_ECHOLNPGM("M917");
L64xxManager.pause_monitor(true); // Keep monitor_driver() from stealing status
char axis_mon[3][3] = { {" "}, {" "}, {" "} }; // list of Axes to be monitored
L64XX_axis_t axis_index[3];
uint16_t axis_status[3];
uint8_t driver_count = 1;
float position_max;
float position_min;
float final_feedrate;
uint8_t kval_hold;
uint8_t OCD_TH_val = 0;
uint8_t STALL_TH_val = 0;
uint16_t over_current_threshold;
constexpr uint8_t over_current_flag = true;
uint8_t j; // general purpose counter
if (L64xxManager.get_user_input(driver_count, axis_index, axis_mon, position_max, position_min, final_feedrate, kval_hold, over_current_flag, OCD_TH_val, STALL_TH_val, over_current_threshold))
return; // quit if invalid user input
DEBUG_ECHOLNPGM("feedrate = ", final_feedrate);
planner.synchronize(); // wait for all current movement commands to complete
const L64XX_Marlin::L64XX_shadow_t &sh = L64xxManager.shadow;
for (j = 0; j < driver_count; j++)
L64xxManager.get_status(axis_index[j]); // clear error flags
char temp_axis_string[] = " ";
temp_axis_string[0] = axis_mon[0][0]; // need a sprintf format string
char gcode_string[80];
uint16_t status_composite = 0;
uint8_t test_phase = 0; // 0 - decreasing OCD - exit when OCD warning occurs (ignore STALL)
// 1 - increasing OCD - exit when OCD warning stops (ignore STALL)
// 2 - OCD finalized - decreasing STALL - exit when STALL warning happens
// 3 - OCD finalized - increasing STALL - exit when STALL warning stop
// 4 - all testing completed
DEBUG_ECHOPGM(".\n.\n.\nover_current threshold : ", (OCD_TH_val + 1) * 375); // first status display
DEBUG_ECHOPGM(" (OCD_TH: : ", OCD_TH_val);
if (sh.STATUS_AXIS_LAYOUT != L6474_STATUS_LAYOUT) {
DEBUG_ECHOPGM(") Stall threshold: ", (STALL_TH_val + 1) * 31.25);
DEBUG_ECHOPGM(" (STALL_TH: ", STALL_TH_val);
}
DEBUG_ECHOLNPGM(")");
do {
if (sh.STATUS_AXIS_LAYOUT != L6474_STATUS_LAYOUT) DEBUG_ECHOPGM("STALL threshold : ", (STALL_TH_val + 1) * 31.25);
DEBUG_ECHOLNPGM(" OCD threshold : ", (OCD_TH_val + 1) * 375);
sprintf_P(gcode_string, PSTR("G0 %s%03d F%03d"), temp_axis_string, uint16_t(position_min), uint16_t(final_feedrate));
process_subcommands_now(gcode_string);
sprintf_P(gcode_string, PSTR("G0 %s%03d F%03d"), temp_axis_string, uint16_t(position_max), uint16_t(final_feedrate));
process_subcommands_now(gcode_string);
planner.synchronize();
status_composite = 0; // clear out the old bits
for (j = 0; j < driver_count; j++) {
axis_status[j] = (~L64xxManager.get_status(axis_index[j])) & sh.L6470_ERROR_MASK; // bits of interest are all active low
status_composite |= axis_status[j];
}
if (status_composite && (status_composite & sh.STATUS_AXIS_UVLO)) {
DEBUG_ECHOLNPGM("Test aborted (Undervoltage lockout active)");
#if ENABLED(L6470_CHITCHAT)
for (j = 0; j < driver_count; j++) {
if (j) DEBUG_ECHOPGM("...");
L64xxManager.error_status_decode(axis_status[j], axis_index[j],
sh.STATUS_AXIS_TH_SD, sh.STATUS_AXIS_TH_WRN,
sh.STATUS_AXIS_STEP_LOSS_A, sh.STATUS_AXIS_STEP_LOSS_B,
sh.STATUS_AXIS_OCD, sh.STATUS_AXIS_LAYOUT);
}
#endif
return;
}
if (status_composite & (sh.STATUS_AXIS_TH_WRN | sh.STATUS_AXIS_TH_SD)) {
DEBUG_ECHOLNPGM("thermal problem - waiting for chip(s) to cool down ");
uint16_t status_composite_temp = 0;
uint8_t k = 0;
do {
k++;
if (!(k % 4)) {
kval_hold *= 0.95;
DEBUG_EOL();
DEBUG_ECHOLNPGM("Lowering KVAL_HOLD by about 5% to ", kval_hold);
for (j = 0; j < driver_count; j++)
L64xxManager.set_param(axis_index[j], L6470_KVAL_HOLD, kval_hold);
}
DEBUG_ECHOLNPGM(".");
reset_stepper_timeout(); // keep steppers powered
safe_delay(5000);
status_composite_temp = 0;
for (j = 0; j < driver_count; j++) {
axis_status[j] = (~L64xxManager.get_status(axis_index[j])) & sh.L6470_ERROR_MASK; // bits of interest are all active low
status_composite_temp |= axis_status[j];
}
}
while (status_composite_temp & (sh.STATUS_AXIS_TH_WRN | sh.STATUS_AXIS_TH_SD));
DEBUG_EOL();
}
if (status_composite & (sh.STATUS_AXIS_STEP_LOSS_A | sh.STATUS_AXIS_STEP_LOSS_B | sh.STATUS_AXIS_OCD)) {
switch (test_phase) {
case 0: {
if (status_composite & sh.STATUS_AXIS_OCD) {
// phase 0 with OCD warning - time to go to next phase
if (OCD_TH_val >= sh.AXIS_OCD_TH_MAX) {
OCD_TH_val = sh.AXIS_OCD_TH_MAX; // limit to max
test_phase = 2; // at highest value so skip phase 1
//DEBUG_ECHOLNPGM("LOGIC E0A OCD at highest - skip to 2");
DEBUG_ECHOLNPGM("OCD at highest - OCD finalized");
}
else {
OCD_TH_val++; // normal exit to next phase
test_phase = 1; // setup for first pass of phase 1
//DEBUG_ECHOLNPGM("LOGIC E0B - inc OCD & go to 1");
DEBUG_ECHOLNPGM("inc OCD");
}
}
else { // phase 0 without OCD warning - keep on decrementing if can
if (OCD_TH_val) {
OCD_TH_val--; // try lower value
//DEBUG_ECHOLNPGM("LOGIC E0C - dec OCD");
DEBUG_ECHOLNPGM("dec OCD");
}
else {
test_phase = 2; // at lowest value without warning so skip phase 1
//DEBUG_ECHOLNPGM("LOGIC E0D - OCD at latest - go to 2");
DEBUG_ECHOLNPGM("OCD finalized");
}
}
} break;
case 1: {
if (status_composite & sh.STATUS_AXIS_OCD) {
// phase 1 with OCD warning - increment if can
if (OCD_TH_val >= sh.AXIS_OCD_TH_MAX) {
OCD_TH_val = sh.AXIS_OCD_TH_MAX; // limit to max
test_phase = 2; // at highest value so go to next phase
//DEBUG_ECHOLNPGM("LOGIC E1A - OCD at max - go to 2");
DEBUG_ECHOLNPGM("OCD finalized");
}
else {
OCD_TH_val++; // try a higher value
//DEBUG_ECHOLNPGM("LOGIC E1B - inc OCD");
DEBUG_ECHOLNPGM("inc OCD");
}
}
else { // phase 1 without OCD warning - normal exit to phase 2
test_phase = 2;
//DEBUG_ECHOLNPGM("LOGIC E1C - no OCD warning - go to 1");
DEBUG_ECHOLNPGM("OCD finalized");
}
} break;
case 2: {
if (sh.STATUS_AXIS_LAYOUT == L6474_STATUS_LAYOUT) { // skip all STALL_TH steps if L6474
test_phase = 4;
break;
}
if (status_composite & (sh.STATUS_AXIS_STEP_LOSS_A | sh.STATUS_AXIS_STEP_LOSS_B)) {
// phase 2 with stall warning - time to go to next phase
if (STALL_TH_val >= 127) {
STALL_TH_val = 127; // limit to max
//DEBUG_ECHOLNPGM("LOGIC E2A - STALL warning, STALL at max, quit");
DEBUG_ECHOLNPGM("finished - STALL at maximum value but still have stall warning");
test_phase = 4;
}
else {
test_phase = 3; // normal exit to next phase (found failing value of STALL)
STALL_TH_val++; // setup for first pass of phase 3
//DEBUG_ECHOLNPGM("LOGIC E2B - INC - STALL warning, inc Stall, go to 3");
DEBUG_ECHOLNPGM("inc Stall");
}
}
else { // phase 2 without stall warning - decrement if can
if (STALL_TH_val) {
STALL_TH_val--; // try a lower value
//DEBUG_ECHOLNPGM("LOGIC E2C - no STALL, dec STALL");
DEBUG_ECHOLNPGM("dec STALL");
}
else {
DEBUG_ECHOLNPGM("finished - STALL at lowest value but still do NOT have stall warning");
test_phase = 4;
//DEBUG_ECHOLNPGM("LOGIC E2D - no STALL, at lowest so quit");
}
}
} break;
case 3: {
if (sh.STATUS_AXIS_LAYOUT == L6474_STATUS_LAYOUT) { // skip all STALL_TH steps if L6474
test_phase = 4;
break;
}
if (status_composite & (sh.STATUS_AXIS_STEP_LOSS_A | sh.STATUS_AXIS_STEP_LOSS_B)) {
// phase 3 with stall warning - increment if can
if (STALL_TH_val >= 127) {
STALL_TH_val = 127; // limit to max
DEBUG_ECHOLNPGM("finished - STALL at maximum value but still have stall warning");
test_phase = 4;
//DEBUG_ECHOLNPGM("LOGIC E3A - STALL, at max so quit");
}
else {
STALL_TH_val++; // still looking for passing value
//DEBUG_ECHOLNPGM("LOGIC E3B - STALL, inc stall");
DEBUG_ECHOLNPGM("inc stall");
}
}
else { //phase 3 without stall warning but have OCD warning
DEBUG_ECHOLNPGM("Hardware problem - OCD warning without STALL warning");
test_phase = 4;
//DEBUG_ECHOLNPGM("LOGIC E3C - not STALLED, hardware problem (quit)");
}
} break;
}
}
else {
switch (test_phase) {
case 0: { // phase 0 without OCD warning - keep on decrementing if can
if (OCD_TH_val) {
OCD_TH_val--; // try lower value
//DEBUG_ECHOLNPGM("LOGIC N0A - DEC OCD");
DEBUG_ECHOLNPGM("DEC OCD");
}
else {
test_phase = 2; // at lowest value without warning so skip phase 1
//DEBUG_ECHOLNPGM("LOGIC N0B - OCD at lowest (go to phase 2)");
DEBUG_ECHOLNPGM("OCD finalized");
}
} break;
case 1: //DEBUG_ECHOLNPGM("LOGIC N1 (go directly to 2)"); // phase 1 without OCD warning - drop directly to phase 2
DEBUG_ECHOLNPGM("OCD finalized");
case 2: { // phase 2 without stall warning - keep on decrementing if can
if (sh.STATUS_AXIS_LAYOUT == L6474_STATUS_LAYOUT) { // skip all STALL_TH steps if L6474
test_phase = 4;
break;
}
if (STALL_TH_val) {
STALL_TH_val--; // try a lower value (stay in phase 2)
//DEBUG_ECHOLNPGM("LOGIC N2B - dec STALL");
DEBUG_ECHOLNPGM("dec STALL");
}
else {
DEBUG_ECHOLNPGM("finished - STALL at lowest value but still no stall warning");
test_phase = 4;
//DEBUG_ECHOLNPGM("LOGIC N2C - STALL at lowest (quit)");
}
} break;
case 3: {
if (sh.STATUS_AXIS_LAYOUT == L6474_STATUS_LAYOUT) { // skip all STALL_TH steps if L6474
test_phase = 4;
break;
}
test_phase = 4;
//DEBUG_ECHOLNPGM("LOGIC N3 - finished!");
DEBUG_ECHOLNPGM("finished!");
} break; // phase 3 without any warnings - desired exit
} //
} // end of status checks
if (test_phase != 4) {
for (j = 0; j < driver_count; j++) { // update threshold(s)
L64xxManager.set_param(axis_index[j], L6470_OCD_TH, OCD_TH_val);
if (sh.STATUS_AXIS_LAYOUT != L6474_STATUS_LAYOUT) L64xxManager.set_param(axis_index[j], L6470_STALL_TH, STALL_TH_val);
if (L64xxManager.get_param(axis_index[j], L6470_OCD_TH) != OCD_TH_val) DEBUG_ECHOLNPGM("OCD mismatch");
if ((L64xxManager.get_param(axis_index[j], L6470_STALL_TH) != STALL_TH_val) && (sh.STATUS_AXIS_LAYOUT != L6474_STATUS_LAYOUT)) DEBUG_ECHOLNPGM("STALL mismatch");
}
}
} while (test_phase != 4);
DEBUG_ECHOLNPGM(".");
if (status_composite) {
#if ENABLED(L6470_CHITCHAT)
for (j = 0; j < driver_count; j++) {
if (j) DEBUG_ECHOPGM("...");
L64xxManager.error_status_decode(axis_status[j], axis_index[j],
sh.STATUS_AXIS_TH_SD, sh.STATUS_AXIS_TH_WRN,
sh.STATUS_AXIS_STEP_LOSS_A, sh.STATUS_AXIS_STEP_LOSS_B,
sh.STATUS_AXIS_OCD, sh.STATUS_AXIS_LAYOUT);
}
DEBUG_ECHOLNPGM(".");
#endif
DEBUG_ECHOLNPGM("Completed with errors");
}
else
DEBUG_ECHOLNPGM("Completed with no errors");
DEBUG_ECHOLNPGM(".");
L64xxManager.pause_monitor(false);
}
/**
* M918: increase speed until error or max feedrate achieved (as shown in configuration.h))
*
* J - select which driver(s) to monitor on multi-driver axis
* 0 - (default) monitor all drivers on the axis or E0
* 1 - monitor only X, Y, Z, E1
* 2 - monitor only X2, Y2, Z2, E2
* Xxxx, Yxxx, Zxxx, Exxx - axis to be monitored with displacement
* xxx (1-255) is distance moved on either side of current position
*
* I - over current threshold
* optional - will report current value from driver if not specified
*
* T - current (mA) setting for TVAL (0 - 4A in 31.25mA increments, rounds down) - L6474 only
* optional - will report current value from driver if not specified
*
* K - value for KVAL_HOLD (0 - 255) (ignored for L6474)
* optional - will report current value from driver if not specified
*
* M - value for microsteps (1 - 128) (optional)
* optional - will report current value from driver if not specified
*/
void GcodeSuite::M918() {
DEBUG_ECHOLNPGM("M918");
L64xxManager.pause_monitor(true); // Keep monitor_driver() from stealing status
char axis_mon[3][3] = { {" "}, {" "}, {" "} }; // list of Axes to be monitored
L64XX_axis_t axis_index[3];
uint16_t axis_status[3];
uint8_t driver_count = 1;
float position_max, position_min;
float final_feedrate;
uint8_t kval_hold;
uint8_t OCD_TH_val = 0;
uint8_t STALL_TH_val = 0;
uint16_t over_current_threshold;
constexpr uint8_t over_current_flag = true;
const L64XX_Marlin::L64XX_shadow_t &sh = L64xxManager.shadow;
uint8_t j; // general purpose counter
if (L64xxManager.get_user_input(driver_count, axis_index, axis_mon, position_max, position_min, final_feedrate, kval_hold, over_current_flag, OCD_TH_val, STALL_TH_val, over_current_threshold))
return; // quit if invalid user input
L64xxManager.get_status(axis_index[0]); // populate shadow array
uint8_t m_steps = parser.byteval('M');
if (m_steps != 0) {
LIMIT(m_steps, 1, sh.STATUS_AXIS_LAYOUT == L6474_STATUS_LAYOUT ? 16 : 128); // L6474
uint8_t stepVal;
for (stepVal = 0; stepVal < 8; stepVal++) { // convert to L64xx register value
if (m_steps == 1) break;
m_steps >>= 1;
}
if (sh.STATUS_AXIS_LAYOUT == L6474_STATUS_LAYOUT)
stepVal |= 0x98; // NO SYNC
else
stepVal |= (!SYNC_EN) | SYNC_SEL_1 | stepVal;
for (j = 0; j < driver_count; j++) {
L64xxManager.set_param(axis_index[j], dSPIN_HARD_HIZ, 0); // can't write STEP register if stepper being powered
// results in an extra NOOP being sent (data 00)
L64xxManager.set_param(axis_index[j], L6470_STEP_MODE, stepVal); // set microsteps
}
}
m_steps = L64xxManager.get_param(axis_index[0], L6470_STEP_MODE) & 0x07; // get microsteps
DEBUG_ECHOLNPGM("Microsteps = ", _BV(m_steps));
DEBUG_ECHOLNPGM("target (maximum) feedrate = ", final_feedrate);
const float feedrate_inc = final_feedrate / 10, // Start at 1/10 of max & go up by 1/10 per step
fr_limit = final_feedrate * 0.99f; // Rounding-safe comparison value
float current_feedrate = 0;
planner.synchronize(); // Wait for moves to complete
for (j = 0; j < driver_count; j++)
L64xxManager.get_status(axis_index[j]); // Clear error flags
char temp_axis_string[2] = " ";
temp_axis_string[0] = axis_mon[0][0]; // Need a sprintf format string
//temp_axis_string[1] = '\n';
char gcode_string[80];
uint16_t status_composite = 0;
DEBUG_ECHOLNPGM(".\n.\n."); // Make feedrate outputs easier to read
do {
current_feedrate += feedrate_inc;
DEBUG_ECHOLNPGM("...feedrate = ", current_feedrate);
sprintf_P(gcode_string, PSTR("G0 %s%03d F%03d"), temp_axis_string, uint16_t(position_min), uint16_t(current_feedrate));
process_subcommands_now(gcode_string);
sprintf_P(gcode_string, PSTR("G0 %s%03d F%03d"), temp_axis_string, uint16_t(position_max), uint16_t(current_feedrate));
process_subcommands_now(gcode_string);
planner.synchronize();
for (j = 0; j < driver_count; j++) {
axis_status[j] = (~L64xxManager.get_status(axis_index[j])) & 0x0800; // Bits of interest are all active LOW
status_composite |= axis_status[j];
}
if (status_composite) break; // Break on any error
} while (current_feedrate < fr_limit);
DEBUG_ECHOPGM("Completed with ");
if (status_composite) {
DEBUG_ECHOLNPGM("errors");
#if ENABLED(L6470_CHITCHAT)
for (j = 0; j < driver_count; j++) {
if (j) DEBUG_ECHOPGM("...");
L64xxManager.error_status_decode(axis_status[j], axis_index[j],
sh.STATUS_AXIS_TH_SD, sh.STATUS_AXIS_TH_WRN,
sh.STATUS_AXIS_STEP_LOSS_A, sh.STATUS_AXIS_STEP_LOSS_B,
sh.STATUS_AXIS_OCD, sh.STATUS_AXIS_LAYOUT);
}
#endif
}
else
DEBUG_ECHOLNPGM("no errors");
L64xxManager.pause_monitor(false);
}
#endif // HAS_L64XX

View File

@ -1005,14 +1005,6 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) {
case 919: M919(); break; // M919: Set stepper Chopper Times
#endif
#if HAS_L64XX
case 122: M122(); break; // M122: Report status
case 906: M906(); break; // M906: Set or get motor drive level
case 916: M916(); break; // M916: L6470 tuning: Increase drive level until thermal warning
case 917: M917(); break; // M917: L6470 tuning: Find minimum current thresholds
case 918: M918(); break; // M918: L6470 tuning: Increase speed until max or error
#endif
#if HAS_MICROSTEPS
case 350: M350(); break; // M350: Set microstepping mode. Warning: Steps per unit remains unchanged. S code sets stepping mode for all drivers.
case 351: M351(); break; // M351: Toggle MS1 MS2 pins directly, S# determines MS1 or MS2, X# sets the pin high/low.

View File

@ -155,7 +155,7 @@
* M120 - Enable endstops detection.
* M121 - Disable endstops detection.
*
* M122 - Debug stepper (Requires at least one _DRIVER_TYPE defined as TMC2130/2160/5130/5160/2208/2209/2660 or L6470)
* M122 - Debug stepper (Requires at least one _DRIVER_TYPE defined as TMC2130/2160/5130/5160/2208/2209/2660)
* M123 - Report fan tachometers. (Requires En_FAN_TACHO_PIN) Optionally set auto-report interval. (Requires AUTO_REPORT_FANS)
* M125 - Save current position and move to filament change position. (Requires PARK_HEAD_ON_PAUSE)
*
@ -286,7 +286,7 @@
* M871 - Print/reset/clear first layer temperature offset values. (Requires PTC_PROBE, PTC_BED, or PTC_HOTEND)
* M876 - Handle Prompt Response. (Requires HOST_PROMPT_SUPPORT and not EMERGENCY_PARSER)
* M900 - Get or Set Linear Advance K-factor. (Requires LIN_ADVANCE)
* M906 - Set or get motor current in milliamps using axis codes XYZE, etc. Report values if no axis codes given. (Requires at least one _DRIVER_TYPE defined as TMC2130/2160/5130/5160/2208/2209/2660 or L6470)
* M906 - Set or get motor current in milliamps using axis codes XYZE, etc. Report values if no axis codes given. (Requires at least one _DRIVER_TYPE defined as TMC2130/2160/5130/5160/2208/2209/2660)
* M907 - Set digital trimpot motor current using axis codes. (Requires a board with digital trimpots)
* M908 - Control digital trimpot directly. (Requires HAS_MOTOR_CURRENT_DAC or DIGIPOTSS_PIN)
* M909 - Print digipot/DAC current value. (Requires HAS_MOTOR_CURRENT_DAC)
@ -295,9 +295,6 @@
* M912 - Clear stepper driver overtemperature pre-warn condition flag. (Requires at least one _DRIVER_TYPE defined as TMC2130/2160/5130/5160/2208/2209/2660)
* M913 - Set HYBRID_THRESHOLD speed. (Requires HYBRID_THRESHOLD)
* M914 - Set StallGuard sensitivity. (Requires SENSORLESS_HOMING or SENSORLESS_PROBING)
* M916 - L6470 tuning: Increase KVAL_HOLD until thermal warning. (Requires at least one _DRIVER_TYPE L6470)
* M917 - L6470 tuning: Find minimum current thresholds. (Requires at least one _DRIVER_TYPE L6470)
* M918 - L6470 tuning: Increase speed until max or error. (Requires at least one _DRIVER_TYPE L6470)
* M919 - Get or Set motor Chopper Times (time_off, hysteresis_end, hysteresis_start) using axis codes XYZE, etc. If no parameters are given, report. (Requires at least one _DRIVER_TYPE defined as TMC2130/2160/5130/5160/2208/2209/2660)
* M951 - Set Magnetic Parking Extruder parameters. (Requires MAGNETIC_PARKING_EXTRUDER)
* M3426 - Read MCP3426 ADC over I2C. (Requires HAS_MCP3426_ADC)
@ -1163,14 +1160,6 @@ private:
static void M919();
#endif
#if HAS_L64XX
static void M122();
static void M906();
static void M916();
static void M917();
static void M918();
#endif
#if HAS_MOTOR_CURRENT_SPI || HAS_MOTOR_CURRENT_PWM || HAS_MOTOR_CURRENT_I2C || HAS_MOTOR_CURRENT_DAC
static void M907();
#if HAS_MOTOR_CURRENT_SPI || HAS_MOTOR_CURRENT_PWM

View File

@ -28,12 +28,6 @@
#if ENABLED(M114_DETAIL)
#if HAS_L64XX
#include "../../libs/L64XX/L64XX_Marlin.h"
#define DEBUG_OUT ENABLED(L6470_CHITCHAT)
#include "../../core/debug_out.h"
#endif
void report_all_axis_pos(const xyze_pos_t &pos, const uint8_t n=LOGICAL_AXES, const uint8_t precision=3) {
char str[12];
LOOP_L_N(a, n) {
@ -84,89 +78,6 @@
planner.synchronize();
#if HAS_L64XX
char temp_buf[80];
int32_t temp;
//#define ABS_POS_SIGN_MASK 0b1111 1111 1110 0000 0000 0000 0000 0000
#define ABS_POS_SIGN_MASK 0b11111111111000000000000000000000
#define REPORT_ABSOLUTE_POS(Q) do{ \
L64xxManager.say_axis(Q, false); \
temp = L6470_GETPARAM(L6470_ABS_POS,Q); \
if (temp & ABS_POS_SIGN_MASK) temp |= ABS_POS_SIGN_MASK; \
sprintf_P(temp_buf, PSTR(":%8ld "), temp); \
DEBUG_ECHO(temp_buf); \
}while(0)
DEBUG_ECHOPGM("\nL6470:");
#if AXIS_IS_L64XX(X)
REPORT_ABSOLUTE_POS(X);
#endif
#if AXIS_IS_L64XX(X2)
REPORT_ABSOLUTE_POS(X2);
#endif
#if AXIS_IS_L64XX(Y)
REPORT_ABSOLUTE_POS(Y);
#endif
#if AXIS_IS_L64XX(Y2)
REPORT_ABSOLUTE_POS(Y2);
#endif
#if AXIS_IS_L64XX(Z)
REPORT_ABSOLUTE_POS(Z);
#endif
#if AXIS_IS_L64XX(Z2)
REPORT_ABSOLUTE_POS(Z2);
#endif
#if AXIS_IS_L64XX(Z3)
REPORT_ABSOLUTE_POS(Z3);
#endif
#if AXIS_IS_L64XX(Z4)
REPORT_ABSOLUTE_POS(Z4);
#endif
#if AXIS_IS_L64XX(I)
REPORT_ABSOLUTE_POS(I);
#endif
#if AXIS_IS_L64XX(J)
REPORT_ABSOLUTE_POS(J);
#endif
#if AXIS_IS_L64XX(K)
REPORT_ABSOLUTE_POS(K);
#endif
#if AXIS_IS_L64XX(U)
REPORT_ABSOLUTE_POS(U);
#endif
#if AXIS_IS_L64XX(V)
REPORT_ABSOLUTE_POS(V);
#endif
#if AXIS_IS_L64XX(W)
REPORT_ABSOLUTE_POS(W);
#endif
#if AXIS_IS_L64XX(E0)
REPORT_ABSOLUTE_POS(E0);
#endif
#if AXIS_IS_L64XX(E1)
REPORT_ABSOLUTE_POS(E1);
#endif
#if AXIS_IS_L64XX(E2)
REPORT_ABSOLUTE_POS(E2);
#endif
#if AXIS_IS_L64XX(E3)
REPORT_ABSOLUTE_POS(E3);
#endif
#if AXIS_IS_L64XX(E4)
REPORT_ABSOLUTE_POS(E4);
#endif
#if AXIS_IS_L64XX(E5)
REPORT_ABSOLUTE_POS(E5);
#endif
#if AXIS_IS_L64XX(E6)
REPORT_ABSOLUTE_POS(E6);
#endif
#if AXIS_IS_L64XX(E7)
REPORT_ABSOLUTE_POS(E7);
#endif
SERIAL_EOL();
#endif // HAS_L64XX
SERIAL_ECHOPGM("Stepper:");
LOOP_LOGICAL_AXES(i) {
SERIAL_ECHOPGM_P((PGM_P)pgm_read_ptr(&SP_AXIS_LBL[i]), stepper.position((AxisEnum)i));

View File

@ -1610,7 +1610,7 @@
#define HAS_X_MS_PINS 1
#endif
#if PIN_EXISTS(X2_ENABLE) || AXIS_IS_L64XX(X2) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(X2))
#if PIN_EXISTS(X2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(X2))
#define HAS_X2_ENABLE 1
#endif
#if PIN_EXISTS(X2_DIR)
@ -1631,7 +1631,7 @@
#endif
#if HAS_Y_AXIS
#if PIN_EXISTS(Y_ENABLE) || AXIS_IS_L64XX(Y) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y))
#if PIN_EXISTS(Y_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y))
#define HAS_Y_ENABLE 1
#endif
#if PIN_EXISTS(Y_DIR)
@ -1644,7 +1644,7 @@
#define HAS_Y_MS_PINS 1
#endif
#if PIN_EXISTS(Y2_ENABLE) || AXIS_IS_L64XX(Y2) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y2))
#if PIN_EXISTS(Y2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y2))
#define HAS_Y2_ENABLE 1
#endif
#if PIN_EXISTS(Y2_DIR)
@ -1664,7 +1664,7 @@
#endif
#if HAS_Z_AXIS
#if PIN_EXISTS(Z_ENABLE) || AXIS_IS_L64XX(Z) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z))
#if PIN_EXISTS(Z_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z))
#define HAS_Z_ENABLE 1
#endif
#if PIN_EXISTS(Z_DIR)
@ -1684,7 +1684,7 @@
#endif
#if NUM_Z_STEPPERS >= 2
#if PIN_EXISTS(Z2_ENABLE) || AXIS_IS_L64XX(Z2) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z2))
#if PIN_EXISTS(Z2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z2))
#define HAS_Z2_ENABLE 1
#endif
#if PIN_EXISTS(Z2_DIR)
@ -1699,7 +1699,7 @@
#endif
#if NUM_Z_STEPPERS >= 3
#if PIN_EXISTS(Z3_ENABLE) || AXIS_IS_L64XX(Z3) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z3))
#if PIN_EXISTS(Z3_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z3))
#define HAS_Z3_ENABLE 1
#endif
#if PIN_EXISTS(Z3_DIR)
@ -1714,7 +1714,7 @@
#endif
#if NUM_Z_STEPPERS >= 4
#if PIN_EXISTS(Z4_ENABLE) || AXIS_IS_L64XX(Z4) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z4))
#if PIN_EXISTS(Z4_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z4))
#define HAS_Z4_ENABLE 1
#endif
#if PIN_EXISTS(Z4_DIR)
@ -1729,7 +1729,7 @@
#endif
#if HAS_I_AXIS
#if PIN_EXISTS(I_ENABLE) || AXIS_IS_L64XX(I) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(I))
#if PIN_EXISTS(I_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(I))
#define HAS_I_ENABLE 1
#endif
#if PIN_EXISTS(I_DIR)
@ -1749,7 +1749,7 @@
#endif
#if HAS_J_AXIS
#if PIN_EXISTS(J_ENABLE) || AXIS_IS_L64XX(J) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(J))
#if PIN_EXISTS(J_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(J))
#define HAS_J_ENABLE 1
#endif
#if PIN_EXISTS(J_DIR)
@ -1769,7 +1769,7 @@
#endif
#if HAS_K_AXIS
#if PIN_EXISTS(K_ENABLE) || AXIS_IS_L64XX(K) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(K))
#if PIN_EXISTS(K_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(K))
#define HAS_K_ENABLE 1
#endif
#if PIN_EXISTS(K_DIR)
@ -1789,7 +1789,7 @@
#endif
#if HAS_U_AXIS
#if PIN_EXISTS(U_ENABLE) || AXIS_IS_L64XX(U) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(U))
#if PIN_EXISTS(U_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(U))
#define HAS_U_ENABLE 1
#endif
#if PIN_EXISTS(U_DIR)
@ -1809,7 +1809,7 @@
#endif
#if HAS_V_AXIS
#if PIN_EXISTS(V_ENABLE) || AXIS_IS_L64XX(V) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(V))
#if PIN_EXISTS(V_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(V))
#define HAS_V_ENABLE 1
#endif
#if PIN_EXISTS(V_DIR)
@ -1829,7 +1829,7 @@
#endif
#if HAS_W_AXIS
#if PIN_EXISTS(W_ENABLE) || AXIS_IS_L64XX(W) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(W))
#if PIN_EXISTS(W_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(W))
#define HAS_W_ENABLE 1
#endif
#if PIN_EXISTS(W_DIR)
@ -1851,7 +1851,7 @@
// Extruder steppers and solenoids
#if HAS_EXTRUDERS
#if PIN_EXISTS(E0_ENABLE) || AXIS_IS_L64XX(E0) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E0))
#if PIN_EXISTS(E0_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E0))
#define HAS_E0_ENABLE 1
#endif
#if PIN_EXISTS(E0_DIR)
@ -1865,7 +1865,7 @@
#endif
#if E_STEPPERS > 1 || ENABLED(E_DUAL_STEPPER_DRIVERS)
#if PIN_EXISTS(E1_ENABLE) || AXIS_IS_L64XX(E1) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E1))
#if PIN_EXISTS(E1_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E1))
#define HAS_E1_ENABLE 1
#endif
#if PIN_EXISTS(E1_DIR)
@ -1880,7 +1880,7 @@
#endif
#if E_STEPPERS > 2
#if PIN_EXISTS(E2_ENABLE) || AXIS_IS_L64XX(E2) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E2))
#if PIN_EXISTS(E2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E2))
#define HAS_E2_ENABLE 1
#endif
#if PIN_EXISTS(E2_DIR)
@ -1895,7 +1895,7 @@
#endif
#if E_STEPPERS > 3
#if PIN_EXISTS(E3_ENABLE) || AXIS_IS_L64XX(E3) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E3))
#if PIN_EXISTS(E3_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E3))
#define HAS_E3_ENABLE 1
#endif
#if PIN_EXISTS(E3_DIR)
@ -1910,7 +1910,7 @@
#endif
#if E_STEPPERS > 4
#if PIN_EXISTS(E4_ENABLE) || AXIS_IS_L64XX(E4) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E4))
#if PIN_EXISTS(E4_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E4))
#define HAS_E4_ENABLE 1
#endif
#if PIN_EXISTS(E4_DIR)
@ -1925,7 +1925,7 @@
#endif
#if E_STEPPERS > 5
#if PIN_EXISTS(E5_ENABLE) || AXIS_IS_L64XX(E5) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E5))
#if PIN_EXISTS(E5_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E5))
#define HAS_E5_ENABLE 1
#endif
#if PIN_EXISTS(E5_DIR)
@ -1940,7 +1940,7 @@
#endif
#if E_STEPPERS > 6
#if PIN_EXISTS(E6_ENABLE) || AXIS_IS_L64XX(E6) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E6))
#if PIN_EXISTS(E6_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E6))
#define HAS_E6_ENABLE 1
#endif
#if PIN_EXISTS(E6_DIR)
@ -1955,7 +1955,7 @@
#endif
#if E_STEPPERS > 7
#if PIN_EXISTS(E7_ENABLE) || AXIS_IS_L64XX(E7) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E7))
#if PIN_EXISTS(E7_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E7))
#define HAS_E7_ENABLE 1
#endif
#if PIN_EXISTS(E7_DIR)

View File

@ -350,7 +350,7 @@
#elif defined(HAVE_TMC2208)
#error "HAVE_TMC2208 is now [AXIS]_DRIVER_TYPE TMC2208."
#elif defined(HAVE_L6470DRIVER)
#error "HAVE_L6470DRIVER is now [AXIS]_DRIVER_TYPE L6470."
#error "HAVE_L6470DRIVER is obsolete. L64xx stepper drivers are no longer supported in Marlin."
#elif defined(X_IS_TMC) || defined(X2_IS_TMC) || defined(Y_IS_TMC) || defined(Y2_IS_TMC) || defined(Z_IS_TMC) || defined(Z2_IS_TMC) || defined(Z3_IS_TMC) \
|| defined(E0_IS_TMC) || defined(E1_IS_TMC) || defined(E2_IS_TMC) || defined(E3_IS_TMC) || defined(E4_IS_TMC) || defined(E5_IS_TMC) || defined(E6_IS_TMC) || defined(E7_IS_TMC)
#error "[AXIS]_IS_TMC is now [AXIS]_DRIVER_TYPE TMC26X."
@ -363,9 +363,6 @@
#elif defined(X_IS_TMC2208) || defined(X2_IS_TMC2208) || defined(Y_IS_TMC2208) || defined(Y2_IS_TMC2208) || defined(Z_IS_TMC2208) || defined(Z2_IS_TMC2208) || defined(Z3_IS_TMC2208) \
|| defined(E0_IS_TMC2208) || defined(E1_IS_TMC2208) || defined(E2_IS_TMC2208) || defined(E3_IS_TMC2208) || defined(E4_IS_TMC2208) || defined(E5_IS_TMC2208) || defined(E6_IS_TMC2208) || defined(E7_IS_TMC2208)
#error "[AXIS]_IS_TMC2208 is now [AXIS]_DRIVER_TYPE TMC2208."
#elif defined(X_IS_L6470) || defined(X2_IS_L6470) || defined(Y_IS_L6470) || defined(Y2_IS_L6470) || defined(Z_IS_L6470) || defined(Z2_IS_L6470) || defined(Z3_IS_L6470) \
|| defined(E0_IS_L6470) || defined(E1_IS_L6470) || defined(E2_IS_L6470) || defined(E3_IS_L6470) || defined(E4_IS_L6470) || defined(E5_IS_L6470) || defined(E6_IS_L6470) || defined(E7_IS_L6470)
#error "[AXIS]_IS_L6470 is now [AXIS]_DRIVER_TYPE L6470."
#elif defined(AUTOMATIC_CURRENT_CONTROL)
#error "AUTOMATIC_CURRENT_CONTROL is now MONITOR_DRIVER_STATUS."
#elif defined(FILAMENT_CHANGE_LOAD_LENGTH)
@ -647,6 +644,26 @@
#error "LEVEL_CENTER_TOO is now BED_TRAMMING_INCLUDE_CENTER."
#endif
// L64xx stepper drivers have been removed
#define _L6470 0x6470
#define _L6474 0x6474
#define _L6480 0x6480
#define _POWERSTEP01 0xF00D
#if HAS_DRIVER(L6470)
#error "L6470 stepper drivers are no longer supported in Marlin."
#elif HAS_DRIVER(L6474)
#error "L6474 stepper drivers are no longer supported in Marlin."
#elif HAS_DRIVER(L6480)
#error "L6480 stepper drivers are no longer supported in Marlin."
#elif HAS_DRIVER(POWERSTEP01)
#error "POWERSTEP01 stepper drivers are no longer supported in Marlin."
#endif
#undef _L6470
#undef _L6474
#undef _L6480
#undef _POWERSTEP01
// Check AXIS_RELATIVE_MODES
constexpr float arm[] = AXIS_RELATIVE_MODES;
static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _LOGICAL_AXES_STR "elements.");
@ -3533,7 +3550,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
/**
* TMC SPI Chaining
*/
#define IN_CHAIN(A) ((A##_CHAIN_POS > 0) && !HAS_L64XX)
#define IN_CHAIN(A) A##_CHAIN_POS > 0
#if IN_CHAIN(X ) || IN_CHAIN(Y ) || IN_CHAIN(Z ) || IN_CHAIN(X2) || IN_CHAIN(Y2) || IN_CHAIN(Z2) || IN_CHAIN(Z3) || IN_CHAIN(Z4) \
|| IN_CHAIN(E0) || IN_CHAIN(E1) || IN_CHAIN(E2) || IN_CHAIN(E3) || IN_CHAIN(E4) || IN_CHAIN(E5) || IN_CHAIN(E6) || IN_CHAIN(E7)
#define BAD_CHAIN(A) (IN_CHAIN(A) && !PIN_EXISTS(A##_CS))
@ -3598,13 +3615,6 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
#endif
#undef IN_CHAIN
/**
* L64XX requirement
*/
#if HAS_L64XX && NUM_AXES > 3
#error "L64XX requires NUM_AXES <= 3. Homing with L64XX is not yet implemented for NUM_AXES > 3."
#endif
/**
* Digipot requirement
*/

View File

@ -1,998 +0,0 @@
/**
* 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/>.
*
*/
/**
* The monitor_driver routines are a close copy of the TMC code
*/
#include "../../inc/MarlinConfig.h"
#if HAS_L64XX
#include "L64XX_Marlin.h"
L64XX_Marlin L64xxManager;
#include "../../module/stepper/indirection.h"
#include "../../gcode/gcode.h"
#include "../../module/planner.h"
#include "../../HAL/shared/Delay.h"
static const char NUM_AXIS_LIST(
str_X[] PROGMEM = "X ", str_Y[] PROGMEM = "Y ", str_Z[] PROGMEM = "Z ",
str_I[] PROGMEM = STR_I " ", str_J[] PROGMEM = STR_J " ", str_K[] PROGMEM = STR_K " "
),
str_X2[] PROGMEM = "X2", str_Y2[] PROGMEM = "Y2",
str_Z2[] PROGMEM = "Z2", str_Z3[] PROGMEM = "Z3", str_Z4[] PROGMEM = "Z4",
LIST_N(EXTRUDERS,
str_E0[] PROGMEM = "E0", str_E1[] PROGMEM = "E1",
str_E2[] PROGMEM = "E2", str_E3[] PROGMEM = "E3",
str_E4[] PROGMEM = "E4", str_E5[] PROGMEM = "E5",
str_E6[] PROGMEM = "E6", str_E7[] PROGMEM = "E7"
)
;
#define _EN_ITEM(N) , str_E##N
PGM_P const L64XX_Marlin::index_to_axis[] PROGMEM = {
NUM_AXIS_LIST(str_X, str_Y, str_Z, str_I, str_J, str_K),
str_X2, str_Y2, str_Z2, str_Z3, str_Z4
REPEAT(E_STEPPERS, _EN_ITEM)
};
#undef _EN_ITEM
#define DEBUG_OUT ENABLED(L6470_CHITCHAT)
#include "../../core/debug_out.h"
void echo_yes_no(const bool yes) { DEBUG_ECHOPGM_P(yes ? PSTR(" YES") : PSTR(" NO ")); UNUSED(yes); }
uint8_t L64XX_Marlin::dir_commands[MAX_L64XX]; // array to hold direction command for each driver
#define _EN_ITEM(N) , ENABLED(INVERT_E##N##_DIR)
const uint8_t L64XX_Marlin::index_to_dir[MAX_L64XX] = {
NUM_AXIS_LIST(ENABLED(INVERT_X_DIR), ENABLED(INVERT_Y_DIR), ENABLED(INVERT_Z_DIR), ENABLED(INVERT_I_DIR), ENABLED(INVERT_J_DIR), ENABLED(INVERT_K_DIR), ENABLED(INVERT_U_DIR), ENABLED(INVERT_V_DIR), ENABLED(INVERT_W_DIR))
, ENABLED(INVERT_X_DIR) ^ BOTH(HAS_DUAL_X_STEPPERS, INVERT_X2_VS_X_DIR) // X2
, ENABLED(INVERT_Y_DIR) ^ BOTH(HAS_DUAL_Y_STEPPERS, INVERT_Y2_VS_Y_DIR) // Y2
, ENABLED(INVERT_Z_DIR) ^ ENABLED(INVERT_Z2_VS_Z_DIR) // Z2
, ENABLED(INVERT_Z_DIR) ^ ENABLED(INVERT_Z3_VS_Z_DIR) // Z3
, ENABLED(INVERT_Z_DIR) ^ ENABLED(INVERT_Z4_VS_Z_DIR) // Z4
REPEAT(E_STEPPERS, _EN_ITEM)
};
#undef _EN_ITEM
volatile uint8_t L64XX_Marlin::spi_abort = false;
uint8_t L64XX_Marlin::spi_active = false;
L64XX_Marlin::L64XX_shadow_t L64XX_Marlin::shadow;
//uint32_t UVLO_ADC = 0x0400; // ADC undervoltage event
void L6470_populate_chain_array() {
#define _L6470_INIT_SPI(Q) do{ stepper##Q.set_chain_info(Q, Q##_CHAIN_POS); }while(0)
#if AXIS_IS_L64XX(X)
_L6470_INIT_SPI(X);
#endif
#if AXIS_IS_L64XX(X2)
_L6470_INIT_SPI(X2);
#endif
#if AXIS_IS_L64XX(Y)
_L6470_INIT_SPI(Y);
#endif
#if AXIS_IS_L64XX(Y2)
_L6470_INIT_SPI(Y2);
#endif
#if AXIS_IS_L64XX(Z)
_L6470_INIT_SPI(Z);
#endif
#if AXIS_IS_L64XX(Z2)
_L6470_INIT_SPI(Z2);
#endif
#if AXIS_IS_L64XX(Z3)
_L6470_INIT_SPI(Z3);
#endif
#if AXIS_IS_L64XX(Z4)
_L6470_INIT_SPI(Z4);
#endif
#if AXIS_IS_L64XX(E0)
_L6470_INIT_SPI(E0);
#endif
#if AXIS_IS_L64XX(E1)
_L6470_INIT_SPI(E1);
#endif
#if AXIS_IS_L64XX(E2)
_L6470_INIT_SPI(E2);
#endif
#if AXIS_IS_L64XX(E3)
_L6470_INIT_SPI(E3);
#endif
#if AXIS_IS_L64XX(E4)
_L6470_INIT_SPI(E4);
#endif
#if AXIS_IS_L64XX(E5)
_L6470_INIT_SPI(E5);
#endif
#if AXIS_IS_L64XX(E6)
_L6470_INIT_SPI(E6);
#endif
#if AXIS_IS_L64XX(E7)
_L6470_INIT_SPI(E7);
#endif
}
/**
* Some status bit positions & definitions differ per driver.
* Copy info to known locations to simplfy check/display logic.
* 1. Copy stepper status
* 2. Copy status bit definitions
* 3. Copy status layout
* 4. Make all error bits active low (as needed)
*/
uint16_t L64XX_Marlin::get_stepper_status(L64XX &st) {
shadow.STATUS_AXIS_RAW = st.getStatus();
shadow.STATUS_AXIS = shadow.STATUS_AXIS_RAW;
shadow.STATUS_AXIS_LAYOUT = st.L6470_status_layout;
shadow.AXIS_OCD_TH_MAX = st.OCD_TH_MAX;
shadow.AXIS_STALL_TH_MAX = st.STALL_TH_MAX;
shadow.AXIS_OCD_CURRENT_CONSTANT_INV = st.OCD_CURRENT_CONSTANT_INV;
shadow.AXIS_STALL_CURRENT_CONSTANT_INV = st.STALL_CURRENT_CONSTANT_INV;
shadow.L6470_AXIS_CONFIG = st.L64XX_CONFIG;
shadow.L6470_AXIS_STATUS = st.L64XX_STATUS;
shadow.STATUS_AXIS_OCD = st.STATUS_OCD;
shadow.STATUS_AXIS_SCK_MOD = st.STATUS_SCK_MOD;
shadow.STATUS_AXIS_STEP_LOSS_A = st.STATUS_STEP_LOSS_A;
shadow.STATUS_AXIS_STEP_LOSS_B = st.STATUS_STEP_LOSS_B;
shadow.STATUS_AXIS_TH_SD = st.STATUS_TH_SD;
shadow.STATUS_AXIS_TH_WRN = st.STATUS_TH_WRN;
shadow.STATUS_AXIS_UVLO = st.STATUS_UVLO;
shadow.STATUS_AXIS_WRONG_CMD = st.STATUS_WRONG_CMD;
shadow.STATUS_AXIS_CMD_ERR = st.STATUS_CMD_ERR;
shadow.STATUS_AXIS_NOTPERF_CMD = st.STATUS_NOTPERF_CMD;
switch (shadow.STATUS_AXIS_LAYOUT) {
case L6470_STATUS_LAYOUT: { // L6470
shadow.L6470_ERROR_MASK = shadow.STATUS_AXIS_UVLO | shadow.STATUS_AXIS_TH_WRN | shadow.STATUS_AXIS_TH_SD | shadow.STATUS_AXIS_OCD | shadow.STATUS_AXIS_STEP_LOSS_A | shadow.STATUS_AXIS_STEP_LOSS_B;
shadow.STATUS_AXIS ^= (shadow.STATUS_AXIS_WRONG_CMD | shadow.STATUS_AXIS_NOTPERF_CMD); // invert just error bits that are active high
break;
}
case L6474_STATUS_LAYOUT: { // L6474
shadow.L6470_ERROR_MASK = shadow.STATUS_AXIS_UVLO | shadow.STATUS_AXIS_TH_WRN | shadow.STATUS_AXIS_TH_SD | shadow.STATUS_AXIS_OCD ;
shadow.STATUS_AXIS ^= (shadow.STATUS_AXIS_WRONG_CMD | shadow.STATUS_AXIS_NOTPERF_CMD); // invert just error bits that are active high
break;
}
case L6480_STATUS_LAYOUT: { // L6480 & powerSTEP01
shadow.L6470_ERROR_MASK = shadow.STATUS_AXIS_UVLO | shadow.STATUS_AXIS_TH_WRN | shadow.STATUS_AXIS_TH_SD | shadow.STATUS_AXIS_OCD | shadow.STATUS_AXIS_STEP_LOSS_A | shadow.STATUS_AXIS_STEP_LOSS_B;
shadow.STATUS_AXIS ^= (shadow.STATUS_AXIS_CMD_ERR | shadow.STATUS_AXIS_TH_WRN | shadow.STATUS_AXIS_TH_SD); // invert just error bits that are active high
break;
}
}
return shadow.STATUS_AXIS;
}
void L64XX_Marlin::init() { // Set up SPI and then init chips
ENABLE_RESET_L64XX_CHIPS(LOW); // hardware reset of drivers
DELAY_US(100);
ENABLE_RESET_L64XX_CHIPS(HIGH);
DELAY_US(1000); // need about 650µs for the chip(s) to fully start up
L6470_populate_chain_array(); // Set up array to control where in the SPI transfer sequence a particular stepper's data goes
spi_init(); // Since L64XX SPI pins are unset we must init SPI here
init_to_defaults(); // init the chips
}
uint16_t L64XX_Marlin::get_status(const L64XX_axis_t axis) {
#define STATUS_L6470(Q) get_stepper_status(stepper##Q)
switch (axis) {
default: break;
#if AXIS_IS_L64XX(X)
case X : return STATUS_L6470(X);
#endif
#if AXIS_IS_L64XX(Y)
case Y : return STATUS_L6470(Y);
#endif
#if AXIS_IS_L64XX(Z)
case Z : return STATUS_L6470(Z);
#endif
#if AXIS_IS_L64XX(X2)
case X2: return STATUS_L6470(X2);
#endif
#if AXIS_IS_L64XX(Y2)
case Y2: return STATUS_L6470(Y2);
#endif
#if AXIS_IS_L64XX(Z2)
case Z2: return STATUS_L6470(Z2);
#endif
#if AXIS_IS_L64XX(Z3)
case Z3: return STATUS_L6470(Z3);
#endif
#if AXIS_IS_L64XX(Z4)
case Z4: return STATUS_L6470(Z4);
#endif
#if AXIS_IS_L64XX(E0)
case E0: return STATUS_L6470(E0);
#endif
#if AXIS_IS_L64XX(E1)
case E1: return STATUS_L6470(E1);
#endif
#if AXIS_IS_L64XX(E2)
case E2: return STATUS_L6470(E2);
#endif
#if AXIS_IS_L64XX(E3)
case E3: return STATUS_L6470(E3);
#endif
#if AXIS_IS_L64XX(E4)
case E4: return STATUS_L6470(E4);
#endif
#if AXIS_IS_L64XX(E5)
case E5: return STATUS_L6470(E5);
#endif
#if AXIS_IS_L64XX(E6)
case E6: return STATUS_L6470(E6);
#endif
#if AXIS_IS_L64XX(E7)
case E7: return STATUS_L6470(E7);
#endif
}
return 0; // Not needed but kills a compiler warning
}
uint32_t L64XX_Marlin::get_param(const L64XX_axis_t axis, const uint8_t param) {
#define GET_L6470_PARAM(Q) L6470_GETPARAM(param, Q)
switch (axis) {
default: break;
#if AXIS_IS_L64XX(X)
case X : return GET_L6470_PARAM(X);
#endif
#if AXIS_IS_L64XX(Y)
case Y : return GET_L6470_PARAM(Y);
#endif
#if AXIS_IS_L64XX(Z)
case Z : return GET_L6470_PARAM(Z);
#endif
#if AXIS_IS_L64XX(X2)
case X2: return GET_L6470_PARAM(X2);
#endif
#if AXIS_IS_L64XX(Y2)
case Y2: return GET_L6470_PARAM(Y2);
#endif
#if AXIS_IS_L64XX(Z2)
case Z2: return GET_L6470_PARAM(Z2);
#endif
#if AXIS_IS_L64XX(Z3)
case Z3: return GET_L6470_PARAM(Z3);
#endif
#if AXIS_IS_L64XX(Z4)
case Z4: return GET_L6470_PARAM(Z4);
#endif
#if AXIS_IS_L64XX(E0)
case E0: return GET_L6470_PARAM(E0);
#endif
#if AXIS_IS_L64XX(E1)
case E1: return GET_L6470_PARAM(E1);
#endif
#if AXIS_IS_L64XX(E2)
case E2: return GET_L6470_PARAM(E2);
#endif
#if AXIS_IS_L64XX(E3)
case E3: return GET_L6470_PARAM(E3);
#endif
#if AXIS_IS_L64XX(E4)
case E4: return GET_L6470_PARAM(E4);
#endif
#if AXIS_IS_L64XX(E5)
case E5: return GET_L6470_PARAM(E5);
#endif
#if AXIS_IS_L64XX(E6)
case E6: return GET_L6470_PARAM(E6);
#endif
#if AXIS_IS_L64XX(E7)
case E7: return GET_L6470_PARAM(E7);
#endif
}
return 0; // not needed but kills a compiler warning
}
void L64XX_Marlin::set_param(const L64XX_axis_t axis, const uint8_t param, const uint32_t value) {
#define SET_L6470_PARAM(Q) stepper##Q.SetParam(param, value)
switch (axis) {
default: break;
#if AXIS_IS_L64XX(X)
case X : SET_L6470_PARAM(X); break;
#endif
#if AXIS_IS_L64XX(Y)
case Y : SET_L6470_PARAM(Y); break;
#endif
#if AXIS_IS_L64XX(Z)
case Z : SET_L6470_PARAM(Z); break;
#endif
#if AXIS_IS_L64XX(I)
case I : SET_L6470_PARAM(I); break;
#endif
#if AXIS_IS_L64XX(J)
case J : SET_L6470_PARAM(J); break;
#endif
#if AXIS_IS_L64XX(K)
case K : SET_L6470_PARAM(K); break;
#endif
#if AXIS_IS_L64XX(X2)
case X2: SET_L6470_PARAM(X2); break;
#endif
#if AXIS_IS_L64XX(Y2)
case Y2: SET_L6470_PARAM(Y2); break;
#endif
#if AXIS_IS_L64XX(Z2)
case Z2: SET_L6470_PARAM(Z2); break;
#endif
#if AXIS_IS_L64XX(Z3)
case Z3: SET_L6470_PARAM(Z3); break;
#endif
#if AXIS_IS_L64XX(Z4)
case Z4: SET_L6470_PARAM(Z4); break;
#endif
#if AXIS_IS_L64XX(E0)
case E0: SET_L6470_PARAM(E0); break;
#endif
#if AXIS_IS_L64XX(E1)
case E1: SET_L6470_PARAM(E1); break;
#endif
#if AXIS_IS_L64XX(E2)
case E2: SET_L6470_PARAM(E2); break;
#endif
#if AXIS_IS_L64XX(E3)
case E3: SET_L6470_PARAM(E3); break;
#endif
#if AXIS_IS_L64XX(E4)
case E4: SET_L6470_PARAM(E4); break;
#endif
#if AXIS_IS_L64XX(E5)
case E5: SET_L6470_PARAM(E5); break;
#endif
#if AXIS_IS_L64XX(E6)
case E6: SET_L6470_PARAM(E6); break;
#endif
#if AXIS_IS_L64XX(E7)
case E7: SET_L6470_PARAM(E7); break;
#endif
}
}
inline void echo_min_max(const char a, const_float_t min, const_float_t max) {
DEBUG_CHAR(' '); DEBUG_CHAR(a);
DEBUG_ECHOLNPGM(" min = ", min, " max = ", max);
}
inline void echo_oct_used(const_float_t oct, const uint8_t stall) {
DEBUG_ECHOPGM("over_current_threshold used : ", oct);
DEBUG_ECHOPGM_P(stall ? PSTR(" (Stall") : PSTR(" (OCD"));
DEBUG_ECHOLNPGM(" threshold)");
}
inline void err_out_of_bounds() { DEBUG_ECHOLNPGM("Test aborted - motion out of bounds"); }
uint8_t L64XX_Marlin::get_user_input(uint8_t &driver_count, L64XX_axis_t axis_index[3], char axis_mon[3][3],
float &position_max, float &position_min, float &final_feedrate, uint8_t &kval_hold,
uint8_t over_current_flag, uint8_t &OCD_TH_val, uint8_t &STALL_TH_val, uint16_t &over_current_threshold
) {
// Return TRUE if the calling routine needs to abort/kill
uint16_t displacement = 0; // " = 0" to eliminate compiler warning
uint8_t j; // general purpose counter
if (!all_axes_homed()) {
DEBUG_ECHOLNPGM("Test aborted - home all before running this command");
return true;
}
uint8_t found_displacement = false;
LOOP_LOGICAL_AXES(i) if (uint16_t _displacement = parser.intval(AXIS_CHAR(i))) {
found_displacement = true;
displacement = _displacement;
const uint8_t axis_offset = parser.byteval('J');
axis_mon[0][0] = AXIS_CHAR(i); // Axis first character, one of XYZ...E
const bool single_or_e = axis_offset >= 2 || axis_mon[0][0] == 'E',
one_or_more = !single_or_e && axis_offset == 0;
uint8_t driver_count_local = 0; // Can't use "driver_count" directly as a subscript because it's passed by reference
if (single_or_e) // Single axis, E0, or E1
axis_mon[0][1] = axis_offset + '0'; // Index given by 'J' parameter
if (single_or_e || one_or_more) {
for (j = 0; j < MAX_L64XX; j++) { // Count up the drivers on this axis
PGM_P str = (PGM_P)pgm_read_ptr(&index_to_axis[j]); // Get a PGM_P from progmem
const char c = pgm_read_byte(str); // Get a char from progmem
if (axis_mon[0][0] == c) { // For each stepper on this axis...
char *mon = axis_mon[driver_count_local];
*mon++ = c; // Copy the 3 letter axis name
*mon++ = pgm_read_byte(&str[1]); // to the axis_mon array
*mon = pgm_read_byte(&str[2]);
axis_index[driver_count_local] = (L64XX_axis_t)j; // And store the L64XX axis index
driver_count_local++;
}
}
if (one_or_more) driver_count = driver_count_local;
}
break; // only take first axis found
}
if (!found_displacement) {
DEBUG_ECHOLNPGM("Test aborted - AXIS with displacement is required");
return true;
}
//
// Position calcs & checks
//
const float LOGICAL_AXIS_LIST(
E_center = current_position.e,
X_center = LOGICAL_X_POSITION(current_position.x),
Y_center = LOGICAL_Y_POSITION(current_position.y),
Z_center = LOGICAL_Z_POSITION(current_position.z),
I_center = LOGICAL_I_POSITION(current_position.i),
J_center = LOGICAL_J_POSITION(current_position.j),
K_center = LOGICAL_K_POSITION(current_position.k)
);
switch (axis_mon[0][0]) {
default: position_max = position_min = 0; break;
case 'X': {
position_min = X_center - displacement;
position_max = X_center + displacement;
echo_min_max('X', position_min, position_max);
if (TERN0(HAS_ENDSTOPS, position_min < (X_MIN_POS) || position_max > (X_MAX_POS))) {
err_out_of_bounds();
return true;
}
} break;
#if HAS_Y_AXIS
case 'Y': {
position_min = Y_center - displacement;
position_max = Y_center + displacement;
echo_min_max('Y', position_min, position_max);
if (TERN0(HAS_ENDSTOPS, position_min < (Y_MIN_POS) || position_max > (Y_MAX_POS))) {
err_out_of_bounds();
return true;
}
} break;
#endif
#if HAS_Z_AXIS
case 'Z': {
position_min = Z_center - displacement;
position_max = Z_center + displacement;
echo_min_max('Z', position_min, position_max);
if (TERN0(HAS_ENDSTOPS, position_min < (Z_MIN_POS) || position_max > (Z_MAX_POS))) {
err_out_of_bounds();
return true;
}
} break;
#endif
#if HAS_I_AXIS
case AXIS4_NAME: {
position_min = I_center - displacement;
position_max = I_center + displacement;
echo_min_max(AXIS4_NAME, position_min, position_max);
if (TERN0(HAS_ENDSTOPS, position_min < (I_MIN_POS) || position_max > (I_MAX_POS))) {
err_out_of_bounds();
return true;
}
} break;
#endif
#if HAS_J_AXIS
case AXIS5_NAME: {
position_min = J_center - displacement;
position_max = J_center + displacement;
echo_min_max(AXIS5_NAME, position_min, position_max);
if (TERN1(HAS_ENDSTOPS, position_min < (J_MIN_POS) || position_max > (J_MAX_POS))) {
err_out_of_bounds();
return true;
}
} break;
#endif
#if HAS_K_AXIS
case AXIS6_NAME: {
position_min = K_center - displacement;
position_max = K_center + displacement;
echo_min_max(AXIS6_NAME, position_min, position_max);
if (TERN2(HAS_ENDSTOPS, position_min < (K_MIN_POS) || position_max > (K_MAX_POS))) {
err_out_of_bounds();
return true;
}
} break;
#endif
#if HAS_EXTRUDERS
case 'E': {
position_min = E_center - displacement;
position_max = E_center + displacement;
echo_min_max('E', position_min, position_max);
} break;
#endif
}
//
// Work on the drivers
//
LOOP_L_N(k, driver_count) {
uint8_t not_found = true;
for (j = 1; j <= L64XX::chain[0]; j++) {
PGM_P const str = (PGM_P)pgm_read_ptr(&index_to_axis[L64XX::chain[j]]);
if (pgm_read_byte(&str[0]) == axis_mon[k][0] && pgm_read_byte(&str[1]) == axis_mon[k][1]) { // See if a L6470 driver
not_found = false;
break;
}
}
if (not_found) {
driver_count = k;
axis_mon[k][0] = ' '; // mark this entry invalid
break;
}
}
if (driver_count == 0) {
DEBUG_ECHOLNPGM("Test aborted - not a L6470 axis");
return true;
}
DEBUG_ECHOPGM("Monitoring:");
for (j = 0; j < driver_count; j++) DEBUG_ECHOPGM(" ", axis_mon[j]);
DEBUG_EOL();
// now have a list of driver(s) to monitor
//
// TVAL & kVAL_HOLD checks & settings
//
const L64XX_shadow_t &sh = shadow;
get_status(axis_index[0]); // populate shadow array
if (sh.STATUS_AXIS_LAYOUT == L6474_STATUS_LAYOUT) { // L6474 - use TVAL
uint16_t TVAL_current = parser.ushortval('T');
if (TVAL_current) {
uint8_t TVAL_count = (TVAL_current / sh.AXIS_STALL_CURRENT_CONSTANT_INV) - 1;
LIMIT(TVAL_count, 0, sh.AXIS_STALL_TH_MAX);
for (j = 0; j < driver_count; j++)
set_param(axis_index[j], L6474_TVAL, TVAL_count);
}
// only print the tval from one of the drivers
kval_hold = get_param(axis_index[0], L6474_TVAL);
DEBUG_ECHOLNPGM("TVAL current (mA) = ", (kval_hold + 1) * sh.AXIS_STALL_CURRENT_CONSTANT_INV);
}
else {
kval_hold = parser.byteval('K');
if (kval_hold) {
DEBUG_ECHOLNPGM("kval_hold = ", kval_hold);
for (j = 0; j < driver_count; j++)
set_param(axis_index[j], L6470_KVAL_HOLD, kval_hold);
}
else {
// only print the KVAL_HOLD from one of the drivers
kval_hold = get_param(axis_index[0], L6470_KVAL_HOLD);
DEBUG_ECHOLNPGM("KVAL_HOLD = ", kval_hold);
}
}
//
// Overcurrent checks & settings
//
if (over_current_flag) {
uint8_t OCD_TH_val_local = 0, // compiler thinks OCD_TH_val is unused if use it directly
STALL_TH_val_local = 0; // just in case ...
over_current_threshold = parser.intval('I');
if (over_current_threshold) {
OCD_TH_val_local = over_current_threshold/375;
LIMIT(OCD_TH_val_local, 0, 15);
STALL_TH_val_local = over_current_threshold/31.25;
LIMIT(STALL_TH_val_local, 0, 127);
uint16_t OCD_TH_actual = (OCD_TH_val_local + 1) * 375,
STALL_TH_actual = (STALL_TH_val_local + 1) * 31.25;
if (OCD_TH_actual < STALL_TH_actual) {
OCD_TH_val_local++;
OCD_TH_actual = (OCD_TH_val_local + 1) * 375;
}
DEBUG_ECHOLNPGM("over_current_threshold specified: ", over_current_threshold);
if (!(sh.STATUS_AXIS_LAYOUT == L6474_STATUS_LAYOUT)) echo_oct_used((STALL_TH_val_local + 1) * 31.25, true);
echo_oct_used((OCD_TH_val_local + 1) * 375, false);
#define SET_OVER_CURRENT(Q) do { stepper##Q.SetParam(L6470_STALL_TH, STALL_TH_val_local); stepper##Q.SetParam(L6470_OCD_TH, OCD_TH_val_local);} while (0)
for (j = 0; j < driver_count; j++) {
set_param(axis_index[j], L6470_STALL_TH, STALL_TH_val_local);
set_param(axis_index[j], L6470_OCD_TH, OCD_TH_val_local);
}
}
else {
// only get & print the OVER_CURRENT values from one of the drivers
STALL_TH_val_local = get_param(axis_index[0], L6470_STALL_TH);
OCD_TH_val_local = get_param(axis_index[0], L6470_OCD_TH);
if (!(sh.STATUS_AXIS_LAYOUT == L6474_STATUS_LAYOUT)) echo_oct_used((STALL_TH_val_local + 1) * 31.25, true);
echo_oct_used((OCD_TH_val_local + 1) * 375, false);
} // over_current_threshold
for (j = 0; j < driver_count; j++) { // set all drivers on axis the same
set_param(axis_index[j], L6470_STALL_TH, STALL_TH_val_local);
set_param(axis_index[j], L6470_OCD_TH, OCD_TH_val_local);
}
OCD_TH_val = OCD_TH_val_local; // force compiler to update the main routine's copy
STALL_TH_val = STALL_TH_val_local; // force compiler to update the main routine's copy
} // end of overcurrent
//
// Feedrate
//
final_feedrate = parser.floatval('F');
if (final_feedrate == 0) {
static constexpr float default_max_feedrate[] = DEFAULT_MAX_FEEDRATE;
const uint8_t num_feedrates = COUNT(default_max_feedrate);
for (j = 0; j < num_feedrates; j++) {
if (AXIS_CHAR(j) == axis_mon[0][0]) {
final_feedrate = default_max_feedrate[j];
break;
}
}
if (j == 3 && num_feedrates > 4) { // have more than one extruder feedrate
uint8_t extruder_num = axis_mon[0][1] - '0';
if (j <= num_feedrates - extruder_num) // have a feedrate specifically for this extruder
final_feedrate = default_max_feedrate[j + extruder_num];
else
final_feedrate = default_max_feedrate[3]; // use E0 feedrate for this extruder
}
final_feedrate *= 60; // convert to mm/minute
} // end of feedrate
return false; // FALSE indicates no user input problems
}
void L64XX_Marlin::say_axis(const L64XX_axis_t axis, const uint8_t label/*=true*/) {
if (label) SERIAL_ECHOPGM("AXIS:");
const char * const str = L64xxManager.index_to_axis[axis];
SERIAL_CHAR(' ', str[0], str[1], ' ');
}
#if ENABLED(L6470_CHITCHAT)
// Assumes status bits have been inverted
void L64XX_Marlin::error_status_decode(const uint16_t status, const L64XX_axis_t axis,
const uint16_t _status_axis_th_sd, const uint16_t _status_axis_th_wrn,
const uint16_t _status_axis_step_loss_a, const uint16_t _status_axis_step_loss_b,
const uint16_t _status_axis_ocd, const uint8_t _status_axis_layout
) {
say_axis(axis);
DEBUG_ECHOPGM(" THERMAL: ");
DEBUG_ECHOPGM_P((status & _status_axis_th_sd) ? PSTR("SHUTDOWN") : (status & _status_axis_th_wrn) ? PSTR("WARNING ") : PSTR("OK "));
DEBUG_ECHOPGM(" OVERCURRENT: ");
echo_yes_no((status & _status_axis_ocd) != 0);
if (!(_status_axis_layout == L6474_STATUS_LAYOUT)) { // L6474 doesn't have these bits
DEBUG_ECHOPGM(" STALL: ");
echo_yes_no((status & (_status_axis_step_loss_a | _status_axis_step_loss_b)) != 0);
}
DEBUG_EOL();
}
#endif
//////////////////////////////////////////////////////////////////////////////////////////////////
////
//// MONITOR_L6470_DRIVER_STATUS routines
////
//////////////////////////////////////////////////////////////////////////////////////////////////
#if ENABLED(MONITOR_L6470_DRIVER_STATUS)
bool L64XX_Marlin::monitor_paused = false; // Flag to skip monitor during M122, M906, M916, M917, M918, etc.
struct L6470_driver_data {
L64XX_axis_t driver_index;
uint32_t driver_status;
uint8_t is_otw;
uint8_t otw_counter;
uint8_t is_ot;
uint8_t is_hi_Z;
uint8_t com_counter;
};
L6470_driver_data driver_L6470_data[] = {
#if AXIS_IS_L64XX(X)
{ X, 0, 0, 0, 0, 0, 0 },
#endif
#if AXIS_IS_L64XX(Y)
{ Y, 0, 0, 0, 0, 0, 0 },
#endif
#if AXIS_IS_L64XX(Z)
{ Z, 0, 0, 0, 0, 0, 0 },
#endif
#if AXIS_IS_L64XX(I)
{ I, 0, 0, 0, 0, 0, 0 },
#endif
#if AXIS_IS_L64XX(J)
{ J, 0, 0, 0, 0, 0, 0 },
#endif
#if AXIS_IS_L64XX(K)
{ K, 0, 0, 0, 0, 0, 0 },
#endif
#if AXIS_IS_L64XX(X2)
{ X2, 0, 0, 0, 0, 0, 0 },
#endif
#if AXIS_IS_L64XX(Y2)
{ Y2, 0, 0, 0, 0, 0, 0 },
#endif
#if AXIS_IS_L64XX(Z2)
{ Z2, 0, 0, 0, 0, 0, 0 },
#endif
#if AXIS_IS_L64XX(Z3)
{ Z3, 0, 0, 0, 0, 0, 0 },
#endif
#if AXIS_IS_L64XX(Z4)
{ Z4, 0, 0, 0, 0, 0, 0 },
#endif
#if AXIS_IS_L64XX(E0)
{ E0, 0, 0, 0, 0, 0, 0 },
#endif
#if AXIS_IS_L64XX(E1)
{ E1, 0, 0, 0, 0, 0, 0 },
#endif
#if AXIS_IS_L64XX(E2)
{ E2, 0, 0, 0, 0, 0, 0 },
#endif
#if AXIS_IS_L64XX(E3)
{ E3, 0, 0, 0, 0, 0, 0 },
#endif
#if AXIS_IS_L64XX(E4)
{ E4, 0, 0, 0, 0, 0, 0 },
#endif
#if AXIS_IS_L64XX(E5)
{ E5, 0, 0, 0, 0, 0, 0 }
#endif
#if AXIS_IS_L64XX(E6)
{ E6, 0, 0, 0, 0, 0, 0 }
#endif
#if AXIS_IS_L64XX(E7)
{ E7, 0, 0, 0, 0, 0, 0 }
#endif
};
void L64XX_Marlin::append_stepper_err(char* &p, const uint8_t stepper_index, const char * const err/*=nullptr*/) {
PGM_P const str = (PGM_P)pgm_read_ptr(&index_to_axis[stepper_index]);
p += sprintf_P(p, PSTR("Stepper %c%c "), pgm_read_byte(&str[0]), pgm_read_byte(&str[1]));
if (err) p += sprintf_P(p, err);
}
void L64XX_Marlin::monitor_update(L64XX_axis_t stepper_index) {
if (spi_abort) return; // don't do anything if set_directions() has occurred
const L64XX_shadow_t &sh = shadow;
get_status(stepper_index); // get stepper status and details
uint16_t status = sh.STATUS_AXIS;
uint8_t kval_hold, tval;
char temp_buf[120], *p = temp_buf;
uint8_t j;
for (j = 0; j < L64XX::chain[0]; j++) // find the table for this stepper
if (driver_L6470_data[j].driver_index == stepper_index) break;
driver_L6470_data[j].driver_status = status;
uint16_t _status = ~status; // all error bits are active low
if (status == 0 || status == 0xFFFF) { // com problem
if (driver_L6470_data[j].com_counter == 0) { // warn user when it first happens
driver_L6470_data[j].com_counter++;
append_stepper_err(p, stepper_index, PSTR(" - communications lost\n"));
DEBUG_ECHO(temp_buf);
}
else {
driver_L6470_data[j].com_counter++;
if (driver_L6470_data[j].com_counter > 240) { // remind of com problem about every 2 minutes
driver_L6470_data[j].com_counter = 1;
append_stepper_err(p, stepper_index, PSTR(" - still no communications\n"));
DEBUG_ECHO(temp_buf);
}
}
}
else {
if (driver_L6470_data[j].com_counter) { // comms re-established
driver_L6470_data[j].com_counter = 0;
append_stepper_err(p, stepper_index, PSTR(" - communications re-established\n.. setting all drivers to default values\n"));
DEBUG_ECHO(temp_buf);
init_to_defaults();
}
else {
// no com problems - do the usual checks
if (_status & sh.L6470_ERROR_MASK) {
append_stepper_err(p, stepper_index);
if (status & STATUS_HIZ) { // The driver has shut down. HiZ is active high
driver_L6470_data[j].is_hi_Z = true;
p += sprintf_P(p, PSTR("%cIS SHUT DOWN"), ' ');
//if (_status & sh.STATUS_AXIS_TH_SD) { // strange - TH_SD never seems to go active, must be implied by the HiZ and TH_WRN
if (_status & sh.STATUS_AXIS_TH_WRN) { // over current shutdown
p += sprintf_P(p, PSTR("%cdue to over temperature"), ' ');
driver_L6470_data[j].is_ot = true;
if (sh.STATUS_AXIS_LAYOUT == L6474_STATUS_LAYOUT) { // L6474
tval = get_param(stepper_index, L6474_TVAL) - 2 * KVAL_HOLD_STEP_DOWN;
set_param(stepper_index, L6474_TVAL, tval); // reduce TVAL
p += sprintf_P(p, PSTR(" - TVAL reduced by %d to %d mA"), uint16_t (2 * KVAL_HOLD_STEP_DOWN * sh.AXIS_STALL_CURRENT_CONSTANT_INV), uint16_t ((tval + 1) * sh.AXIS_STALL_CURRENT_CONSTANT_INV)); // let user know
}
else {
kval_hold = get_param(stepper_index, L6470_KVAL_HOLD) - 2 * KVAL_HOLD_STEP_DOWN;
set_param(stepper_index, L6470_KVAL_HOLD, kval_hold); // reduce KVAL_HOLD
p += sprintf_P(p, PSTR(" - KVAL_HOLD reduced by %d to %d"), 2 * KVAL_HOLD_STEP_DOWN, kval_hold); // let user know
}
}
else
driver_L6470_data[j].is_ot = false;
}
else {
driver_L6470_data[j].is_hi_Z = false;
if (_status & sh.STATUS_AXIS_TH_WRN) { // have an over temperature warning
driver_L6470_data[j].is_otw = true;
driver_L6470_data[j].otw_counter++;
kval_hold = get_param(stepper_index, L6470_KVAL_HOLD);
if (driver_L6470_data[j].otw_counter > 4) { // otw present for 2 - 2.5 seconds, reduce KVAL_HOLD
driver_L6470_data[j].otw_counter = 0;
driver_L6470_data[j].is_otw = true;
if (sh.STATUS_AXIS_LAYOUT == L6474_STATUS_LAYOUT) { // L6474
tval = get_param(stepper_index, L6474_TVAL) - KVAL_HOLD_STEP_DOWN;
set_param(stepper_index, L6474_TVAL, tval); // reduce TVAL
p += sprintf_P(p, PSTR(" - TVAL reduced by %d to %d mA"), uint16_t (KVAL_HOLD_STEP_DOWN * sh.AXIS_STALL_CURRENT_CONSTANT_INV), uint16_t ((tval + 1) * sh.AXIS_STALL_CURRENT_CONSTANT_INV)); // let user know
}
else {
kval_hold = get_param(stepper_index, L6470_KVAL_HOLD) - KVAL_HOLD_STEP_DOWN;
set_param(stepper_index, L6470_KVAL_HOLD, kval_hold); // reduce KVAL_HOLD
p += sprintf_P(p, PSTR(" - KVAL_HOLD reduced by %d to %d"), KVAL_HOLD_STEP_DOWN, kval_hold); // let user know
}
}
else if (driver_L6470_data[j].otw_counter)
p += sprintf_P(p, PSTR("%c- thermal warning"), ' '); // warn user
}
}
#if ENABLED(L6470_STOP_ON_ERROR)
if (_status & (sh.STATUS_AXIS_UVLO | sh.STATUS_AXIS_TH_WRN | sh.STATUS_AXIS_TH_SD))
kill(temp_buf);
#endif
#if ENABLED(L6470_CHITCHAT)
if (_status & sh.STATUS_AXIS_OCD)
p += sprintf_P(p, PSTR("%c over current"), ' ');
if (_status & (sh.STATUS_AXIS_STEP_LOSS_A | sh.STATUS_AXIS_STEP_LOSS_B))
p += sprintf_P(p, PSTR("%c stall"), ' ');
if (_status & sh.STATUS_AXIS_UVLO)
p += sprintf_P(p, PSTR("%c under voltage lock out"), ' ');
p += sprintf_P(p, PSTR("%c\n"), ' ');
#endif
DEBUG_ECHOLN(temp_buf); // print the error message
}
else {
driver_L6470_data[j].is_ot = false;
driver_L6470_data[j].otw_counter = 0; //clear out warning indicators
driver_L6470_data[j].is_otw = false;
} // end usual checks
} // comms established but have errors
} // comms re-established
} // end monitor_update()
void L64XX_Marlin::monitor_driver() {
static millis_t next_cOT = 0;
if (ELAPSED(millis(), next_cOT)) {
next_cOT = millis() + 500;
if (!monitor_paused) { // Skip during M122, M906, M916, M917 or M918 (could steal status result from test)
spi_active = true; // Tell set_directions() a series of SPI transfers is underway
#if AXIS_IS_L64XX(X)
monitor_update(X);
#endif
#if AXIS_IS_L64XX(Y)
monitor_update(Y);
#endif
#if AXIS_IS_L64XX(Z)
monitor_update(Z);
#endif
#if AXIS_IS_L64XX(I)
monitor_update(I);
#endif
#if AXIS_IS_L64XX(J)
monitor_update(J);
#endif
#if AXIS_IS_L64XX(K)
monitor_update(K);
#endif
#if AXIS_IS_L64XX(X2)
monitor_update(X2);
#endif
#if AXIS_IS_L64XX(Y2)
monitor_update(Y2);
#endif
#if AXIS_IS_L64XX(Z2)
monitor_update(Z2);
#endif
#if AXIS_IS_L64XX(Z3)
monitor_update(Z3);
#endif
#if AXIS_IS_L64XX(Z4)
monitor_update(Z4);
#endif
#if AXIS_IS_L64XX(E0)
monitor_update(E0);
#endif
#if AXIS_IS_L64XX(E1)
monitor_update(E1);
#endif
#if AXIS_IS_L64XX(E2)
monitor_update(E2);
#endif
#if AXIS_IS_L64XX(E3)
monitor_update(E3);
#endif
#if AXIS_IS_L64XX(E4)
monitor_update(E4);
#endif
#if AXIS_IS_L64XX(E5)
monitor_update(E5);
#endif
#if AXIS_IS_L64XX(E6)
monitor_update(E6);
#endif
#if AXIS_IS_L64XX(E7)
monitor_update(E7);
#endif
if (TERN0(L6470_DEBUG, report_L6470_status)) DEBUG_EOL();
spi_active = false; // done with all SPI transfers - clear handshake flags
spi_abort = false;
}
}
}
#endif // MONITOR_L6470_DRIVER_STATUS
#endif // HAS_L64XX

View File

@ -1,141 +0,0 @@
/**
* 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 <L6470.h>
#if !(L6470_LIBRARY_VERSION >= 0x000800)
#error 'L6470_LIBRARY_VERSION 0x000800 or later required'
#endif
#define L6470_GETPARAM(P,Q) stepper##Q.GetParam(P)
#define dSPIN_STEP_CLOCK 0x58
#define dSPIN_STEP_CLOCK_FWD dSPIN_STEP_CLOCK
#define dSPIN_STEP_CLOCK_REV dSPIN_STEP_CLOCK+1
#define HAS_L64XX_EXTRUDER (AXIS_IS_L64XX(E0) || AXIS_IS_L64XX(E1) || AXIS_IS_L64XX(E2) || AXIS_IS_L64XX(E3) || AXIS_IS_L64XX(E4) || AXIS_IS_L64XX(E5) || AXIS_IS_L64XX(E6) || AXIS_IS_L64XX(E7))
#define _EN_ITEM(N) , E##N
enum L64XX_axis_t : uint8_t { MAIN_AXIS_NAMES, X2, Y2, Z2, Z3, Z4 REPEAT(E_STEPPERS, _EN_ITEM), MAX_L64XX };
#undef _EN_ITEM
class L64XX_Marlin : public L64XXHelper {
public:
static PGM_P const index_to_axis[MAX_L64XX];
static const uint8_t index_to_dir[MAX_L64XX];
static uint8_t dir_commands[MAX_L64XX];
// Flags to guarantee graceful switch if stepper interrupts L6470 SPI transfer
static volatile uint8_t spi_abort;
static uint8_t spi_active;
L64XX_Marlin() {}
static void init();
static void init_to_defaults();
static uint16_t get_stepper_status(L64XX &st);
static uint16_t get_status(const L64XX_axis_t axis);
static uint32_t get_param(const L64XX_axis_t axis, const uint8_t param);
static void set_param(const L64XX_axis_t axis, const uint8_t param, const uint32_t value);
//static void send_command(const L64XX_axis_t axis, uint8_t command);
static uint8_t get_user_input(uint8_t &driver_count, L64XX_axis_t axis_index[3], char axis_mon[3][3],
float &position_max, float &position_min, float &final_feedrate, uint8_t &kval_hold,
uint8_t over_current_flag, uint8_t &OCD_TH_val, uint8_t &STALL_TH_val, uint16_t &over_current_threshold);
static void transfer(uint8_t L6470_buf[], const uint8_t length);
static void say_axis(const L64XX_axis_t axis, const uint8_t label=true);
#if ENABLED(L6470_CHITCHAT)
static void error_status_decode(
const uint16_t status, const L64XX_axis_t axis,
const uint16_t _status_axis_th_sd, const uint16_t _status_axis_th_wrn,
const uint16_t _status_axis_step_loss_a, const uint16_t _status_axis_step_loss_b,
const uint16_t _status_axis_ocd, const uint8_t _status_axis_layout
);
#else
FORCE_INLINE static void error_status_decode(
const uint16_t, const L64XX_axis_t,
const uint16_t, const uint16_t,
const uint16_t, const uint16_t,
const uint16_t, const uint8_t
){}
#endif
// ~40 bytes SRAM to simplify status decode routines
typedef struct {
uint8_t STATUS_AXIS_LAYOUT; // Copy of L6470_status_layout
uint8_t AXIS_OCD_TH_MAX; // Size of OCD_TH field
uint8_t AXIS_STALL_TH_MAX; // Size of STALL_TH field
float AXIS_OCD_CURRENT_CONSTANT_INV; // mA per count
float AXIS_STALL_CURRENT_CONSTANT_INV; // mA per count
uint8_t L6470_AXIS_CONFIG, // Address of the CONFIG register
L6470_AXIS_STATUS; // Address of the STATUS register
uint16_t L6470_ERROR_MASK, // STATUS_UVLO | STATUS_TH_WRN | STATUS_TH_SD | STATUS_OCD | STATUS_STEP_LOSS_A | STATUS_STEP_LOSS_B
L6474_ERROR_MASK, // STATUS_UVLO | STATUS_TH_WRN | STATUS_TH_SD | STATUS_OCD
STATUS_AXIS_RAW, // Copy of status register contents
STATUS_AXIS, // Copy of status register contents but with all error bits active low
STATUS_AXIS_OCD, // Overcurrent detected bit position
STATUS_AXIS_SCK_MOD, // Step clock mode is active bit position
STATUS_AXIS_STEP_LOSS_A, // Stall detected on A bridge bit position
STATUS_AXIS_STEP_LOSS_B, // Stall detected on B bridge bit position
STATUS_AXIS_TH_SD, // Thermal shutdown bit position
STATUS_AXIS_TH_WRN, // Thermal warning bit position
STATUS_AXIS_UVLO, // Undervoltage lockout is active bit position
STATUS_AXIS_WRONG_CMD, // Last command not valid bit position
STATUS_AXIS_CMD_ERR, // Command error bit position
STATUS_AXIS_NOTPERF_CMD; // Last command not performed bit position
} L64XX_shadow_t;
static L64XX_shadow_t shadow;
#if ENABLED(MONITOR_L6470_DRIVER_STATUS)
static bool monitor_paused;
static void pause_monitor(const bool p) { monitor_paused = p; }
static void monitor_update(L64XX_axis_t stepper_index);
static void monitor_driver();
#else
static void pause_monitor(const bool) {}
#endif
//protected:
// L64XXHelper methods
static void spi_init();
static uint8_t transfer_single(uint8_t data, int16_t ss_pin);
static uint8_t transfer_chain(uint8_t data, int16_t ss_pin, uint8_t chain_position);
private:
static void append_stepper_err(char* &p, const uint8_t stepper_index, const char * const err=nullptr);
};
void echo_yes_no(const bool yes);
extern L64XX_Marlin L64xxManager;

View File

@ -1,98 +0,0 @@
### L64XX Stepper Driver
*Arduino-L6470* library revision 0.8.0 or above is required.
This software can be used with the L6470, L6474, L6480 and the powerSTEP01 (collectively referred to as "L64xx" from now on). Different drivers can be mixed within a system.
These devices use voltage PWMs to drive the stepper phases. On the L6474 the phase current is controlled by the `TVAL` register. On all the other drivers the phase current is indirectly controlled via the `KVAL_HOLD` register which scales the PWM duty cycle.
This software assumes that all drivers are in one SPI daisy chain.
### Hardware Setup
- MOSI from controller tied to SDI on the first device
- SDO of the first device is tied to SDI of the next device
- SDO of the last device is tied to MISO of the controller
- All devices share the same `SCK_PIN` and `SS_PIN` pins. The user must supply a macro to control the `RESET_PIN`(s).
- Each L6470 passes the data it saw on its SDI to its neighbor on the **NEXT** SPI cycle (8 bit delay).
- Each L6470 acts on the **last** SPI data it saw when the `SS_PIN` **goes high**.
The L6474 uses the standard STEP DIR interface. Phase currents are changed in response to step pulses. The direction is set by the DIR pin. Instead of an ENA pin, stepper power is controlled with SPI commands.
The other drivers operate in `STEP_CLOCK` mode. In this mode the Direction / Enable functions are done with SPI commands and the phase currents are changed in response to STEP pulses.
### Hardware / Software Interaction
Except for the L6474, powering up a stepper and setting the direction are done by the same command. You can't do one without the other.
**All** directions are set **every time** a new block is popped off the queue by the stepper ISR.
When setting direction, SPI transfers are minimized by using arrays and a specialized SPI method. *Arduino-L6470* library calls are not used. For N L64xx drivers, this results in N bytes transferred. If library calls were used then N<sup>2</sup> bytes would be sent.
### Power-up (Reset) Sequence
- Stepper objects are instantiated before the `setup()` entry point is reached.
- In `setup()` (before stepper drivers are initialized) the `L6470_init()` method is called to do the following:
- If present, pulse the hardware reset pin.
- Populate the `L6470_chain` array, which maps positions in the SPI stream to commands/data for L64XX stepper drivers.
- Initialize the L64XX Software SPI pin states.
- Initialize L64XX drivers. They may be reset later by a call to `L6470_init_to_defaults()`.
The steppers are **NOT** powered up (enabled) during this sequence.
### `L6470_chain` array
This array is used by all routines that transmit SPI data. For a chain with N devices, the array contains:
Index|Value
-----|-----
0|Number of drivers in chain
1|Axis index of the first device in the chain (closest to MOSI)
...|
N|Axis index of the last device chain (closest to MISO)
### Set Direction and Enable
The `DIR_WRITE` macros for the L64xx drivers are written so that the standard X, Y, Z and extruder logic used by the `set_directions()` routine is not altered. These macros write the correct forward/reverse command to the corresponding location in the array `L6470_dir_commands`. On the L6474 the array the command used just enables the stepper because direction is set by the DIR pin.
At the end of the `set_directions()` routine, the array `L6470_chain` is used to grab the corresponding direction/enable commands out of the array `L6470_dir_commands` and put them in the correct sequence in the array `L6470_buf`. Array `L6470_buf` is then passed to the **`void`** `L6470_Transfer` function which actually sends the data to the devices.
### Utilities, etc.
The **absolute position** registers should accurately reflect Marlins stepper position counts. They are set to zero during initialization. `G28` sets them to the Marlin counts for the corresponding axis after homing. NOTE: These registers are often the negative of the Marlin counts. This is because the Marlin counts reflect the logical direction while the registers reflect the stepper direction. The register contents are displayed via the `M114 D` command.
The `L6470_monitor` feature reads the status of each device every half second. It will report if there are any error conditions present or if communications has been lost/restored. The `KVAL_HOLD` value is reduced every 2 2.5 seconds if the thermal warning or thermal shutdown conditions are present.
**M122** displays the settings of most of the bits in the status register plus a couple of other items.
**M906** can be used to set the `KVAL_HOLD` register (`TVAL` on L6474) one driver at a time. If a setting is not included with the command then the contents of the registers that affect the phase current/voltage are displayed.
**M916, M917 & M918**
These utilities are used to tune the system. They can get you in the ballpark for acceptable jerk, acceleration, top speed and `KVAL_HOLD` settings (`TVAL` on L6474). In general they seem to provide an overly optimistic `KVAL_HOLD` (`TVAL`) setting because of the lag between setting `KVAL_HOLD` (`TVAL`) and the driver reaching final temperature. Enabling the `L6470_monitor` feature during prints will provide the **final useful setting**.
The amount of power needed to move the stepper without skipping steps increases as jerk, acceleration, top speed, and micro-steps increase. The power dissipated by the driver increases as the power to the stepper increases. The net result is a balancing act between jerk, acceleration, top speed, micro-steps, and power dissipated by the driver.
**M916** - Increases `KVAL_HOLD` (`TVAL`) while moving one axis until a thermal warning is generated. This routine is also useful for determining the approximate `KVAL_HOLD` (`TVAL`) where the stepper stops losing steps. The sound will get noticeably quieter as it stops losing steps.
**M917** - Find minimum current thresholds. This is accomplished by doing the following steps while moving an axis:
1. Decrease OCD current until overcurrent error.
2. Increase OCD until overcurrent error goes away.
3. Decrease stall threshold until stall error (not available on the L6474).
4. Increase stall until stall error goes away (not available on the L6474).
**M918** - Increase speed until error or max feedrate achieved.

View File

@ -117,12 +117,6 @@ Stepper stepper; // Singleton
#include "../feature/runout.h"
#endif
#if HAS_L64XX
#include "../libs/L64XX/L64XX_Marlin.h"
uint8_t L6470_buf[MAX_L64XX + 1]; // chip command sequence - element 0 not used
bool L64XX_OK_to_power_up = false; // flag to keep L64xx steppers powered down after a reset or power up
#endif
#if ENABLED(AUTO_POWER_CONTROL)
#include "../feature/power.h"
#endif
@ -618,27 +612,6 @@ void Stepper::set_directions() {
#endif
#endif // !LIN_ADVANCE
#if HAS_L64XX
if (L64XX_OK_to_power_up) { // OK to send the direction commands (which powers up the L64XX steppers)
if (L64xxManager.spi_active) {
L64xxManager.spi_abort = true; // Interrupted SPI transfer needs to shut down gracefully
for (uint8_t j = 1; j <= L64XX::chain[0]; j++)
L6470_buf[j] = dSPIN_NOP; // Fill buffer with NOOPs
L64xxManager.transfer(L6470_buf, L64XX::chain[0]); // Send enough NOOPs to complete any command
L64xxManager.transfer(L6470_buf, L64XX::chain[0]);
L64xxManager.transfer(L6470_buf, L64XX::chain[0]);
}
// L64xxManager.dir_commands[] is an array that holds direction command for each stepper
// Scan command array, copy matches into L64xxManager.transfer
for (uint8_t j = 1; j <= L64XX::chain[0]; j++)
L6470_buf[j] = L64xxManager.dir_commands[L64XX::chain[j]];
L64xxManager.transfer(L6470_buf, L64XX::chain[0]); // send the command stream to the drivers
}
#endif
DIR_WAIT_AFTER();
}
@ -2351,13 +2324,11 @@ uint32_t Stepper::block_phase_isr() {
else LA_isr_rate = LA_ADV_NEVER;
#endif
if ( ENABLED(HAS_L64XX) // Always set direction for L64xx (Also enables the chips)
|| ENABLED(DUAL_X_CARRIAGE) // TODO: Find out why this fixes "jittery" small circles
if ( ENABLED(DUAL_X_CARRIAGE) // TODO: Find out why this fixes "jittery" small circles
|| current_block->direction_bits != last_direction_bits
|| TERN(MIXING_EXTRUDER, false, stepper_extruder != last_moved_extruder)
) {
E_TERN_(last_moved_extruder = stepper_extruder);
TERN_(HAS_L64XX, L64XX_OK_to_power_up = true);
set_directions(current_block->direction_bits);
}

View File

@ -1,264 +0,0 @@
/**
* 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/>.
*
*/
/**
* stepper/L64xx.cpp
* Stepper driver indirection for L64XX drivers
*/
#include "../../inc/MarlinConfig.h"
#if HAS_L64XX
#include "L64xx.h"
#if AXIS_IS_L64XX(X)
L64XX_CLASS(X) stepperX(L6470_CHAIN_SS_PIN);
#endif
#if AXIS_IS_L64XX(X2)
L64XX_CLASS(X2) stepperX2(L6470_CHAIN_SS_PIN);
#endif
#if AXIS_IS_L64XX(Y)
L64XX_CLASS(Y) stepperY(L6470_CHAIN_SS_PIN);
#endif
#if AXIS_IS_L64XX(Y2)
L64XX_CLASS(Y2) stepperY2(L6470_CHAIN_SS_PIN);
#endif
#if AXIS_IS_L64XX(Z)
L64XX_CLASS(Z) stepperZ(L6470_CHAIN_SS_PIN);
#endif
#if AXIS_IS_L64XX(Z2)
L64XX_CLASS(Z2) stepperZ2(L6470_CHAIN_SS_PIN);
#endif
#if AXIS_IS_L64XX(Z3)
L64XX_CLASS(Z3) stepperZ3(L6470_CHAIN_SS_PIN);
#endif
#if AXIS_IS_L64XX(Z4)
L64XX_CLASS(Z4) stepperZ4(L6470_CHAIN_SS_PIN);
#endif
#if AXIS_IS_L64XX(I)
L64XX_CLASS(I) stepperI(L6470_CHAIN_SS_PIN);
#endif
#if AXIS_IS_L64XX(J)
L64XX_CLASS(J) stepperJ(L6470_CHAIN_SS_PIN);
#endif
#if AXIS_IS_L64XX(K)
L64XX_CLASS(K) stepperK(L6470_CHAIN_SS_PIN);
#endif
#if AXIS_IS_L64XX(U)
L64XX_CLASS(u) stepperU(L6470_CHAIN_SS_PIN);
#endif
#if AXIS_IS_L64XX(V)
L64XX_CLASS(v) stepperV(L6470_CHAIN_SS_PIN);
#endif
#if AXIS_IS_L64XX(W)
L64XX_CLASS(w) stepperW(L6470_CHAIN_SS_PIN);
#endif
#if AXIS_IS_L64XX(E0)
L64XX_CLASS(E0) stepperE0(L6470_CHAIN_SS_PIN);
#endif
#if AXIS_IS_L64XX(E1)
L64XX_CLASS(E1) stepperE1(L6470_CHAIN_SS_PIN);
#endif
#if AXIS_IS_L64XX(E2)
L64XX_CLASS(E2) stepperE2(L6470_CHAIN_SS_PIN);
#endif
#if AXIS_IS_L64XX(E3)
L64XX_CLASS(E3) stepperE3(L6470_CHAIN_SS_PIN);
#endif
#if AXIS_IS_L64XX(E4)
L64XX_CLASS(E4) stepperE4(L6470_CHAIN_SS_PIN);
#endif
#if AXIS_IS_L64XX(E5)
L64XX_CLASS(E5) stepperE5(L6470_CHAIN_SS_PIN);
#endif
#if AXIS_IS_L64XX(E6)
L64XX_CLASS(E6) stepperE6(L6470_CHAIN_SS_PIN);
#endif
#if AXIS_IS_L64XX(E7)
L64XX_CLASS(E7) stepperE7(L6470_CHAIN_SS_PIN);
#endif
// Not using L64XX class init method because it
// briefly sends power to the steppers
inline void L6470_init_chip(L64XX &st, const int ms, const int oc, const int sc, const int mv, const int slew_rate) {
st.set_handlers(L64xxManager.spi_init, L64xxManager.transfer_single, L64xxManager.transfer_chain); // specify which external SPI routines to use
switch (st.L6470_status_layout) {
case L6470_STATUS_LAYOUT: {
st.resetDev();
st.softFree();
st.SetParam(st.L64XX_CONFIG, CONFIG_PWM_DIV_1 | CONFIG_PWM_MUL_2 | CONFIG_OC_SD_DISABLE | CONFIG_VS_COMP_DISABLE | CONFIG_SW_HARD_STOP | CONFIG_INT_16MHZ);
st.SetParam(L6470_KVAL_RUN, 0xFF);
st.SetParam(L6470_KVAL_ACC, 0xFF);
st.SetParam(L6470_KVAL_DEC, 0xFF);
st.setMicroSteps(ms);
st.setOverCurrent(oc);
st.setStallCurrent(sc);
st.SetParam(L6470_KVAL_HOLD, mv);
st.SetParam(L6470_ABS_POS, 0);
uint32_t config_temp = st.GetParam(st.L64XX_CONFIG);
config_temp &= ~CONFIG_POW_SR;
switch (slew_rate) {
case 0: st.SetParam(st.L64XX_CONFIG, config_temp | CONFIG_SR_75V_us); break;
default:
case 1: st.SetParam(st.L64XX_CONFIG, config_temp | CONFIG_SR_110V_us); break;
case 3:
case 2: st.SetParam(st.L64XX_CONFIG, config_temp | CONFIG_SR_260V_us); break;
}
st.getStatus();
st.getStatus();
break;
}
case L6474_STATUS_LAYOUT: {
st.free();
//st.SetParam(st.L64XX_CONFIG, CONFIG_PWM_DIV_1 | CONFIG_PWM_MUL_2 | CONFIG_OC_SD_DISABLE | CONFIG_VS_COMP_DISABLE | CONFIG_SW_HARD_STOP | CONFIG_INT_16MHZ);
//st.SetParam(L6474_TVAL, 0xFF);
st.setMicroSteps(ms);
st.setOverCurrent(oc);
st.setTVALCurrent(sc);
st.SetParam(L6470_ABS_POS, 0);
uint32_t config_temp = st.GetParam(st.L64XX_CONFIG);
config_temp &= ~CONFIG_POW_SR & ~CONFIG_EN_TQREG; // clear out slew rate and set current to be controlled by TVAL register
switch (slew_rate) {
case 0: st.SetParam(st.L64XX_CONFIG, config_temp | CONFIG_SR_75V_us); break;
default:
case 1: st.SetParam(st.L64XX_CONFIG, config_temp | CONFIG_SR_110V_us); break;
case 3:
case 2: st.SetParam(st.L64XX_CONFIG, config_temp | CONFIG_SR_260V_us); break;
//case 0: st.SetParam(st.L64XX_CONFIG, 0x2E88 | CONFIG_EN_TQREG | CONFIG_SR_75V_us); break;
//default:
//case 1: st.SetParam(st.L64XX_CONFIG, 0x2E88 | CONFIG_EN_TQREG | CONFIG_SR_110V_us); break;
//case 3:
//case 2: st.SetParam(st.L64XX_CONFIG, 0x2E88 | CONFIG_EN_TQREG | CONFIG_SR_260V_us); break;
//case 0: st.SetParam(st.L64XX_CONFIG, 0x2E88 ); break;
//default:
//case 1: st.SetParam(st.L64XX_CONFIG, 0x2E88 ); break;
//case 3:
//case 2: st.SetParam(st.L64XX_CONFIG, 0x2E88 ); break;
}
st.getStatus();
st.getStatus();
break;
}
case L6480_STATUS_LAYOUT: {
st.resetDev();
st.softFree();
st.SetParam(st.L64XX_CONFIG, CONFIG_PWM_DIV_1 | CONFIG_PWM_MUL_2 | CONFIG_OC_SD_DISABLE | CONFIG_VS_COMP_DISABLE | CONFIG_SW_HARD_STOP | CONFIG_INT_16MHZ);
st.SetParam(L6470_KVAL_RUN, 0xFF);
st.SetParam(L6470_KVAL_ACC, 0xFF);
st.SetParam(L6470_KVAL_DEC, 0xFF);
st.setMicroSteps(ms);
st.setOverCurrent(oc);
st.setStallCurrent(sc);
st.SetParam(+-L6470_KVAL_HOLD, mv);
st.SetParam(L6470_ABS_POS, 0);
st.SetParam(st.L64XX_CONFIG,(st.GetParam(st.L64XX_CONFIG) | PWR_VCC_7_5V));
st.getStatus(); // must clear out status bits before can set slew rate
st.getStatus();
switch (slew_rate) {
case 0: st.SetParam(L6470_GATECFG1, CONFIG1_SR_220V_us); st.SetParam(L6470_GATECFG2, CONFIG2_SR_220V_us); break;
default:
case 1: st.SetParam(L6470_GATECFG1, CONFIG1_SR_400V_us); st.SetParam(L6470_GATECFG2, CONFIG2_SR_400V_us); break;
case 2: st.SetParam(L6470_GATECFG1, CONFIG1_SR_520V_us); st.SetParam(L6470_GATECFG2, CONFIG2_SR_520V_us); break;
case 3: st.SetParam(L6470_GATECFG1, CONFIG1_SR_980V_us); st.SetParam(L6470_GATECFG2, CONFIG2_SR_980V_us); break;
}
break;
}
}
}
#define L6470_INIT_CHIP(Q) L6470_init_chip(stepper##Q, Q##_MICROSTEPS, Q##_OVERCURRENT, Q##_STALLCURRENT, Q##_MAX_VOLTAGE, Q##_SLEW_RATE)
void L64XX_Marlin::init_to_defaults() {
#if AXIS_IS_L64XX(X)
L6470_INIT_CHIP(X);
#endif
#if AXIS_IS_L64XX(X2)
L6470_INIT_CHIP(X2);
#endif
#if AXIS_IS_L64XX(Y)
L6470_INIT_CHIP(Y);
#endif
#if AXIS_IS_L64XX(Y2)
L6470_INIT_CHIP(Y2);
#endif
#if AXIS_IS_L64XX(Z)
L6470_INIT_CHIP(Z);
#endif
#if AXIS_IS_L64XX(Z2)
L6470_INIT_CHIP(Z2);
#endif
#if AXIS_IS_L64XX(Z3)
L6470_INIT_CHIP(Z3);
#endif
#if AXIS_IS_L64XX(Z4)
L6470_INIT_CHIP(Z4);
#endif
#if AXIS_IS_L64XX(I)
L6470_INIT_CHIP(I);
#endif
#if AXIS_IS_L64XX(J)
L6470_INIT_CHIP(J);
#endif
#if AXIS_IS_L64XX(K)
L6470_INIT_CHIP(K);
#endif
#if AXIS_IS_L64XX(U)
L6470_INIT_CHIP(U);
#endif
#if AXIS_IS_L64XX(V)
L6470_INIT_CHIP(V);
#endif
#if AXIS_IS_L64XX(W)
L6470_INIT_CHIP(W);
#endif
#if AXIS_IS_L64XX(E0)
L6470_INIT_CHIP(E0);
#endif
#if AXIS_IS_L64XX(E1)
L6470_INIT_CHIP(E1);
#endif
#if AXIS_IS_L64XX(E2)
L6470_INIT_CHIP(E2);
#endif
#if AXIS_IS_L64XX(E3)
L6470_INIT_CHIP(E3);
#endif
#if AXIS_IS_L64XX(E4)
L6470_INIT_CHIP(E4);
#endif
#if AXIS_IS_L64XX(E5)
L6470_INIT_CHIP(E5);
#endif
#if AXIS_IS_L64XX(E6)
L6470_INIT_CHIP(E6);
#endif
#if AXIS_IS_L64XX(E7)
L6470_INIT_CHIP(E7);
#endif
}
#endif // HAS_L64XX

View File

@ -1,490 +0,0 @@
/**
* 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
/**
* stepper/L64xx.h
* Stepper driver indirection for L64XX drivers
*/
#include "../../inc/MarlinConfig.h"
#include "../../libs/L64XX/L64XX_Marlin.h"
// Convert option names to L64XX classes
#define CLASS_L6470 L6470
#define CLASS_L6474 L6474
#define CLASS_POWERSTEP01 powerSTEP01
#define __L64XX_CLASS(TYPE) CLASS_##TYPE
#define _L64XX_CLASS(TYPE) __L64XX_CLASS(TYPE)
#define L64XX_CLASS(ST) _L64XX_CLASS(ST##_DRIVER_TYPE)
#define L6474_DIR_WRITE(A,STATE) do{ L64xxManager.dir_commands[A] = dSPIN_L6474_ENABLE; WRITE(A##_DIR_PIN, STATE); }while(0)
#define L64XX_DIR_WRITE(A,STATE) do{ L64xxManager.dir_commands[A] = (STATE) ? dSPIN_STEP_CLOCK_REV : dSPIN_STEP_CLOCK_FWD; }while(0)
// X Stepper
#if AXIS_IS_L64XX(X)
extern L64XX_CLASS(X) stepperX;
#define X_ENABLE_INIT() NOOP
#define X_ENABLE_WRITE(STATE) (STATE ? stepperX.hardStop() : stepperX.free())
#define X_ENABLE_READ() (stepperX.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_X(L6474)
#define X_DIR_INIT() SET_OUTPUT(X_DIR_PIN)
#define X_DIR_WRITE(STATE) L6474_DIR_WRITE(X, STATE)
#define X_DIR_READ() READ(X_DIR_PIN)
#else
#define X_DIR_INIT() NOOP
#define X_DIR_WRITE(STATE) L64XX_DIR_WRITE(X, STATE)
#define X_DIR_READ() (stepper##X.getStatus() & STATUS_DIR);
#if AXIS_DRIVER_TYPE_X(L6470)
#define DISABLE_STEPPER_X() stepperX.free()
#endif
#endif
#endif
// Y Stepper
#if AXIS_IS_L64XX(Y)
extern L64XX_CLASS(Y) stepperY;
#define Y_ENABLE_INIT() NOOP
#define Y_ENABLE_WRITE(STATE) (STATE ? stepperY.hardStop() : stepperY.free())
#define Y_ENABLE_READ() (stepperY.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_Y(L6474)
#define Y_DIR_INIT() SET_OUTPUT(Y_DIR_PIN)
#define Y_DIR_WRITE(STATE) L6474_DIR_WRITE(Y, STATE)
#define Y_DIR_READ() READ(Y_DIR_PIN)
#else
#define Y_DIR_INIT() NOOP
#define Y_DIR_WRITE(STATE) L64XX_DIR_WRITE(Y, STATE)
#define Y_DIR_READ() (stepper##Y.getStatus() & STATUS_DIR);
#if AXIS_DRIVER_TYPE_Y(L6470)
#define DISABLE_STEPPER_Y() stepperY.free()
#endif
#endif
#endif
// Z Stepper
#if AXIS_IS_L64XX(Z)
extern L64XX_CLASS(Z) stepperZ;
#define Z_ENABLE_INIT() NOOP
#define Z_ENABLE_WRITE(STATE) (STATE ? stepperZ.hardStop() : stepperZ.free())
#define Z_ENABLE_READ() (stepperZ.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_Z(L6474)
#define Z_DIR_INIT() SET_OUTPUT(Z_DIR_PIN)
#define Z_DIR_WRITE(STATE) L6474_DIR_WRITE(Z, STATE)
#define Z_DIR_READ() READ(Z_DIR_PIN)
#else
#define Z_DIR_INIT() NOOP
#define Z_DIR_WRITE(STATE) L64XX_DIR_WRITE(Z, STATE)
#define Z_DIR_READ() (stepper##Z.getStatus() & STATUS_DIR);
#if AXIS_DRIVER_TYPE_Z(L6470)
#define DISABLE_STEPPER_Z() stepperZ.free()
#endif
#endif
#endif
// X2 Stepper
#if HAS_X2_ENABLE && AXIS_IS_L64XX(X2)
extern L64XX_CLASS(X2) stepperX2;
#define X2_ENABLE_INIT() NOOP
#define X2_ENABLE_WRITE(STATE) (STATE ? stepperX2.hardStop() : stepperX2.free())
#define X2_ENABLE_READ() (stepperX2.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_X2(L6474)
#define X2_DIR_INIT() SET_OUTPUT(X2_DIR_PIN)
#define X2_DIR_WRITE(STATE) L6474_DIR_WRITE(X2, STATE)
#define X2_DIR_READ() READ(X2_DIR_PIN)
#else
#define X2_DIR_INIT() NOOP
#define X2_DIR_WRITE(STATE) L64XX_DIR_WRITE(X2, STATE)
#define X2_DIR_READ() (stepper##X2.getStatus() & STATUS_DIR);
#endif
#endif
#if AXIS_DRIVER_TYPE_X2(L6470)
#define DISABLE_STEPPER_X2() stepperX2.free()
#endif
// Y2 Stepper
#if HAS_Y2_ENABLE && AXIS_IS_L64XX(Y2)
extern L64XX_CLASS(Y2) stepperY2;
#define Y2_ENABLE_INIT() NOOP
#define Y2_ENABLE_WRITE(STATE) (STATE ? stepperY2.hardStop() : stepperY2.free())
#define Y2_ENABLE_READ() (stepperY2.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_Y2(L6474)
#define Y2_DIR_INIT() SET_OUTPUT(Y2_DIR_PIN)
#define Y2_DIR_WRITE(STATE) L6474_DIR_WRITE(Y2, STATE)
#define Y2_DIR_READ() READ(Y2_DIR_PIN)
#else
#define Y2_DIR_INIT() NOOP
#define Y2_DIR_WRITE(STATE) L64XX_DIR_WRITE(Y2, STATE)
#define Y2_DIR_READ() (stepper##Y2.getStatus() & STATUS_DIR);
#endif
#endif
#if AXIS_DRIVER_TYPE_Y2(L6470)
#define DISABLE_STEPPER_Y2() stepperY2.free()
#endif
// Z2 Stepper
#if HAS_Z2_ENABLE && AXIS_IS_L64XX(Z2)
extern L64XX_CLASS(Z2) stepperZ2;
#define Z2_ENABLE_INIT() NOOP
#define Z2_ENABLE_WRITE(STATE) (STATE ? stepperZ2.hardStop() : stepperZ2.free())
#define Z2_ENABLE_READ() (stepperZ2.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_Z2(L6474)
#define Z2_DIR_INIT() SET_OUTPUT(Z2_DIR_PIN)
#define Z2_DIR_WRITE(STATE) L6474_DIR_WRITE(Z2, STATE)
#define Z2_DIR_READ() READ(Z2_DIR_PIN)
#else
#define Z2_DIR_INIT() NOOP
#define Z2_DIR_WRITE(STATE) L64XX_DIR_WRITE(Z2, STATE)
#define Z2_DIR_READ() (stepper##Z2.getStatus() & STATUS_DIR);
#endif
#endif
#if AXIS_DRIVER_TYPE_Z2(L6470)
#define DISABLE_STEPPER_Z2() stepperZ2.free()
#endif
// Z3 Stepper
#if HAS_Z3_ENABLE && AXIS_IS_L64XX(Z3)
extern L64XX_CLASS(Z3) stepperZ3;
#define Z3_ENABLE_INIT() NOOP
#define Z3_ENABLE_WRITE(STATE) (STATE ? stepperZ3.hardStop() : stepperZ3.free())
#define Z3_ENABLE_READ() (stepperZ3.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_Z3(L6474)
#define Z3_DIR_INIT() SET_OUTPUT(Z3_DIR_PIN)
#define Z3_DIR_WRITE(STATE) L6474_DIR_WRITE(Z3, STATE)
#define Z3_DIR_READ() READ(Z3_DIR_PIN)
#else
#define Z3_DIR_INIT() NOOP
#define Z3_DIR_WRITE(STATE) L64XX_DIR_WRITE(Z3, STATE)
#define Z3_DIR_READ() (stepper##Z3.getStatus() & STATUS_DIR);
#endif
#endif
#if AXIS_DRIVER_TYPE_Z3(L6470)
#define DISABLE_STEPPER_Z3() stepperZ3.free()
#endif
// Z4 Stepper
#if HAS_Z4_ENABLE && AXIS_IS_L64XX(Z4)
extern L64XX_CLASS(Z4) stepperZ4;
#define Z4_ENABLE_INIT() NOOP
#define Z4_ENABLE_WRITE(STATE) (STATE ? stepperZ4.hardStop() : stepperZ4.free())
#define Z4_ENABLE_READ() (stepperZ4.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_Z4(L6474)
#define Z4_DIR_INIT() SET_OUTPUT(Z4_DIR_PIN)
#define Z4_DIR_WRITE(STATE) L6474_DIR_WRITE(Z4, STATE)
#define Z4_DIR_READ() READ(Z4_DIR_PIN)
#else
#define Z4_DIR_INIT() NOOP
#define Z4_DIR_WRITE(STATE) L64XX_DIR_WRITE(Z4, STATE)
#define Z4_DIR_READ() (stepper##Z4.getStatus() & STATUS_DIR);
#endif
#endif
#if AXIS_DRIVER_TYPE_Z4(L6470)
#define DISABLE_STEPPER_Z4() stepperZ4.free()
#endif
// I Stepper
#if AXIS_IS_L64XX(I)
extern L64XX_CLASS(I) stepperI;
#define I_ENABLE_INIT() NOOP
#define I_ENABLE_WRITE(STATE) (STATE ? stepperI.hardStop() : stepperI.free())
#define I_ENABLE_READ() (stepperI.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_I(L6474)
#define I_DIR_INIT() SET_OUTPUT(I_DIR_PIN)
#define I_DIR_WRITE(STATE) L6474_DIR_WRITE(I, STATE)
#define I_DIR_READ() READ(I_DIR_PIN)
#else
#define I_DIR_INIT() NOOP
#define I_DIR_WRITE(STATE) L64XX_DIR_WRITE(I, STATE)
#define I_DIR_READ() (stepper##I.getStatus() & STATUS_DIR);
#if AXIS_DRIVER_TYPE_I(L6470)
#define DISABLE_STEPPER_I() stepperI.free()
#endif
#endif
#endif
// J Stepper
#if AXIS_IS_L64XX(J)
extern L64XX_CLASS(J) stepperJ;
#define J_ENABLE_INIT() NOOP
#define J_ENABLE_WRITE(STATE) (STATE ? stepperJ.hardStop() : stepperJ.free())
#define J_ENABLE_READ() (stepperJ.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_J(L6474)
#define J_DIR_INIT() SET_OUTPUT(J_DIR_PIN)
#define J_DIR_WRITE(STATE) L6474_DIR_WRITE(J, STATE)
#define J_DIR_READ() READ(J_DIR_PIN)
#else
#define J_DIR_INIT() NOOP
#define J_DIR_WRITE(STATE) L64XX_DIR_WRITE(J, STATE)
#define J_DIR_READ() (stepper##J.getStatus() & STATUS_DIR);
#if AXIS_DRIVER_TYPE_J(L6470)
#define DISABLE_STEPPER_J() stepperJ.free()
#endif
#endif
#endif
// K Stepper
#if AXIS_IS_L64XX(K)
extern L64XX_CLASS(K) stepperK;
#define K_ENABLE_INIT() NOOP
#define K_ENABLE_WRITE(STATE) (STATE ? stepperK.hardStop() : stepperK.free())
#define K_ENABLE_READ() (stepperK.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_K(L6474)
#define K_DIR_INIT() SET_OUTPUT(K_DIR_PIN)
#define K_DIR_WRITE(STATE) L6474_DIR_WRITE(K, STATE)
#define K_DIR_READ() READ(K_DIR_PIN)
#else
#define K_DIR_INIT() NOOP
#define K_DIR_WRITE(STATE) L64XX_DIR_WRITE(K, STATE)
#define K_DIR_READ() (stepper##K.getStatus() & STATUS_DIR);
#if AXIS_DRIVER_TYPE_K(L6470)
#define DISABLE_STEPPER_K() stepperK.free()
#endif
#endif
#endif
// U Stepper
#if HAS_U_AXIS
#if AXIS_IS_L64XX(U)
extern L64XX_CLASS(U) stepperU;
#define U_ENABLE_INIT() NOOP
#define U_ENABLE_WRITE(STATE) (STATE ? stepperU.hardStop() : stepperU.free())
#define U_ENABLE_READ() (stepperU.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_U(L6474)
#define U_DIR_INIT() SET_OUTPUT(U_DIR_PIN)
#define U_DIR_WRITE(STATE) L6474_DIR_WRITE(U, STATE)
#define U_DIR_READ() READ(U_DIR_PIN)
#else
#define U_DIR_INIT() NOOP
#define U_DIR_WRITE(STATE) L64XX_DIR_WRITE(U, STATE)
#define U_DIR_READ() (stepper##U.getStatus() & STATUS_DIR);
#if AXIS_DRIVER_TYPE_U(L6470)
#define DISABLE_STEPPER_U() stepperU.free()
#endif
#endif
#endif
#endif
// V Stepper
#if HAS_V_AXIS
#if AXIS_IS_L64XX(V)
extern L64XX_CLASS(V) stepperV;
#define V_ENABLE_INIT() NOOP
#define V_ENABLE_WRITE(STATE) (STATE ? stepperV.hardStop() : stepperV.free())
#define V_ENABLE_READ() (stepperV.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_V(L6474)
#define V_DIR_INIT() SET_OUTPUT(V_DIR_PIN)
#define V_DIR_WRITE(STATE) L6474_DIR_WRITE(V, STATE)
#define V_DIR_READ() READ(V_DIR_PIN)
#else
#define V_DIR_INIT() NOOP
#define V_DIR_WRITE(STATE) L64XX_DIR_WRITE(V, STATE)
#define V_DIR_READ() (stepper##V.getStatus() & STATUS_DIR);
#if AXIS_DRIVER_TYPE_V(L6470)
#define DISABLE_STEPPER_V() stepperV.free()
#endif
#endif
#endif
#endif
// W Stepper
#if HAS_W_AXIS
#if AXIS_IS_L64XX(W)
extern L64XX_CLASS(w) stepperW;
#define W_ENABLE_INIT() NOOP
#define W_ENABLE_WRITE(STATE) (STATE ? stepperW.hardStop() : stepperW.free())
#define W_ENABLE_READ() (stepperW.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_W(L6474)
#define W_DIR_INIT() SET_OUTPUT(W_DIR_PIN)
#define W_DIR_WRITE(STATE) L6474_DIR_WRITE(W, STATE)
#define W_DIR_READ() READ(W_DIR_PIN)
#else
#define W_DIR_INIT() NOOP
#define W_DIR_WRITE(STATE) L64XX_DIR_WRITE(W, STATE)
#define W_DIR_READ() (stepper##W.getStatus() & STATUS_DIR);
#if AXIS_DRIVER_TYPE_W(L6470)
#define DISABLE_STEPPER_W() stepperW.free()
#endif
#endif
#endif
#endif
// E0 Stepper
#if AXIS_IS_L64XX(E0)
extern L64XX_CLASS(E0) stepperE0;
#define E0_ENABLE_INIT() NOOP
#define E0_ENABLE_WRITE(STATE) (STATE ? stepperE0.hardStop() : stepperE0.free())
#define E0_ENABLE_READ() (stepperE0.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_E0(L6474)
#define E0_DIR_INIT() SET_OUTPUT(E0_DIR_PIN)
#define E0_DIR_WRITE(STATE) L6474_DIR_WRITE(E0, STATE)
#define E0_DIR_READ() READ(E0_DIR_PIN)
#else
#define E0_DIR_INIT() NOOP
#define E0_DIR_WRITE(STATE) L64XX_DIR_WRITE(E0, STATE)
#define E0_DIR_READ() (stepper##E0.getStatus() & STATUS_DIR);
#if AXIS_DRIVER_TYPE_E0(L6470)
#define DISABLE_STEPPER_E0() do{ stepperE0.free(); }while(0)
#endif
#endif
#endif
// E1 Stepper
#if AXIS_IS_L64XX(E1)
extern L64XX_CLASS(E1) stepperE1;
#define E1_ENABLE_INIT() NOOP
#define E1_ENABLE_WRITE(STATE) (STATE ? stepperE1.hardStop() : stepperE1.free())
#define E1_ENABLE_READ() (stepperE1.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_E1(L6474)
#define E1_DIR_INIT() SET_OUTPUT(E1_DIR_PIN)
#define E1_DIR_WRITE(STATE) L6474_DIR_WRITE(E1, STATE)
#define E1_DIR_READ() READ(E1_DIR_PIN)
#else
#define E1_DIR_INIT() NOOP
#define E1_DIR_WRITE(STATE) L64XX_DIR_WRITE(E1, STATE)
#define E1_DIR_READ() (stepper##E1.getStatus() & STATUS_DIR);
#if AXIS_DRIVER_TYPE_E1(L6470)
#define DISABLE_STEPPER_E1() do{ stepperE1.free(); }while(0)
#endif
#endif
#endif
// E2 Stepper
#if AXIS_IS_L64XX(E2)
extern L64XX_CLASS(E2) stepperE2;
#define E2_ENABLE_INIT() NOOP
#define E2_ENABLE_WRITE(STATE) (STATE ? stepperE2.hardStop() : stepperE2.free())
#define E2_ENABLE_READ() (stepperE2.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_E2(L6474)
#define E2_DIR_INIT() SET_OUTPUT(E2_DIR_PIN)
#define E2_DIR_WRITE(STATE) L6474_DIR_WRITE(E2, STATE)
#define E2_DIR_READ() READ(E2_DIR_PIN)
#else
#define E2_DIR_INIT() NOOP
#define E2_DIR_WRITE(STATE) L64XX_DIR_WRITE(E2, STATE)
#define E2_DIR_READ() (stepper##E2.getStatus() & STATUS_DIR);
#if AXIS_DRIVER_TYPE_E2(L6470)
#define DISABLE_STEPPER_E2() do{ stepperE2.free(); }while(0)
#endif
#endif
#endif
// E3 Stepper
#if AXIS_IS_L64XX(E3)
extern L64XX_CLASS(E3) stepperE3;
#define E3_ENABLE_INIT() NOOP
#define E3_ENABLE_WRITE(STATE) (STATE ? stepperE3.hardStop() : stepperE3.free())
#define E3_ENABLE_READ() (stepperE3.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_E3(L6474)
#define E3_DIR_INIT() SET_OUTPUT(E3_DIR_PIN)
#define E3_DIR_WRITE(STATE) L6474_DIR_WRITE(E3, STATE)
#define E3_DIR_READ() READ(E3_DIR_PIN)
#else
#define E3_DIR_INIT() NOOP
#define E3_DIR_WRITE(STATE) L64XX_DIR_WRITE(E3, STATE)
#define E3_DIR_READ() (stepper##E3.getStatus() & STATUS_DIR);
#endif
#endif
// E4 Stepper
#if AXIS_IS_L64XX(E4)
extern L64XX_CLASS(E4) stepperE4;
#define E4_ENABLE_INIT() NOOP
#define E4_ENABLE_WRITE(STATE) (STATE ? stepperE4.hardStop() : stepperE4.free())
#define E4_ENABLE_READ() (stepperE4.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_E4(L6474)
#define E4_DIR_INIT() SET_OUTPUT(E4_DIR_PIN)
#define E4_DIR_WRITE(STATE) L6474_DIR_WRITE(E4, STATE)
#define E4_DIR_READ() READ(E4_DIR_PIN)
#else
#define E4_DIR_INIT() NOOP
#define E4_DIR_WRITE(STATE) L64XX_DIR_WRITE(E4, STATE)
#define E4_DIR_READ() (stepper##E4.getStatus() & STATUS_DIR);
#if AXIS_DRIVER_TYPE_E4(L6470)
#define DISABLE_STEPPER_E4() do{ stepperE4.free(); }while(0)
#endif
#endif
#endif
// E5 Stepper
#if AXIS_IS_L64XX(E5)
extern L64XX_CLASS(E5) stepperE5;
#define E5_ENABLE_INIT() NOOP
#define E5_ENABLE_WRITE(STATE) (STATE ? stepperE5.hardStop() : stepperE5.free())
#define E5_ENABLE_READ() (stepperE5.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_E5(L6474)
#define E5_DIR_INIT() SET_OUTPUT(E5_DIR_PIN)
#define E5_DIR_WRITE(STATE) L6474_DIR_WRITE(E5, STATE)
#define E5_DIR_READ() READ(E5_DIR_PIN)
#else
#define E5_DIR_INIT() NOOP
#define E5_DIR_WRITE(STATE) L64XX_DIR_WRITE(E5, STATE)
#define E5_DIR_READ() (stepper##E5.getStatus() & STATUS_DIR);
#if AXIS_DRIVER_TYPE_E5(L6470)
#define DISABLE_STEPPER_E5() do{ stepperE5.free(); }while(0)
#endif
#endif
#endif
// E6 Stepper
#if AXIS_IS_L64XX(E6)
extern L64XX_CLASS(E6) stepperE6;
#define E6_ENABLE_INIT() NOOP
#define E6_ENABLE_WRITE(STATE) (STATE ? stepperE6.hardStop() : stepperE6.free())
#define E6_ENABLE_READ() (stepperE6.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_E6(L6474)
#define E6_DIR_INIT() SET_OUTPUT(E6_DIR_PIN)
#define E6_DIR_WRITE(STATE) L6474_DIR_WRITE(E6, STATE)
#define E6_DIR_READ() READ(E6_DIR_PIN)
#else
#define E6_DIR_INIT() NOOP
#define E6_DIR_WRITE(STATE) L64XX_DIR_WRITE(E6, STATE)
#define E6_DIR_READ() (stepper##E6.getStatus() & STATUS_DIR);
#if AXIS_DRIVER_TYPE_E6(L6470)
#define DISABLE_STEPPER_E6() do{ stepperE6.free(); }while(0)
#endif
#endif
#endif
// E7 Stepper
#if AXIS_IS_L64XX(E7)
extern L64XX_CLASS(E7) stepperE7;
#define E7_ENABLE_INIT() NOOP
#define E7_ENABLE_WRITE(STATE) (STATE ? stepperE7.hardStop() : stepperE7.free())
#define E7_ENABLE_READ() (stepperE7.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_E7(L6474)
#define E7_DIR_INIT() SET_OUTPUT(E7_DIR_PIN)
#define E7_DIR_WRITE(STATE) L6474_DIR_WRITE(E7, STATE)
#define E7_DIR_READ() READ(E7_DIR_PIN)
#else
#define E7_DIR_INIT() NOOP
#define E7_DIR_WRITE(STATE) L64XX_DIR_WRITE(E7, STATE)
#define E7_DIR_READ() (stepper##E7.getStatus() & STATUS_DIR);
#if AXIS_DRIVER_TYPE_E7(L6470)
#define DISABLE_STEPPER_E7() do{ stepperE7.free(); }while(0)
#endif
#endif
#endif

View File

@ -38,7 +38,6 @@ void restore_stepper_drivers() {
void reset_stepper_drivers() {
TERN_(HAS_TMC26X, tmc26x_init_to_defaults());
TERN_(HAS_L64XX, L64xxManager.init_to_defaults());
TERN_(HAS_TRINAMIC_CONFIG, reset_trinamic_drivers());
}

View File

@ -32,10 +32,6 @@
#include "../../inc/MarlinConfig.h"
#if HAS_L64XX
#include "L64xx.h"
#endif
#if HAS_TMC26X
#include "TMC26X.h"
#endif

View File

@ -629,8 +629,6 @@
#include "stm32f4/pins_RUMBA32_BTT.h" // STM32F4 env:rumba32
#elif MB(BLACK_STM32F407VE)
#include "stm32f4/pins_BLACK_STM32F407VE.h" // STM32F4 env:STM32F407VE_black
#elif MB(STEVAL_3DP001V1)
#include "stm32f4/pins_STEVAL_3DP001V1.h" // STM32F4 env:STM32F401VE_STEVAL
#elif MB(BTT_SKR_PRO_V1_1)
#include "stm32f4/pins_BTT_SKR_PRO_V1_1.h" // STM32F4 env:BIGTREE_SKR_PRO env:BIGTREE_SKR_PRO_usb_flash_drive
#elif MB(BTT_SKR_PRO_V1_2)
@ -786,6 +784,7 @@
#define BOARD_STM32F103R 99906
#define BOARD_ESP32 99907
#define BOARD_STEVAL 99908
#define BOARD_STEVAL_3DP001V1 99908
#define BOARD_BIGTREE_SKR_V1_1 99909
#define BOARD_BIGTREE_SKR_V1_3 99910
#define BOARD_BIGTREE_SKR_V1_4 99911
@ -841,7 +840,7 @@
#elif MOTHERBOARD == BOARD_ESP32
#error "BOARD_ESP32 has been renamed BOARD_ESPRESSIF_ESP32. Please update your configuration."
#elif MB(STEVAL)
#error "BOARD_STEVAL has been renamed BOARD_STEVAL_3DP001V1. Please update your configuration."
#error "BOARD_STEVAL_3DP001V1 (BOARD_STEVAL) is no longer supported in Marlin."
#elif MB(RUMBA32)
#error "BOARD_RUMBA32 is now BOARD_RUMBA32_MKS or BOARD_RUMBA32_V1_0. Please update your configuration."
#elif MB(RUMBA32_AUS3D)
@ -873,7 +872,7 @@
#undef BOARD_STM32F103R
#undef BOARD_ESP32
#undef BOARD_STEVAL
#undef BOARD_BIGTREE_SKR_MINI_E3
#undef BOARD_STEVAL_3DP001V1
#undef BOARD_BIGTREE_SKR_V1_1
#undef BOARD_BIGTREE_SKR_V1_3
#undef BOARD_BIGTREE_SKR_V1_4
@ -881,6 +880,7 @@
#undef BOARD_BIGTREE_BTT002_V1_0
#undef BOARD_BIGTREE_SKR_PRO_V1_1
#undef BOARD_BIGTREE_SKR_MINI_V1_1
#undef BOARD_BIGTREE_SKR_MINI_E3
#undef BOARD_BIGTREE_SKR_E3_DIP
#undef BOARD_RUMBA32
#undef BOARD_RUMBA32_AUS3D

View File

@ -1826,21 +1826,6 @@
#if PIN_EXISTS(K_SERIAL_RX)
REPORT_NAME_DIGITAL(__LINE__, K_SERIAL_RX_PIN)
#endif
#if PIN_EXISTS(L6470_CHAIN_SCK)
REPORT_NAME_DIGITAL(__LINE__, L6470_CHAIN_SCK_PIN)
#endif
#if PIN_EXISTS(L6470_CHAIN_MISO)
REPORT_NAME_DIGITAL(__LINE__, L6470_CHAIN_MISO_PIN)
#endif
#if PIN_EXISTS(L6470_CHAIN_MOSI)
REPORT_NAME_DIGITAL(__LINE__, L6470_CHAIN_MOSI_PIN)
#endif
#if PIN_EXISTS(L6470_CHAIN_SS)
REPORT_NAME_DIGITAL(__LINE__, L6470_CHAIN_SS_PIN)
#endif
#if PIN_EXISTS(L6470_RESET_CHAIN)
REPORT_NAME_DIGITAL(__LINE__, L6470_RESET_CHAIN_PIN)
#endif
#if PIN_EXISTS(FET_SAFETY)
REPORT_NAME_DIGITAL(__LINE__, FET_SAFETY_PIN)
#endif

View File

@ -1,325 +0,0 @@
/**
* 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
// Source: https://github.com/stm32duino/Arduino_Core_STM32/blob/master/variants/ST3DP001_EVAL/variant.cpp
/**
* HOW TO COMPILE
*
* PlatformIO - Use the STM32F401VE_STEVAL environment (or the "Auto Build Marlin" extension).
*
* Arduino - Tested with 1.8.10
* Install library per https://github.com/stm32duino/Arduino_Core_STM32
* Make the following selections under the TOOL menu in the Arduino IDE
* Board: "3D printer boards"
* Board part number: "STEVAL-3DP001V1"
* U(S)ART support: "Enabled (generic "Serial")"
* USB support (if available): "CDC (no generic "Serial")"
* Optimize: "Smallest (-Os default)"
* C Runtime Library: "newlib Nano (default)"
*/
#include "env_validate.h"
#ifndef MACHINE_NAME
#define MACHINE_NAME "STEVAL-3DP001V1"
#endif
//
// Limit Switches
//
#define X_MIN_PIN PD8 // X_STOP
#define Y_MIN_PIN PD9 // Y_STOP
#define Z_MIN_PIN PD10 // Z_STOP
#define X_MAX_PIN PD0 // W_STOP
#define Y_MAX_PIN PA8 // V_STOP
#define Z_MAX_PIN PD11 // U_STOP
//
// Z Probe (when not Z_MIN_PIN)
//
//#ifndef Z_MIN_PROBE_PIN
// #define Z_MIN_PROBE_PIN PA4 // SPI1_CS
//#endif
//
// Filament runout
//
//#define FIL_RUNOUT_PIN PA3 // BED_THERMISTOR_3
//
// Steppers
//
#define X_STEP_PIN PE14 // X_PWM
#define X_DIR_PIN PE15 // X_DIR
#define X_ENABLE_PIN PE13 // X_RESET
#define X_CS_PIN PA4 // SPI1_CS
#define Y_STEP_PIN PB10 // Y_PWM
#define Y_DIR_PIN PE9 // Y_DIR
#define Y_ENABLE_PIN PE10 // Y_RESET
#define Y_CS_PIN PA4 // SPI1_CS
#define Z_STEP_PIN PC6 // Z_PWM
#define Z_DIR_PIN PC0 // Z_DIR
#define Z_ENABLE_PIN PC15 // Z_RESET
#define Z_CS_PIN PA4 // SPI1_CS
#define E0_STEP_PIN PD12 // E1_PW
#define E0_DIR_PIN PC13 // E1_DIR
#define E0_ENABLE_PIN PC14 // E1_RESET
#define E0_CS_PIN PA4 // SPI1_CS
#define E1_STEP_PIN PE5 // E2_PWM
#define E1_DIR_PIN PE6 // E2_DIR
#define E1_ENABLE_PIN PE4 // E2_RESET
#define E1_CS_PIN PA4 // SPI1_CS
#define E2_STEP_PIN PB8 // E3_PWM
#define E2_DIR_PIN PE2 // E3_DIR
#define E2_ENABLE_PIN PE3 // E3_RESET
#define E2_CS_PIN PA4 // SPI1_CS
// needed to pass a sanity check
#define X2_CS_PIN PA4 // SPI1_CS
#define Y2_CS_PIN PA4 // SPI1_CS
#define Z2_CS_PIN PA4 // SPI1_CS
#define Z3_CS_PIN PA4 // SPI1_CS
#define E3_CS_PIN PA4 // SPI1_CS
#define E4_CS_PIN PA4 // SPI1_CS
#define E5_CS_PIN PA4 // SPI1_CS
#if HAS_L64XX
#define L6470_CHAIN_SCK_PIN PA5 // SPI1_SCK
#define L6470_CHAIN_MISO_PIN PA6 // SPI1_MISO
#define L6470_CHAIN_MOSI_PIN PA7 // SPI1_MOSI
#define L6470_CHAIN_SS_PIN PA4 // SPI1_CS
//#define SD_SCK_PIN L6470_CHAIN_SCK_PIN
//#define SD_MISO_PIN L6470_CHAIN_MISO_PIN
//#define SD_MOSI_PIN L6470_CHAIN_MOSI_PIN
#else
//#define SD_SCK_PIN PB13 // SPI2_SCK
//#define SD_MISO_PIN PB14 // SPI2_MISO
//#define SD_MOSI_PIN PB15 // SPI2_MOSI
#endif
/**
* Macro to reset/enable L6474 stepper drivers
*
* IMPORTANT - To disable (bypass) L6474s, install the corresponding
* resistors (R11 - R17) and change the "V" to "0" for the
* corresponding pins here:
*/
#define ENABLE_RESET_L64XX_CHIPS(V) do{ OUT_WRITE(X_ENABLE_PIN, V); \
OUT_WRITE(Y_ENABLE_PIN, V); \
OUT_WRITE(Z_ENABLE_PIN, V); \
OUT_WRITE(E0_ENABLE_PIN,V); \
OUT_WRITE(E1_ENABLE_PIN,V); \
OUT_WRITE(E2_ENABLE_PIN,V); \
}while(0)
//
// Temperature Sensors
//
#define TEMP_0_PIN PA0 // Analog Input 3
#define TEMP_1_PIN PA1 // Analog Input 4
#define TEMP_2_PIN PA2 // Analog Input 5
#define TEMP_BED_PIN PC2 // Analog Input 0
#define TEMP_BED_1_PIN PC3 // Analog Input 1
#define TEMP_BED_2_PIN PA3 // Analog Input 2
//
// Heaters / Fans
//
#define HEATER_0_PIN PC7 // E1_HEAT_PWM
#define HEATER_1_PIN PB0 // E2_HEAT_PWM
#define HEATER_2_PIN PB1 // E3_HEAT_PWM
#define HEATER_BED_PIN PD14 // BED_HEAT_1 FET
#define HEATER_BED_1_PIN PD13 // BED_HEAT_2 FET
#define HEATER_BED_2_PIN PD15 // BED_HEAT_3 FET
#define FAN_PIN PC4 // E1_FAN PWM pin, Part cooling fan FET
#define FAN1_PIN PC5 // E2_FAN PWM pin, Extruder fan FET
#define FAN2_PIN PE8 // E3_FAN PWM pin, Controller fan FET
#ifndef E0_AUTO_FAN_PIN
#define E0_AUTO_FAN_PIN PC5 // FAN1_PIN
#endif
//
// Misc functions
//
#define LED_PIN -1 // PE1 Green LED Heartbeat
#define PS_ON_PIN -1
#define KILL_PIN -1
#define POWER_LOSS_PIN -1 // PWR_LOSS / nAC_FAULT
//
// LCD / Controller
//
//#define SD_DETECT_PIN PA15 // SD_CARD_DETECT
//#define BEEPER_PIN PC9 // SDIO_D1
//#define LCD_PINS_RS PE9 // Y_DIR
//#define LCD_PINS_ENABLE PE8 // E3_FAN
//#define LCD_PINS_D4 PB12 // SPI2_CS
//#define LCD_PINS_D5 PB13 // SPI2_SCK
//#define LCD_PINS_D6 PB14 // SPI2_MISO
//#define LCD_PINS_D7 PB15 // SPI2_MOSI
//#define BTN_EN1 PC4 // E1_FAN
//#define BTN_EN2 PC5 // E2_FAN
//#define BTN_ENC PC3 // BED_THERMISTOR_2
//
// Extension pins
//
//#define EXT0_PIN PB0 // E2_HEAT
//#define EXT1_PIN PB1 // E3_HEAT
//#define EXT2_PIN PB2 // not used (tied to ground)
//#define EXT3_PIN PD8 // X_STOP
//#define EXT4_PIN PD9 // Y_STOP
//#define EXT5_PIN PD10 // Z_STOP
//#define EXT6_PIN PD11 // U_STOP
//#define EXT7_PIN PD12 // E1_PWM
//#define EXT8_PIN PB10 // Y_PWM
// WIFI
// PD3 CTS
// PD4 RTS
// PD5 TX
// PD6 RX
// PB5 WIFI_WAKEUP
// PE11 WIFI_RESET
// PE12 WIFI_BOOT
// I2C USER
// PB7 SDA
// PB6 SCL
// JTAG
// PA13 JTAG_TMS/SWDIO
// PA14 JTAG_TCK/SWCLK
// PB3 JTAG_TDO/SWO
//
// Onboard SD support
//
#ifndef SDCARD_CONNECTION
#define SDCARD_CONNECTION ONBOARD
#endif
#if SD_CONNECTION_IS(ONBOARD)
#define SDIO_SUPPORT // Use SDIO for onboard SD
#if DISABLED(SDIO_SUPPORT)
#define SOFTWARE_SPI // Use soft SPI for onboard SD
#define SDSS PC11
#define SD_SCK_PIN PC12
#define SD_MISO_PIN PC8
#define SD_MOSI_PIN PD2
#endif
//#define SD_DETECT_PIN PA15
#endif
#ifndef SDSS
#define SDSS PA4 // SPI1_CS
#endif
// OTG
// PA11 OTG_DM
// PA12 OTG_DP
// USER_PINS
// PD7 USER3
// PB9 USER1
// PE0 USER2
// PB4 USER4
// USERKET
// PE7 USER_BUTTON
// PA9 TX
// PA10 RX
// IR/PROBE
// PD1 IR_OUT
// PC1 IR_ON
/**
* Logical pin vs. port/pin cross reference
*
* PA0 E1_THERMISTOR PD0 W_STOP
* PA1 E2_THERMISTOR PD1 IR_OUT
* PA2 E3_THERMISTOR PD2 SDIO_CMD
* PA3 BED_THERMISTOR_3 PD3 CTS
* PA4 SPI1_CS PD4 RTS
* PA5 SPI1_SCK PD5 TX
* PA6 SPI1_MISO PD6 RX
* PA7 SPI1_MOSI PD7 USER3
* PA8 V_STOP PD8 X_STOP
* PA9 TX PD9 Y_STOP
* PA10 RX PD10 Z_STOP
* PA11 OTG_DM PD11 U_STOP
* PA12 OTG_DP PD12 E1_PWM
* PA13 JTAG_TMS/SWDIO PD13 BED_HEAT_2
* PA14 JTAG_TCK/SWCLK PD14 BED_HEAT_1
* PA15 SD_CARD_DETECT PD15 BED_HEAT_3
*
* PB0 E2_HEAT_PWM PE0 USER2
* PB1 E3_HEAT_PWM PE1 STATUS_LED
* PB2 --- PE2 E3_DIR
* PB3 JTAG_TDO/SWO PE3 E3_RESET
* PB4 USER4 PE4 E2_RESET
* PB5 WIFI_WAKEUP PE5 E2_PWM
* PB6 SCL PE6 E2_DIR
* PB7 SDA PE7 USER_BUTTON
* PB8 E3_PWM PE8 E3_FAN
* PB9 USER1 PE9 Y_DIR
* PB10 Y_PWM PE10 Y_RESET
* PB11 --- PE11 WIFI_RESET
* PB12 SPI2_CS PE12 WIFI_BOOT
* PB13 SPI2_SCK PE13 X_RESET
* PB14 SPI2_MISO PE14 X_PWM
* PB15 SPI2_MOSI PE15 X_DIR
*
* PC0 Z_DIR
* PC1 IR_ON
* PC2 BED_THERMISTOR_1
* PC3 BED_THERMISTOR_2
* PC4 E1_FAN
* PC5 E2_FAN
* PC6 Z_PWM
* PC7 E1_HEAT_PWM
* PC8 SDIO_D0
* PC9 SDIO_D1
* PC10 SDIO_D2
* PC11 SDIO_D3
* PC12 SDIO_CK
* PC13 E1_DIR
* PC14 E1_RESET
* PC15 Z_RESET
*/

View File

@ -1,64 +0,0 @@
{
"build": {
"core": "stm32",
"cpu": "cortex-m4",
"extra_flags": "-DSTM32F401xx -DARDUINO_STEVAL",
"f_cpu": "84000000L",
"hwids": [
[
"0x1EAF",
"0x0003"
],
[
"0x0483",
"0x3748"
]
],
"mcu": "stm32f401vet6",
"variant": "MARLIN_STEVAL_F401VE"
},
"debug": {
"jlink_device": "STM32F401VE",
"openocd_target": "stm32f4x",
"svd_path": "STM32F40x.svd",
"tools": {
"stlink": {
"server": {
"arguments": [
"-f",
"scripts/interface/stlink.cfg",
"-c",
"transport select hla_swd",
"-f",
"scripts/target/stm32f4x.cfg",
"-c",
"reset_config none"
],
"executable": "bin/openocd",
"package": "tool-openocd"
}
}
}
},
"frameworks": [
"arduino",
"stm32cube"
],
"name": "STM32F401VE (96k RAM. 512k Flash)",
"upload": {
"disable_flushing": false,
"maximum_ram_size": 98304,
"maximum_size": 514288,
"protocol": "stlink",
"protocols": [
"stlink",
"dfu",
"jlink"
],
"require_upload_port": true,
"use_1200bps_touch": false,
"wait_for_upload_port": false
},
"url": "https://www.st.com/en/evaluation-tools/steval-3dp001v1.html",
"vendor": "Generic"
}

View File

@ -1,260 +0,0 @@
/*
*******************************************************************************
* Copyright (c) 2019, STMicroelectronics
* All rights reserved.
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
*******************************************************************************
* Automatically generated from STM32F401V(D-E)Tx.xml
*/
#include "Arduino.h"
#include "PeripheralPins.h"
/* =====
* Note: Commented lines are alternative possibilities which are not used per default.
* If you change them, you will have to know what you do
* =====
*/
//*** ADC ***
#ifdef HAL_ADC_MODULE_ENABLED
WEAK const PinMap PinMap_ADC[] = {
{PA_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC1_IN0
{PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1
{PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2
{PA_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3
//{PA_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4
//{PA_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_IN5
//{PA_6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6
//{PA_7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7
//{PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8
//{PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9
//{PC_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10
//{PC_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC1_IN11
{PC_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC1_IN12
{PC_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC1_IN13
//{PC_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_IN14
//{PC_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15
{NC, NP, 0}
};
#endif
//*** No DAC ***
//*** I2C ***
#ifdef HAL_I2C_MODULE_ENABLED
WEAK const PinMap PinMap_I2C_SDA[] = {
//{PB_3, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF9_I2C2)},
//{PB_4, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF9_I2C3)},
{PB_7, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
//{PB_9, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
//{PC_9, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)},
{NC, NP, 0}
};
WEAK const PinMap PinMap_I2C_SCL[] = {
//{PA_8, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)},
{PB_6, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
//{PB_8, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
//{PB_10, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)},
{NC, NP, 0}
};
#endif
//*** PWM ***
#ifdef HAL_TIM_MODULE_ENABLED
WEAK const PinMap PinMap_PWM[] = {
//{PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1
//{PA_0, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1
//{PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2
//{PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2
//{PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3
//{PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3
//{PA_2, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1
//{PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4
//{PA_3, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 4, 0)}, // TIM5_CH4
//{PA_3, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2
//{PA_5, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1
//{PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1
//{PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N
//{PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2
//{PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1
//{PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2
//{PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3
//{PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4
//{PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1
//{PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N
{PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3
//{PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N
{PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4
//{PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2
//{PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1
//{PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2
//{PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1
//{PB_7, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2
//{PB_8, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3
//{PB_8, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1
//{PB_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4
//{PB_9, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1
{PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3
//{PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N
//{PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N
//{PB_15, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N
{PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1
{PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2
//{PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3
//{PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4
{PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1
{PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2
{PD_14, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3
{PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4
{PE_5, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1
//{PE_6, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2
//{PE_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N
//{PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1
//{PE_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N
//{PE_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2
//{PE_12, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N
//{PE_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3
{PE_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4
{NC, NP, 0}
};
#endif
//*** SERIAL ***
#ifdef HAL_UART_MODULE_ENABLED
WEAK const PinMap PinMap_UART_TX[] = {
//{PA_2, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
{PA_9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
//{PA_11, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)},
//{PB_6, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
//{PC_6, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)},
{PD_5, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
{NC, NP, 0}
};
WEAK const PinMap PinMap_UART_RX[] = {
//{PA_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
{PA_10, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
//{PA_12, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)},
//{PB_7, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
//{PC_7, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)},
{PD_6, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
{NC, NP, 0}
};
WEAK const PinMap PinMap_UART_RTS[] = {
//{PA_1, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
//{PA_12, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
{PD_4, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
{NC, NP, 0}
};
WEAK const PinMap PinMap_UART_CTS[] = {
//{PA_0, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
//{PA_11, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
{PD_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
{NC, NP, 0}
};
#endif
//*** SPI ***
#ifdef HAL_SPI_MODULE_ENABLED
WEAK const PinMap PinMap_SPI_MOSI[] = {
{PA_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
//{PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
//{PB_5, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
{PB_15, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
//{PC_3, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
//{PC_12, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
//{PD_6, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
//{PE_6, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)},
//{PE_14, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)},
{NC, NP, 0}
};
WEAK const PinMap PinMap_SPI_MISO[] = {
{PA_6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
//{PB_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
//{PB_4, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
{PB_14, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
//{PC_2, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
//{PC_11, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
//{PE_5, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)},
//{PE_13, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)},
{NC, NP, 0}
};
WEAK const PinMap PinMap_SPI_SCLK[] = {
{PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
//{PB_3, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
//{PB_3, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
//{PB_10, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
{PB_13, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
//{PC_10, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
//{PD_3, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
//{PE_2, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)},
//{PE_12, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)},
{NC, NP, 0}
};
WEAK const PinMap PinMap_SPI_SSEL[] = {
{PA_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
//{PA_4, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
//{PA_15, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
//{PA_15, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
//{PB_9, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
{PB_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
//{PE_4, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)},
//{PE_11, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)},
{NC, NP, 0}
};
#endif
//*** No CAN ***
//*** No ETHERNET ***
//*** No QUADSPI ***
//*** USB ***
#ifdef HAL_PCD_MODULE_ENABLED
WEAK const PinMap PinMap_USB_OTG_FS[] = {
//{PA_8, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_SOF
//{PA_9, USB_OTG_FS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_FS_VBUS
//{PA_10, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_ID
{PA_11, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DM
{PA_12, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DP
{NC, NP, 0}
};
#endif
//*** No USB_OTG_HS ***
//*** SD ***
#ifdef HAL_SD_MODULE_ENABLED
WEAK const PinMap PinMap_SD[] = {
//{PB_8, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D4
//{PB_9, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D5
//{PC_6, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D6
//{PC_7, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D7
{PC_8, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D0
{PC_9, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D1
{PC_10, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D2
{PC_11, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D3
{PC_12, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF12_SDIO)}, // SDIO_CK
{PD_2, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF12_SDIO)}, // SDIO_CMD
{NC, NP, 0}
};
#endif

View File

@ -1,33 +0,0 @@
/* SYS_WKUP */
#ifdef PWR_WAKEUP_PIN1
SYS_WKUP1 = PA_0,
#endif
#ifdef PWR_WAKEUP_PIN2
SYS_WKUP2 = NC,
#endif
#ifdef PWR_WAKEUP_PIN3
SYS_WKUP3 = NC,
#endif
#ifdef PWR_WAKEUP_PIN4
SYS_WKUP4 = NC,
#endif
#ifdef PWR_WAKEUP_PIN5
SYS_WKUP5 = NC,
#endif
#ifdef PWR_WAKEUP_PIN6
SYS_WKUP6 = NC,
#endif
#ifdef PWR_WAKEUP_PIN7
SYS_WKUP7 = NC,
#endif
#ifdef PWR_WAKEUP_PIN8
SYS_WKUP8 = NC,
#endif
/* USB */
#ifdef USBCON
USB_OTG_FS_SOF = PA_8,
USB_OTG_FS_VBUS = PA_9,
USB_OTG_FS_ID = PA_10,
USB_OTG_FS_DM = PA_11,
USB_OTG_FS_DP = PA_12,
#endif

View File

@ -1,495 +0,0 @@
/**
******************************************************************************
* @file stm32f4xx_hal_conf.h
* @brief HAL configuration file.
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2017 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F4xx_HAL_CONF_CUSTOM
#define __STM32F4xx_HAL_CONF_CUSTOM
#ifdef __cplusplus
extern "C" {
#endif
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* ########################## Module Selection ############################## */
/**
* @brief This is the list of modules to be used in the HAL driver
*/
#define HAL_MODULE_ENABLED
#define HAL_ADC_MODULE_ENABLED
#define HAL_CRC_MODULE_ENABLED
#define HAL_DMA_MODULE_ENABLED
#define HAL_EXTI_MODULE_ENABLED // Needed for Endstop (and other external) Interrupts
#define HAL_FLASH_MODULE_ENABLED
#define HAL_GPIO_MODULE_ENABLED
#define HAL_I2C_MODULE_ENABLED
#define HAL_IWDG_MODULE_ENABLED
#define HAL_PWR_MODULE_ENABLED
#define HAL_RCC_MODULE_ENABLED
#define HAL_RTC_MODULE_ENABLED
#define HAL_SD_MODULE_ENABLED
#define HAL_SPI_MODULE_ENABLED
#define HAL_TIM_MODULE_ENABLED
#define HAL_CORTEX_MODULE_ENABLED
//#define HAL_PCD_MODULE_ENABLED // Automatically added if any type of USB is enabled, as in Arduino IDE. (STM32 v3.10700.191028)
//#define HAL_CAN_MODULE_ENABLED
//#define HAL_CAN_LEGACY_MODULE_ENABLED
//#define HAL_CEC_MODULE_ENABLED
//#define HAL_CRYP_MODULE_ENABLED
//#define HAL_DAC_MODULE_ENABLED
//#define HAL_DCMI_MODULE_ENABLED
//#define HAL_DMA2D_MODULE_ENABLED
//#define HAL_ETH_MODULE_ENABLED
//#define HAL_NAND_MODULE_ENABLED
//#define HAL_NOR_MODULE_ENABLED
//#define HAL_PCCARD_MODULE_ENABLED
//#define HAL_SRAM_MODULE_ENABLED
//#define HAL_SDRAM_MODULE_ENABLED
//#define HAL_HASH_MODULE_ENABLED
//#define HAL_SMBUS_MODULE_ENABLED
//#define HAL_I2S_MODULE_ENABLED
//#define HAL_LTDC_MODULE_ENABLED
//#define HAL_DSI_MODULE_ENABLED
//#define HAL_QSPI_MODULE_ENABLED
//#define HAL_RNG_MODULE_ENABLED
//#define HAL_SAI_MODULE_ENABLED
//#define HAL_UART_MODULE_ENABLED // by default
//#define HAL_USART_MODULE_ENABLED
//#define HAL_IRDA_MODULE_ENABLED
//#define HAL_SMARTCARD_MODULE_ENABLED
//#define HAL_WWDG_MODULE_ENABLED
//#define HAL_HCD_MODULE_ENABLED
//#define HAL_FMPI2C_MODULE_ENABLED
//#define HAL_SPDIFRX_MODULE_ENABLED
//#define HAL_DFSDM_MODULE_ENABLED
//#define HAL_LPTIM_MODULE_ENABLED
//#define HAL_MMC_MODULE_ENABLED
/* ########################## HSE/HSI Values adaptation ##################### */
/**
* @brief Adjust the value of External High Speed oscillator (HSE) used in your application.
* This value is used by the RCC HAL module to compute the system frequency
* (when HSE is used as system clock source, directly or through the PLL).
*/
#ifndef HSE_VALUE
#define HSE_VALUE 8000000U /*!< Value of the External oscillator in Hz */
#endif /* HSE_VALUE */
#ifndef HSE_STARTUP_TIMEOUT
#define HSE_STARTUP_TIMEOUT 100U /*!< Time out for HSE start up, in ms */
#endif /* HSE_STARTUP_TIMEOUT */
/**
* @brief Internal High Speed oscillator (HSI) value.
* This value is used by the RCC HAL module to compute the system frequency
* (when HSI is used as system clock source, directly or through the PLL).
*/
#ifndef HSI_VALUE
#define HSI_VALUE 16000000U /*!< Value of the Internal oscillator in Hz */
#endif /* HSI_VALUE */
/**
* @brief Internal Low Speed oscillator (LSI) value.
*/
#ifndef LSI_VALUE
#define LSI_VALUE 32000U /*!< LSI Typical Value in Hz */
#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz
The real value may vary depending on the variations
in voltage and temperature. */
/**
* @brief External Low Speed oscillator (LSE) value.
*/
#ifndef LSE_VALUE
#define LSE_VALUE 32768U /*!< Value of the External Low Speed oscillator in Hz */
#endif /* LSE_VALUE */
#ifndef LSE_STARTUP_TIMEOUT
#define LSE_STARTUP_TIMEOUT 5000U /*!< Time out for LSE start up, in ms */
#endif /* LSE_STARTUP_TIMEOUT */
/**
* @brief External clock source for I2S peripheral
* This value is used by the I2S HAL module to compute the I2S clock source
* frequency, this source is inserted directly through I2S_CKIN pad.
*/
#ifndef EXTERNAL_CLOCK_VALUE
#define EXTERNAL_CLOCK_VALUE 12288000U /*!< Value of the External oscillator in Hz*/
#endif /* EXTERNAL_CLOCK_VALUE */
/* Tip: To avoid modifying this file each time you need to use different HSE,
=== you can define the HSE value in your toolchain compiler preprocessor. */
/* ########################### System Configuration ######################### */
/**
* @brief This is the HAL system configuration section
*/
#if !defined (VDD_VALUE)
#define VDD_VALUE 3300U /*!< Value of VDD in mv */
#endif
#if !defined (TICK_INT_PRIORITY)
#define TICK_INT_PRIORITY 0x00U /*!< tick interrupt priority */
#endif
#if !defined (USE_RTOS)
#define USE_RTOS 0U
#endif
#if !defined (PREFETCH_ENABLE)
#define PREFETCH_ENABLE 1U
#endif
#if !defined (INSTRUCTION_CACHE_ENABLE)
#define INSTRUCTION_CACHE_ENABLE 1U
#endif
#if !defined (DATA_CACHE_ENABLE)
#define DATA_CACHE_ENABLE 1U
#endif
#define USE_HAL_ADC_REGISTER_CALLBACKS 0U /* ADC register callback disabled */
#define USE_HAL_CAN_REGISTER_CALLBACKS 0U /* CAN register callback disabled */
#define USE_HAL_CEC_REGISTER_CALLBACKS 0U /* CEC register callback disabled */
#define USE_HAL_CRYP_REGISTER_CALLBACKS 0U /* CRYP register callback disabled */
#define USE_HAL_DAC_REGISTER_CALLBACKS 0U /* DAC register callback disabled */
#define USE_HAL_DCMI_REGISTER_CALLBACKS 0U /* DCMI register callback disabled */
#define USE_HAL_DFSDM_REGISTER_CALLBACKS 0U /* DFSDM register callback disabled */
#define USE_HAL_DMA2D_REGISTER_CALLBACKS 0U /* DMA2D register callback disabled */
#define USE_HAL_DSI_REGISTER_CALLBACKS 0U /* DSI register callback disabled */
#define USE_HAL_ETH_REGISTER_CALLBACKS 0U /* ETH register callback disabled */
#define USE_HAL_HASH_REGISTER_CALLBACKS 0U /* HASH register callback disabled */
#define USE_HAL_HCD_REGISTER_CALLBACKS 0U /* HCD register callback disabled */
#define USE_HAL_I2C_REGISTER_CALLBACKS 0U /* I2C register callback disabled */
#define USE_HAL_FMPI2C_REGISTER_CALLBACKS 0U /* FMPI2C register callback disabled */
#define USE_HAL_I2S_REGISTER_CALLBACKS 0U /* I2S register callback disabled */
#define USE_HAL_IRDA_REGISTER_CALLBACKS 0U /* IRDA register callback disabled */
#define USE_HAL_LPTIM_REGISTER_CALLBACKS 0U /* LPTIM register callback disabled */
#define USE_HAL_LTDC_REGISTER_CALLBACKS 0U /* LTDC register callback disabled */
#define USE_HAL_MMC_REGISTER_CALLBACKS 0U /* MMC register callback disabled */
#define USE_HAL_NAND_REGISTER_CALLBACKS 0U /* NAND register callback disabled */
#define USE_HAL_NOR_REGISTER_CALLBACKS 0U /* NOR register callback disabled */
#define USE_HAL_PCCARD_REGISTER_CALLBACKS 0U /* PCCARD register callback disabled */
#define USE_HAL_PCD_REGISTER_CALLBACKS 0U /* PCD register callback disabled */
#define USE_HAL_QSPI_REGISTER_CALLBACKS 0U /* QSPI register callback disabled */
#define USE_HAL_RNG_REGISTER_CALLBACKS 0U /* RNG register callback disabled */
#define USE_HAL_RTC_REGISTER_CALLBACKS 0U /* RTC register callback disabled */
#define USE_HAL_SAI_REGISTER_CALLBACKS 0U /* SAI register callback disabled */
#define USE_HAL_SD_REGISTER_CALLBACKS 0U /* SD register callback disabled */
#define USE_HAL_SMARTCARD_REGISTER_CALLBACKS 0U /* SMARTCARD register callback disabled */
#define USE_HAL_SDRAM_REGISTER_CALLBACKS 0U /* SDRAM register callback disabled */
#define USE_HAL_SRAM_REGISTER_CALLBACKS 0U /* SRAM register callback disabled */
#define USE_HAL_SPDIFRX_REGISTER_CALLBACKS 0U /* SPDIFRX register callback disabled */
#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0U /* SMBUS register callback disabled */
#define USE_HAL_SPI_REGISTER_CALLBACKS 0U /* SPI register callback disabled */
#define USE_HAL_TIM_REGISTER_CALLBACKS 0U /* TIM register callback disabled */
#define USE_HAL_UART_REGISTER_CALLBACKS 0U /* UART register callback disabled */
#define USE_HAL_USART_REGISTER_CALLBACKS 0U /* USART register callback disabled */
#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U /* WWDG register callback disabled */
/* ########################## Assert Selection ############################## */
/**
* @brief Uncomment the line below to expanse the "assert_param" macro in the
* HAL drivers code
*/
/* #define USE_FULL_ASSERT 1U */
/* ################## Ethernet peripheral configuration ##################### */
/* Section 1 : Ethernet peripheral configuration */
/* MAC ADDRESS: MAC_ADDR0:MAC_ADDR1:MAC_ADDR2:MAC_ADDR3:MAC_ADDR4:MAC_ADDR5 */
#define MAC_ADDR0 2U
#define MAC_ADDR1 0U
#define MAC_ADDR2 0U
#define MAC_ADDR3 0U
#define MAC_ADDR4 0U
#define MAC_ADDR5 0U
/* Definition of the Ethernet driver buffers size and count */
#define ETH_RX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for receive */
#define ETH_TX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for transmit */
#define ETH_RXBUFNB ((uint32_t)4U) /* 4 Rx buffers of size ETH_RX_BUF_SIZE */
#define ETH_TXBUFNB ((uint32_t)4U) /* 4 Tx buffers of size ETH_TX_BUF_SIZE */
/* Section 2: PHY configuration section */
/* DP83848_PHY_ADDRESS Address*/
#define DP83848_PHY_ADDRESS 0x01U
/* PHY Reset delay these values are based on a 1 ms Systick interrupt*/
#define PHY_RESET_DELAY 0x000000FFU
/* PHY Configuration delay */
#define PHY_CONFIG_DELAY 0x00000FFFU
#define PHY_READ_TO 0x0000FFFFU
#define PHY_WRITE_TO 0x0000FFFFU
/* Section 3: Common PHY Registers */
#define PHY_BCR ((uint16_t)0x0000) /*!< Transceiver Basic Control Register */
#define PHY_BSR ((uint16_t)0x0001) /*!< Transceiver Basic Status Register */
#define PHY_RESET ((uint16_t)0x8000) /*!< PHY Reset */
#define PHY_LOOPBACK ((uint16_t)0x4000) /*!< Select loop-back mode */
#define PHY_FULLDUPLEX_100M ((uint16_t)0x2100) /*!< Set the full-duplex mode at 100 Mb/s */
#define PHY_HALFDUPLEX_100M ((uint16_t)0x2000) /*!< Set the half-duplex mode at 100 Mb/s */
#define PHY_FULLDUPLEX_10M ((uint16_t)0x0100) /*!< Set the full-duplex mode at 10 Mb/s */
#define PHY_HALFDUPLEX_10M ((uint16_t)0x0000) /*!< Set the half-duplex mode at 10 Mb/s */
#define PHY_AUTONEGOTIATION ((uint16_t)0x1000) /*!< Enable auto-negotiation function */
#define PHY_RESTART_AUTONEGOTIATION ((uint16_t)0x0200) /*!< Restart auto-negotiation function */
#define PHY_POWERDOWN ((uint16_t)0x0800) /*!< Select the power down mode */
#define PHY_ISOLATE ((uint16_t)0x0400) /*!< Isolate PHY from MII */
#define PHY_AUTONEGO_COMPLETE ((uint16_t)0x0020) /*!< Auto-Negotiation process completed */
#define PHY_LINKED_STATUS ((uint16_t)0x0004) /*!< Valid link established */
#define PHY_JABBER_DETECTION ((uint16_t)0x0002) /*!< Jabber condition detected */
/* Section 4: Extended PHY Registers */
#define PHY_SR ((uint16_t)0x10U) /*!< PHY status register Offset */
#define PHY_SPEED_STATUS ((uint16_t)0x0002U) /*!< PHY Speed mask */
#define PHY_DUPLEX_STATUS ((uint16_t)0x0004U) /*!< PHY Duplex mask */
/* ################## SPI peripheral configuration ########################## */
/* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver
* Activated: CRC code is present inside driver
* Deactivated: CRC code cleaned from driver
*/
#ifndef USE_SPI_CRC
#define USE_SPI_CRC 0U
#endif
/* Includes ------------------------------------------------------------------*/
/**
* @brief Include module's header file
*/
#ifdef HAL_RCC_MODULE_ENABLED
#include "stm32f4xx_hal_rcc.h"
#endif /* HAL_RCC_MODULE_ENABLED */
#ifdef HAL_GPIO_MODULE_ENABLED
#include "stm32f4xx_hal_gpio.h"
#endif /* HAL_GPIO_MODULE_ENABLED */
#ifdef HAL_EXTI_MODULE_ENABLED
#include "stm32f4xx_hal_exti.h"
#endif /* HAL_EXTI_MODULE_ENABLED */
#ifdef HAL_DMA_MODULE_ENABLED
#include "stm32f4xx_hal_dma.h"
#endif /* HAL_DMA_MODULE_ENABLED */
#ifdef HAL_CORTEX_MODULE_ENABLED
#include "stm32f4xx_hal_cortex.h"
#endif /* HAL_CORTEX_MODULE_ENABLED */
#ifdef HAL_ADC_MODULE_ENABLED
#include "stm32f4xx_hal_adc.h"
#endif /* HAL_ADC_MODULE_ENABLED */
#ifdef HAL_CAN_MODULE_ENABLED
#include "stm32f4xx_hal_can.h"
#endif /* HAL_CAN_MODULE_ENABLED */
#ifdef HAL_CAN_LEGACY_MODULE_ENABLED
#include "stm32f4xx_hal_can_legacy.h"
#endif /* HAL_CAN_LEGACY_MODULE_ENABLED */
#ifdef HAL_CRC_MODULE_ENABLED
#include "stm32f4xx_hal_crc.h"
#endif /* HAL_CRC_MODULE_ENABLED */
#ifdef HAL_CRYP_MODULE_ENABLED
#include "stm32f4xx_hal_cryp.h"
#endif /* HAL_CRYP_MODULE_ENABLED */
#ifdef HAL_DMA2D_MODULE_ENABLED
#include "stm32f4xx_hal_dma2d.h"
#endif /* HAL_DMA2D_MODULE_ENABLED */
#ifdef HAL_DAC_MODULE_ENABLED
#include "stm32f4xx_hal_dac.h"
#endif /* HAL_DAC_MODULE_ENABLED */
#ifdef HAL_DCMI_MODULE_ENABLED
#include "stm32f4xx_hal_dcmi.h"
#endif /* HAL_DCMI_MODULE_ENABLED */
#ifdef HAL_ETH_MODULE_ENABLED
#include "stm32f4xx_hal_eth.h"
#endif /* HAL_ETH_MODULE_ENABLED */
#ifdef HAL_FLASH_MODULE_ENABLED
#include "stm32f4xx_hal_flash.h"
#endif /* HAL_FLASH_MODULE_ENABLED */
#ifdef HAL_SRAM_MODULE_ENABLED
#include "stm32f4xx_hal_sram.h"
#endif /* HAL_SRAM_MODULE_ENABLED */
#ifdef HAL_NOR_MODULE_ENABLED
#include "stm32f4xx_hal_nor.h"
#endif /* HAL_NOR_MODULE_ENABLED */
#ifdef HAL_NAND_MODULE_ENABLED
#include "stm32f4xx_hal_nand.h"
#endif /* HAL_NAND_MODULE_ENABLED */
#ifdef HAL_PCCARD_MODULE_ENABLED
#include "stm32f4xx_hal_pccard.h"
#endif /* HAL_PCCARD_MODULE_ENABLED */
#ifdef HAL_SDRAM_MODULE_ENABLED
#include "stm32f4xx_hal_sdram.h"
#endif /* HAL_SDRAM_MODULE_ENABLED */
#ifdef HAL_HASH_MODULE_ENABLED
#include "stm32f4xx_hal_hash.h"
#endif /* HAL_HASH_MODULE_ENABLED */
#ifdef HAL_I2C_MODULE_ENABLED
#include "stm32f4xx_hal_i2c.h"
#endif /* HAL_I2C_MODULE_ENABLED */
#ifdef HAL_SMBUS_MODULE_ENABLED
#include "stm32f4xx_hal_smbus.h"
#endif /* HAL_SMBUS_MODULE_ENABLED */
#ifdef HAL_I2S_MODULE_ENABLED
#include "stm32f4xx_hal_i2s.h"
#endif /* HAL_I2S_MODULE_ENABLED */
#ifdef HAL_IWDG_MODULE_ENABLED
#include "stm32f4xx_hal_iwdg.h"
#endif /* HAL_IWDG_MODULE_ENABLED */
#ifdef HAL_LTDC_MODULE_ENABLED
#include "stm32f4xx_hal_ltdc.h"
#endif /* HAL_LTDC_MODULE_ENABLED */
#ifdef HAL_PWR_MODULE_ENABLED
#include "stm32f4xx_hal_pwr.h"
#endif /* HAL_PWR_MODULE_ENABLED */
#ifdef HAL_RNG_MODULE_ENABLED
#include "stm32f4xx_hal_rng.h"
#endif /* HAL_RNG_MODULE_ENABLED */
#ifdef HAL_RTC_MODULE_ENABLED
#include "stm32f4xx_hal_rtc.h"
#endif /* HAL_RTC_MODULE_ENABLED */
#ifdef HAL_SAI_MODULE_ENABLED
#include "stm32f4xx_hal_sai.h"
#endif /* HAL_SAI_MODULE_ENABLED */
#ifdef HAL_SD_MODULE_ENABLED
#include "stm32f4xx_hal_sd.h"
#endif /* HAL_SD_MODULE_ENABLED */
#ifdef HAL_SPI_MODULE_ENABLED
#include "stm32f4xx_hal_spi.h"
#endif /* HAL_SPI_MODULE_ENABLED */
#ifdef HAL_TIM_MODULE_ENABLED
#include "stm32f4xx_hal_tim.h"
#endif /* HAL_TIM_MODULE_ENABLED */
#ifdef HAL_UART_MODULE_ENABLED
#include "stm32f4xx_hal_uart.h"
#endif /* HAL_UART_MODULE_ENABLED */
#ifdef HAL_USART_MODULE_ENABLED
#include "stm32f4xx_hal_usart.h"
#endif /* HAL_USART_MODULE_ENABLED */
#ifdef HAL_IRDA_MODULE_ENABLED
#include "stm32f4xx_hal_irda.h"
#endif /* HAL_IRDA_MODULE_ENABLED */
#ifdef HAL_SMARTCARD_MODULE_ENABLED
#include "stm32f4xx_hal_smartcard.h"
#endif /* HAL_SMARTCARD_MODULE_ENABLED */
#ifdef HAL_WWDG_MODULE_ENABLED
#include "stm32f4xx_hal_wwdg.h"
#endif /* HAL_WWDG_MODULE_ENABLED */
#ifdef HAL_PCD_MODULE_ENABLED
#include "stm32f4xx_hal_pcd.h"
#endif /* HAL_PCD_MODULE_ENABLED */
#ifdef HAL_HCD_MODULE_ENABLED
#include "stm32f4xx_hal_hcd.h"
#endif /* HAL_HCD_MODULE_ENABLED */
#ifdef HAL_DSI_MODULE_ENABLED
#include "stm32f4xx_hal_dsi.h"
#endif /* HAL_DSI_MODULE_ENABLED */
#ifdef HAL_QSPI_MODULE_ENABLED
#include "stm32f4xx_hal_qspi.h"
#endif /* HAL_QSPI_MODULE_ENABLED */
#ifdef HAL_CEC_MODULE_ENABLED
#include "stm32f4xx_hal_cec.h"
#endif /* HAL_CEC_MODULE_ENABLED */
#ifdef HAL_FMPI2C_MODULE_ENABLED
#include "stm32f4xx_hal_fmpi2c.h"
#endif /* HAL_FMPI2C_MODULE_ENABLED */
#ifdef HAL_SPDIFRX_MODULE_ENABLED
#include "stm32f4xx_hal_spdifrx.h"
#endif /* HAL_SPDIFRX_MODULE_ENABLED */
#ifdef HAL_DFSDM_MODULE_ENABLED
#include "stm32f4xx_hal_dfsdm.h"
#endif /* HAL_DFSDM_MODULE_ENABLED */
#ifdef HAL_LPTIM_MODULE_ENABLED
#include "stm32f4xx_hal_lptim.h"
#endif /* HAL_LPTIM_MODULE_ENABLED */
#ifdef HAL_MMC_MODULE_ENABLED
#include "stm32f4xx_hal_mmc.h"
#endif /* HAL_MMC_MODULE_ENABLED */
/* Exported macro ------------------------------------------------------------*/
#ifdef USE_FULL_ASSERT
/**
* @brief The assert_param macro is used for function's parameters check.
* @param expr If expr is false, it calls assert_failed function
* which reports the name of the source file and the source
* line number of the call that failed.
* If expr is true, it returns no value.
* @retval None
*/
#define assert_param(expr) ((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__))
/* Exported functions ------------------------------------------------------- */
void assert_failed(uint8_t *file, uint32_t line);
#else
#define assert_param(expr) ((void)0U)
#endif /* USE_FULL_ASSERT */
#ifdef __cplusplus
}
#endif
#endif /* __STM32F4xx_HAL_CONF_CUSTOM_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,187 +0,0 @@
/*
*****************************************************************************
**
** File : ldscript.ld
**
** Abstract : Linker script for STM32F401RETx Device with
** 512KByte FLASH, 96KByte RAM
**
** Set heap size, stack size and stack location according
** to application requirements.
**
** Set memory bank area and size if external memory is used.
**
** Target : STMicroelectronics STM32
**
**
** Distribution: The file is distributed as is, without any warranty
** of any kind.
**
*****************************************************************************
** @attention
**
** <h2><center>&copy; COPYRIGHT(c) 2014 Ac6</center></h2>
**
** Redistribution and use in source and binary forms, with or without modification,
** are permitted provided that the following conditions are met:
** 1. Redistributions of source code must retain the above copyright notice,
** this list of conditions and the following disclaimer.
** 2. Redistributions in binary form must reproduce the above copyright notice,
** this list of conditions and the following disclaimer in the documentation
** and/or other materials provided with the distribution.
** 3. Neither the name of Ac6 nor the names of its contributors
** may be used to endorse or promote products derived from this software
** without specific prior written permission.
**
** THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
** AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
** IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
** DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
** FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
** DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
** SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
** CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
** OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
** OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
**
*****************************************************************************
*/
/* Entry Point */
ENTRY(Reset_Handler)
/* Highest address of the user mode stack */
_estack = 0x20018000; /* end of RAM */
/* Generate a link error if heap and stack don't fit into RAM */
_Min_Heap_Size = 0x200; /* required amount of heap */
_Min_Stack_Size = 0x400; /* required amount of stack */
/* Specify the memory areas */
MEMORY
{
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 512K
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 96K
}
/* Define output sections */
SECTIONS
{
/* The startup code goes first into FLASH */
.isr_vector :
{
. = ALIGN(4);
KEEP(*(.isr_vector)) /* Startup code */
. = ALIGN(4);
} >FLASH
/* The program code and other data goes into FLASH */
.text :
{
. = ALIGN(4);
*(.text) /* .text sections (code) */
*(.text*) /* .text* sections (code) */
*(.glue_7) /* glue arm to thumb code */
*(.glue_7t) /* glue thumb to arm code */
*(.eh_frame)
KEEP (*(.init))
KEEP (*(.fini))
. = ALIGN(4);
_etext = .; /* define a global symbols at end of code */
} >FLASH
/* Constant data goes into FLASH */
.rodata :
{
. = ALIGN(4);
*(.rodata) /* .rodata sections (constants, strings, etc.) */
*(.rodata*) /* .rodata* sections (constants, strings, etc.) */
. = ALIGN(4);
} >FLASH
.ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
.ARM : {
__exidx_start = .;
*(.ARM.exidx*)
__exidx_end = .;
} >FLASH
.preinit_array :
{
PROVIDE_HIDDEN (__preinit_array_start = .);
KEEP (*(.preinit_array*))
PROVIDE_HIDDEN (__preinit_array_end = .);
} >FLASH
.init_array :
{
PROVIDE_HIDDEN (__init_array_start = .);
KEEP (*(SORT(.init_array.*)))
KEEP (*(.init_array*))
PROVIDE_HIDDEN (__init_array_end = .);
} >FLASH
.fini_array :
{
PROVIDE_HIDDEN (__fini_array_start = .);
KEEP (*(SORT(.fini_array.*)))
KEEP (*(.fini_array*))
PROVIDE_HIDDEN (__fini_array_end = .);
} >FLASH
/* used by the startup to initialize data */
_sidata = LOADADDR(.data);
/* Initialized data sections goes into RAM, load LMA copy after code */
.data :
{
. = ALIGN(4);
_sdata = .; /* create a global symbol at data start */
*(.data) /* .data sections */
*(.data*) /* .data* sections */
. = ALIGN(4);
_edata = .; /* define a global symbol at data end */
} >RAM AT> FLASH
/* Uninitialized data section */
. = ALIGN(4);
.bss :
{
/* This is used by the startup in order to initialize the .bss section */
_sbss = .; /* define a global symbol at bss start */
__bss_start__ = _sbss;
*(.bss)
*(.bss*)
*(COMMON)
. = ALIGN(4);
_ebss = .; /* define a global symbol at bss end */
__bss_end__ = _ebss;
} >RAM
/* User_heap_stack section, used to check that there is enough RAM left */
._user_heap_stack :
{
. = ALIGN(4);
PROVIDE ( end = . );
PROVIDE ( _end = . );
. = . + _Min_Heap_Size;
. = . + _Min_Stack_Size;
. = ALIGN(4);
} >RAM
/* Remove information from the standard libraries */
/DISCARD/ :
{
libc.a ( * )
libm.a ( * )
libgcc.a ( * )
}
.ARM.attributes 0 : { *(.ARM.attributes) }
}

View File

@ -1,310 +0,0 @@
/*
*******************************************************************************
* Copyright (c) 2017, STMicroelectronics
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*******************************************************************************
*/
#include "pins_arduino.h"
#ifdef __cplusplus
extern "C" {
#endif
#ifdef ARDUINO_STEVAL
// Pin number
// This array allows to wrap Arduino pin number(Dx or x)
// to STM32 PinName (PX_n)
const PinName digitalPin[] = {
PA_9, // TX
PA_10, // RX
// WIFI
PD_3, // CTS
PD_4, // RTS
PD_5, // TX
PD_6, // RX
PB_5, // WIFI_WAKEUP
PE_11, // WIFI_RESET
PE_12, // WIFI_BOOT
// STATUS_LED
PE_1, //STATUS_LED
// SPI USER
PB_12, // SPI_CS
PB_15, // SPI_MOSI
PB_14, // SPI_MISO
PB_13, // SPI_SCK
// I2C USER
PB_7, // SDA
PB_6, // SCL
// SPI
PA_4, // SPI_CS
PA_5, // SPI_SCK
PA_6, // SPI_MISO
PA_7, // SPI_MOSI
// JTAG
PA_13, // JTAG_TMS/SWDIO
PA_14, // JTAG_TCK/SWCLK
PB_3, // JTAG_TDO/SWO
// SDCARD
PC_8, // SDIO_D0
PC_9, // SDIO_D1
PA_15, // SD_CARD_DETECT
PC_10, // SDIO_D2
PC_11, // SDIO_D3
PC_12, // SDIO_CK
PD_2, // SDIO_CMD
// OTG
PA_11, // OTG_DM
PA_12, // OTG_DP
// IR/PROBE
PD_1, // IR_OUT
PC_1, // IR_ON
// USER_PINS
PD_7, // USER3
PB_9, // USER1
PE_0, // USER2
PB_4, // USER4
// USERKET
PE_7, // USER_BUTTON
// ENDSTOPS
PD_8, // X_STOP
PD_9, // Y_STOP
PD_10, // Z_STOP
PD_11, // U_STOP
PA_8, // V_STOP
PD_0, // W_STOP
// HEATERS
PD_13, // BED_HEAT_2
PD_14, // BED_HEAT_1
PD_15, // BED_HEAT_3
PC_7, // E1_HEAT_PWM
PB_0, // E2_HEAT_PWM
PB_1, // E3_HEAT_PWM
// THERMISTOR
PC_2, // BED_THERMISTOR_1
PC_3, // BED_THERMISTOR_2
PA_3, // BED_THERMISTOR_3
PA_0, // E1_THERMISTOR
PA_1, // E2_THERMISTOR
PA_2, // E3_THERMISTOR
// FANS
PC_4, // E1_FAN
PC_5, // E2_FAN
PE_8, // E3_FAN
// X_MOTOR
PE_13, // X_RESET
PE_14, // X_PWM
PE_15, // X_DIR
// Y_MOTOR
PE_10, // Y_RESET
PB_10, // Y_PWM
PE_9, // Y_DIR
// Z_MOTOR
PC_15, // Z_RESET
PC_6, // Z_PWM
PC_0, // Z_DIR
// E1_MOTOR
PC_14, // E1_RESET
PC_13, // E1_DIR
PD_12, // E1_PWM
// E2_MOTOR
PE_4, // E2_RESET
PE_5, // E2_PWM
PE_6, // E2_DIR
// E3_MOTOR
PE_3, // E3_RESET
PE_2, // E3_DIR
PB_8 // E3_PWM
};
#endif
#ifdef __cplusplus
}
#endif
// ----------------------------------------------------------------------------
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief System Clock Configuration
* The system Clock is configured as follow :
* System Clock source = PLL (HSI)
* SYSCLK(Hz) = 84000000
* HCLK(Hz) = 84000000
* AHB Prescaler = 1
* APB1 Prescaler = 2
* APB2 Prescaler = 1
* HSI Frequency(Hz) = 16000000
* PLL_M = 16
* PLL_N = 336
* PLL_P = 4
* PLL_Q = 7
* VDD(V) = 3.3
* Main regulator output voltage = Scale2 mode
* Flash Latency(WS) = 2
* @param None
* @retval None
*/
WEAK void SystemClock_Config(void)
{
RCC_OscInitTypeDef RCC_OscInitStruct = {};
RCC_ClkInitTypeDef RCC_ClkInitStruct = {};
/* Configure the main internal regulator output voltage */
__HAL_RCC_PWR_CLK_ENABLE();
__HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE2);
/* Initializes the CPU, AHB and APB busses clocks */
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
RCC_OscInitStruct.HSEState = RCC_HSE_ON;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
RCC_OscInitStruct.PLL.PLLM = 15;
RCC_OscInitStruct.PLL.PLLN = 144;
RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV4;
RCC_OscInitStruct.PLL.PLLQ = 5;
if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) {
Error_Handler();
}
/* Initializes the CPU, AHB and APB busses clocks */
RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_SYSCLK
| RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2;
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2;
RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1;
if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_1) != HAL_OK) {
Error_Handler();
}
}
#ifdef __cplusplus
}
#endif
// PA_0 54 // E1_THERMISTOR
// PA_1 55 // E2_THERMISTOR
// PA_2 56 // E3_THERMISTOR
// PA_3 53 // BED_THERMISTOR_3
// PA_4 16 // SPI_CS
// PA_5 17 // SPI_SCK
// PA_6 18 // SPI_MISO
// PA_7 19 // SPI_MOSI
// PA_8 43 // V_STOP
// PA_9 0 //TX
// PA_10 1 //RX
// PA_11 30 //OTG_DM
// PA_12 31 //OTG_DP
// PA_13 20 // JTAG_TMS/SWDIO
// PA_14 21 // JTAG_TCK/SWCLK
// PA_15 25 // SD_CARD_DETECT
// PB_0 49 // E2_HEAT_PWM
// PB_1 50 // E3_HEAT_PWM
// PB_3 22 // JTAG_TDO/SWO
// PB_4 37 // USER4
// PB_5 6 // WIFI_WAKEUP
// PB_6 15 // SCL
// PB_7 14 // SDA
// PB_8 77 // E3_PWM
// PB_9 35 // USER1
// PB_10 64 // Y_PWM
// PB_12 10 // SPI_CS
// PB_13 13 // SPI_SCK
// PB_14 12 // SPI_MISO
// PB_15 11 // SPI_MOSI
// PC_0 68 // Z_DIR
// PC_1 33 //IR_ON
// PC_2 51 // BED_THERMISTOR_1
// PC_3 52 // BED_THERMISTOR_2
// PC_4 57 // E1_FAN
// PC_5 58 // E2_FAN
// PC_6 67 // Z_PWM
// PC_7 48 // E1_HEAT_PWM
// PC_8 23 // SDIO_D0
// PC_9 24 // SDIO_D1
// PC_10 26 // SDIO_D2
// PC_11 27 // SDIO_D3
// PC_12 28 // SDIO_CK
// PC_13 70 // E1_DIR
// PC_14 69 // E1_RESET
// PC_15 66 // Z_RESET
// PD_0 44 // W_STOP
// PD_1 32 //IR_OUT
// PD_2 29 // SDIO_CMD
// PD_3 2 // CTS
// PD_4 3 // RTS
// PD_5 4 // TX
// PD_6 5 // RX
// PD_7 34 // USER3
// PD_8 39 // X_STOP
// PD_9 40 // Y_STOP
// PD_10 41 // Z_STOP
// PD_11 42 // U_STOP
// PD_12 71 // E1_PWM
// PD_13 45 // BED_HEAT_2
// PD_14 46 // BED_HEAT_1
// PD_15 47 // BED_HEAT_3
// PE_0 36 // USER2
// PE_1 9 // STATUS_LED
// PE_2 76 // E3_DIR
// PE_3 75 // E3_RESET
// PE_4 72 // E2_RESET
// PE_5 73 // E2_PWM
// PE_6 74 // E2_DIR
// PE_7 38 // USER_BUTTON
// PE_8 59 // E3_FAN
// PE_9 65 // Y_DIR
// PE_10 63 // Y_RESET
// PE_11 7 // WIFI_RESET
// PE_12 8 // WIFI_BOOT
// PE_13 60 // X_RESET
// PE_14 61 // X_PWM
// PE_15 62 // X_DIR

View File

@ -1,327 +0,0 @@
/*
*******************************************************************************
* Copyright (c) 2017, STMicroelectronics
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*******************************************************************************
*/
#ifndef _VARIANT_ARDUINO_STM32_
#define _VARIANT_ARDUINO_STM32_
/*----------------------------------------------------------------------------
* Headers
*----------------------------------------------------------------------------*/
#ifdef __cplusplus
extern "C" {
#endif // __cplusplus
/*----------------------------------------------------------------------------
* Pins
*----------------------------------------------------------------------------*/
#ifdef ARDUINO_STEVAL
/*----------------------------------------------------------------------------
* Pins
*----------------------------------------------------------------------------*/
// USART1_MAIN
#define PA9 0 //TX
#define PA10 1 //RX
// WIFI (USART2)
#define PD3 2 // CTS
#define PD4 3 // RTS
#define PD5 4 // TX
#define PD6 5 // RX
#define PB5 6 // WIFI_WAKEUP
#define PE11 7 // WIFI_RESET
#define PE12 8 // WIFI_BOOT
// STATUS_LED
#define PE1 9 // STATUS_LED
// SPI USER
#define PB12 10 // SPI_CS
#define PB15 11 // SPI_MOSI
#define PB14 12 // SPI_MISO
#define PB13 13 // SPI_SCK
// I2C USER
#define PB7 14 // SDA
#define PB6 15 // SCL
// SPI
#define PA4 16 // SPI_CS
#define PA5 17 // SPI_SCK
#define PA6 18 // SPI_MISO
#define PA7 19 // SPI_MOSI
// JTAG
#define PA13 20 // JTAG_TMS/SWDIO
#define PA14 21 // JTAG_TCK/SWCLK
#define PB3 22 // JTAG_TDO/SWO
// SDCARD
#define PC8 23 // SDIO_D0
#define PC9 24 // SDIO_D1
#define PA15 25 // SD_CARD_DETECT
#define PC10 26 // SDIO_D2
#define PC11 27 // SDIO_D3
#define PC12 28 // SDIO_CK
#define PD2 29 // SDIO_CMD
// OTG
#define PA11 30 //OTG_DM
#define PA12 31 //OTG_DP
// IR/PROBE
#define PD1 32 //IR_OUT
#define PC1 33 //IR_ON
// USER_PINS
#define PD7 34 // USER3
#define PB9 35 // USER1
#define PE0 36 // USER2
#define PB4 37 // USER4
// USERKET
#define PE7 38 // USER_BUTTON
// ENDSTOPS
#define PD8 39 // X_STOP
#define PD9 40 // Y_STOP
#define PD10 41 // Z_STOP
#define PD11 42 // U_STOP
#define PA8 43 // V_STOP
#define PD0 44 // W_STOP
// HEATERS
#define PD13 45 // BED_HEAT_2
#define PD14 46 // BED_HEAT_1
#define PD15 47 // BED_HEAT_3
#define PC7 48 // E1_HEAT_PWM
#define PB0 49 // E2_HEAT_PWM
#define PB1 50 // E3_HEAT_PWM
// THERMISTOR
#define PC2 51 // BED_THERMISTOR_1
#define PC3 52 // BED_THERMISTOR_2
#define PA3 53 // BED_THERMISTOR_3
#define PA0 54 // E1_THERMISTOR
#define PA1 55 // E2_THERMISTOR
#define PA2 56 // E3_THERMISTOR
// FANS
#define PC4 57 // E1_FAN
#define PC5 58 // E2_FAN
#define PE8 59 // E3_FAN
// X_MOTOR
#define PE13 60 // X_RESET
#define PE14 61 // X_PWM
#define PE15 62 // X_DIR
// Y_MOTOR
#define PE10 63 // Y_RESET
#define PB10 64 // Y_PWM
#define PE9 65 // Y_DIR
// Z_MOTOR
#define PC15 66 // Z_RESET
#define PC6 67 // Z_PWM
#define PC0 68 // Z_DIR
// E1_MOTOR
#define PC14 69 // E1_RESET
#define PC13 70 // E1_DIR
#define PD12 71 // E1_PWM
// E2_MOTOR
#define PE4 72 // E2_RESET
#define PE5 73 // E2_PWM
#define PE6 74 // E2_DIR
// E3_MOTOR
#define PE3 75 // E3_RESET
#define PE2 76 // E3_DIR
#define PB8 77 // E3_PWM
// This must be a literal
#define NUM_DIGITAL_PINS 78
// This must be a literal with a value less than or equal to to MAX_ANALOG_INPUTS
#define NUM_ANALOG_INPUTS 6
#define NUM_ANALOG_FIRST 51
// On-board LED pin number
#define LED_BUILTIN PE1
#define LED_GREEN LED_BUILTIN
// On-board user button
#define USER_BTN PE7
// UART Definitions
#define SERIAL_UART_INSTANCE 1 // Connected to ST-Link
//#define SERIAL_UART_INSTANCE 2 // Connected to WIFI
// Default pin used for 'Serial' instance (ex: ST-Link)
// Mandatory for Firmata
#if SERIAL_UART_INSTANCE == 1 // ST-Link & J23
#define PIN_SERIAL_RX PA10
#define PIN_SERIAL_TX PA9
#elif SERIAL_UART_INSTANCE == 2 // WIFI interface
#define PIN_SERIAL2_RX PD6
#define PIN_SERIAL2_TX PD5
#else
#error "Invalid setting for SERIAL_UART_INSTANCE."
#endif
// Timer Definitions
#define TIMER_SERVO TIM4 // TIMER_SERVO must be defined in this file
#define TIMER_TONE TIM5 // TIMER_TONE must be defined in this file
/* SD detect signal */
/*
* By default, R67 is not provided, so SD card detect is not used.
* Note: SD CD (pin 16 of expansion connector J23) can be connected
* to GND in order to be able to use SD_DETECT_PIN
*/
/*#define SD_DETECT_PIN PA15*/
/* HAL configuration */
#define HSE_VALUE 25000000U
/* Extra HAL modules */
#define HAL_SD_MODULE_ENABLED
#endif
#ifdef __cplusplus
} // extern "C"
#endif
/*----------------------------------------------------------------------------
* Arduino objects - C++ only
*----------------------------------------------------------------------------*/
#ifdef __cplusplus
// These serial port names are intended to allow libraries and architecture-neutral
// sketches to automatically default to the correct port name for a particular type
// of use. For example, a GPS module would normally connect to SERIAL_PORT_HARDWARE_OPEN,
// the first hardware serial port whose RX/TX pins are not dedicated to another use.
//
// SERIAL_PORT_MONITOR Port which normally prints to the Arduino Serial Monitor
//
// SERIAL_PORT_USBVIRTUAL Port which is USB virtual serial
//
// SERIAL_PORT_LINUXBRIDGE Port which connects to a Linux system via Bridge library
//
// SERIAL_PORT_HARDWARE Hardware serial port, physical RX & TX pins.
//
// SERIAL_PORT_HARDWARE_OPEN Hardware serial ports which are open for use. Their RX & TX
// pins are NOT connected to anything by default.
#define SERIAL_PORT_MONITOR Serial
#define SERIAL_PORT_HARDWARE Serial1
#endif
#endif // _VARIANT_ARDUINO_STM32_
// PA0 54 // E1_THERMISTOR
// PA1 55 // E2_THERMISTOR
// PA2 56 // E3_THERMISTOR
// PA3 53 // BED_THERMISTOR_3
// PA4 16 // SPI_CS
// PA5 17 // SPI_SCK
// PA6 18 // SPI_MISO
// PA7 19 // SPI_MOSI
// PA8 43 // V_STOP
// PA9 0 //TX
// PA10 1 //RX
// PA11 30 //OTG_DM
// PA12 31 //OTG_DP
// PA13 20 // JTAG_TMS/SWDIO
// PA14 21 // JTAG_TCK/SWCLK
// PA15 25 // SD_CARD_DETECT
// PB0 49 // E2_HEAT_PWM
// PB1 50 // E3_HEAT_PWM
// PB3 22 // JTAG_TDO/SWO
// PB4 37 // USER4
// PB5 6 // WIFI_WAKEUP
// PB6 15 // SCL
// PB7 14 // SDA
// PB8 77 // E3_PWM
// PB9 35 // USER1
// PB10 64 // Y_PWM
// PB12 10 // SPI_CS
// PB13 13 // SPI_SCK
// PB14 12 // SPI_MISO
// PB15 11 // SPI_MOSI
// PC0 68 // Z_DIR
// PC1 33 //IR_ON
// PC2 51 // BED_THERMISTOR_1
// PC3 52 // BED_THERMISTOR_2
// PC4 57 // E1_FAN
// PC5 58 // E2_FAN
// PC6 67 // Z_PWM
// PC7 48 // E1_HEAT_PWM
// PC8 23 // SDIO_D0
// PC9 24 // SDIO_D1
// PC10 26 // SDIO_D2
// PC11 27 // SDIO_D3
// PC12 28 // SDIO_CK
// PC13 70 // E1_DIR
// PC14 69 // E1_RESET
// PC15 66 // Z_RESET
// PD0 44 // W_STOP
// PD1 32 //IR_OUT
// PD2 29 // SDIO_CMD
// PD3 2 // CTS
// PD4 3 // RTS
// PD5 4 // TX
// PD6 5 // RX
// PD7 34 // USER3
// PD8 39 // X_STOP
// PD9 40 // Y_STOP
// PD10 41 // Z_STOP
// PD11 42 // U_STOP
// PD12 71 // E1_PWM
// PD13 45 // BED_HEAT_2
// PD14 46 // BED_HEAT_1
// PD15 47 // BED_HEAT_3
// PE0 36 // USER2
// PE1 9 // STATUS_LED
// PE2 76 // E3_DIR
// PE3 75 // E3_RESET
// PE4 72 // E2_RESET
// PE5 73 // E2_PWM
// PE6 74 // E2_DIR
// PE7 38 // USER_BUTTON
// PE8 59 // E3_FAN
// PE9 65 // Y_DIR
// PE10 63 // Y_RESET
// PE11 7 // WIFI_RESET
// PE12 8 // WIFI_BOOT
// PE13 60 // X_RESET
// PE14 61 // X_PWM
// PE15 62 // X_DIR

View File

@ -18,15 +18,11 @@ exec_test $1 $2 "FYSETC F6 1.3 with DGUS" "$3"
# Delta Config (generic) + UBL + ALLEN_KEY + EEPROM_SETTINGS + OLED_PANEL_TINYBOY2
#
use_example_configs delta/generic
opt_set MOTHERBOARD BOARD_FYSETC_F6_13 \
LCD_LANGUAGE ko_KR \
X_DRIVER_TYPE L6470 Y_DRIVER_TYPE L6470 Z_DRIVER_TYPE L6470 \
L6470_CHAIN_SCK_PIN 53 L6470_CHAIN_MISO_PIN 49 L6470_CHAIN_MOSI_PIN 40 L6470_CHAIN_SS_PIN 42 \
'ENABLE_RESET_L64XX_CHIPS(V)' NOOP
opt_set MOTHERBOARD BOARD_FYSETC_F6_13 LCD_LANGUAGE ko_KR
opt_enable RESTORE_LEVELING_AFTER_G28 EEPROM_SETTINGS EEPROM_CHITCHAT \
Z_PROBE_ALLEN_KEY AUTO_BED_LEVELING_UBL UBL_MESH_WIZARD \
OLED_PANEL_TINYBOY2 MESH_EDIT_GFX_OVERLAY DELTA_CALIBRATION_MENU
exec_test $1 $2 "DELTA, RAMPS, L6470, UBL, Allen Key, EEPROM, OLED_PANEL_TINYBOY2..." "$3"
exec_test $1 $2 "DELTA, FYSETC F6 1.3, UBL, Allen Key, EEPROM, OLED_PANEL_TINYBOY2..." "$3"
#
# Test mixed TMC config

View File

@ -1,15 +0,0 @@
#!/usr/bin/env bash
#
# Build tests for STM32F401VE_STEVAL
#
# exit on first failure
set -e
# Build examples
restore_configs
opt_set MOTHERBOARD BOARD_STEVAL_3DP001V1 SERIAL_PORT -1
exec_test $1 $2 "STM32F401VE_STEVAL Default Config" "$3"
# cleanup
restore_configs

View File

@ -26,8 +26,6 @@ HAS_MOTOR_CURRENT_I2C = SlowSoftI2CMaster
src_filter=+<src/feature/digipot>
HAS_TMC26X = TMC26XStepper=https://github.com/MarlinFirmware/TMC26XStepper/archive/master.zip
src_filter=+<src/module/stepper/TMC26X.cpp>
HAS_L64XX = Arduino-L6470@0.8.0
src_filter=+<src/libs/L64XX> +<src/module/stepper/L64xx.cpp> +<src/gcode/feature/L6470> +<src/HAL/shared/HAL_spi_L6470.cpp>
LIB_INTERNAL_MAX31865 = src_filter=+<src/libs/MAX31865.cpp>
NEOPIXEL_LED = adafruit/Adafruit NeoPixel@~1.8.0
src_filter=+<src/feature/leds/neopixel.cpp>

View File

@ -28,17 +28,6 @@ board = armed_v1
build_flags = ${common_stm32.build_flags}
-O2 -ffreestanding -fsigned-char -fno-move-loop-invariants -fno-strict-aliasing
#
# STM32F401VE
# 'STEVAL-3DP001V1' STM32F401VE board - https://www.st.com/en/evaluation-tools/steval-3dp001v1.html
#
[env:STM32F401VE_STEVAL]
extends = stm32_variant
board = marlin_STEVAL_STM32F401VE
build_flags = ${stm32_variant.build_flags}
-DSTM32F401xE -DDISABLE_GENERIC_SERIALUSB
-DUSBD_USE_CDC_COMPOSITE -DUSE_USB_FS
#
# STM32F401RC
#