diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 1da43df24c23..777f9a534bf3 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -706,7 +706,7 @@ * Enable if your probe or endstops falsely trigger due to noise. * * - Higher values may affect repeatability or accuracy of some bed probes. - * - To fix noise install a 100nF ceramic capacitor inline with the switch. + * - To fix noise install a 100nF ceramic capacitor in parallel with the switch. * - This feature is not required for common micro-switches mounted on PCBs * based on the Makerbot design, which already have the 100nF capacitor. * diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 25bd3391697e..16fe3824f0b4 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -770,7 +770,7 @@ //#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated // Minimum time that a segment needs to take if the buffer is emptied -#define DEFAULT_MINSEGMENTTIME 20000 // (ms) +#define DEFAULT_MINSEGMENTTIME 20000 // (µs) // Slow down the machine if the look ahead buffer is (by default) half full. // Increase the slowdown divisor for larger buffer sizes. @@ -1381,7 +1381,6 @@ //#define AO_EXP2_PINMAP // AlephObjects CLCD UI EXP2 mapping //#define CR10_TFT_PINMAP // Rudolph Riedel's CR10 pin mapping //#define S6_TFT_PINMAP // FYSETC S6 pin mapping - //#define CHEETAH_TFT_PINMAP // FYSETC Cheetah pin mapping //#define E3_EXP1_PINMAP // E3 type boards (SKR E3/DIP, and Stock boards) EXP1 pin mapping //#define GENERIC_EXP2_PINMAP // GENERIC EXP2 pin mapping @@ -1663,6 +1662,16 @@ // Support for G5 with XYZE destination and IJPQ offsets. Requires ~2666 bytes. //#define BEZIER_CURVE_SUPPORT +/** + * Direct Stepping + * + * Comparable to the method used by Klipper, G6 direct stepping significantly + * reduces motion calculations, increases top printing speeds, and results in + * less step aliasing by calculating all motions in advance. + * Preparing your G-code: https://github.com/colinrgodsey/step-daemon + */ +//#define DIRECT_STEPPING + /** * G38 Probe Target * @@ -1731,14 +1740,16 @@ //================================= Buffers ================================= //=========================================================================== -// @section hidden +// @section motion -// The number of linear motions that can be in the plan at any give time. -// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering. -#if ENABLED(SDSUPPORT) - #define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller +// The number of lineear moves that can be in the planner at once. +// The value of BLOCK_BUFFER_SIZE must be a power of 2 (e.g. 8, 16, 32) +#if BOTH(SDSUPPORT, DIRECT_STEPPING) + #define BLOCK_BUFFER_SIZE 8 +#elif ENABLED(SDSUPPORT) + #define BLOCK_BUFFER_SIZE 16 #else - #define BLOCK_BUFFER_SIZE 16 // maximize block buffer + #define BLOCK_BUFFER_SIZE 16 #endif // @section serial @@ -1781,10 +1792,14 @@ //#define SERIAL_STATS_DROPPED_RX #endif -// Enable an emergency-command parser to intercept certain commands as they -// enter the serial receive buffer, so they cannot be blocked. -// Currently handles M108, M112, M410 -// Does not work on boards using AT90USB (USBCON) processors! +/** + * Emergency Command Parser + * + * Add a low-level parser to intercept certain commands as they + * enter the serial receive buffer, so they cannot be blocked. + * Currently handles M108, M112, M410, M876 + * NOTE: Not yet implemented for all platforms. + */ //#define EMERGENCY_PARSER // Bad Serial-connections can miss a received command by sending an 'ok' diff --git a/Marlin/Version.h b/Marlin/Version.h index c2788603fa38..2d4a8e9b5c03 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -34,7 +34,7 @@ * Verbose version identifier which should contain a reference to the location * from where the binary was downloaded or the source code was compiled. */ -//#define DETAILED_BUILD_VERSION SHORT_BUILD_VERSION " (Github)" +//#define DETAILED_BUILD_VERSION SHORT_BUILD_VERSION /** * The STRING_DISTRIBUTION_DATE represents when the binary file was built, diff --git a/Marlin/src/HAL/AVR/MarlinSerial.cpp b/Marlin/src/HAL/AVR/MarlinSerial.cpp index 350d0f302d19..c544b905f36c 100644 --- a/Marlin/src/HAL/AVR/MarlinSerial.cpp +++ b/Marlin/src/HAL/AVR/MarlinSerial.cpp @@ -43,6 +43,10 @@ #include "MarlinSerial.h" #include "../../MarlinCore.h" + #if ENABLED(DIRECT_STEPPING) + #include "../../feature/direct_stepping.h" + #endif + template typename MarlinSerial::ring_buffer_r MarlinSerial::rx_buffer = { 0, 0, { 0 } }; template typename MarlinSerial::ring_buffer_t MarlinSerial::tx_buffer = { 0 }; template bool MarlinSerial::_written = false; @@ -131,6 +135,18 @@ static EmergencyParser::State emergency_state; // = EP_RESET + // This must read the R_UCSRA register before reading the received byte to detect error causes + if (Cfg::DROPPED_RX && B_DOR && !++rx_dropped_bytes) --rx_dropped_bytes; + if (Cfg::RX_OVERRUNS && B_DOR && !++rx_buffer_overruns) --rx_buffer_overruns; + if (Cfg::RX_FRAMING_ERRORS && B_FE && !++rx_framing_errors) --rx_framing_errors; + + // Read the character from the USART + uint8_t c = R_UDR; + + #if ENABLED(DIRECT_STEPPING) + if (page_manager.maybe_store_rxd_char(c)) return; + #endif + // Get the tail - Nothing can alter its value while this ISR is executing, but there's // a chance that this ISR interrupted the main process while it was updating the index. // The backup mechanism ensures the correct value is always returned. @@ -142,14 +158,6 @@ // Get the next element ring_buffer_pos_t i = (ring_buffer_pos_t)(h + 1) & (ring_buffer_pos_t)(Cfg::RX_SIZE - 1); - // This must read the R_UCSRA register before reading the received byte to detect error causes - if (Cfg::DROPPED_RX && B_DOR && !++rx_dropped_bytes) --rx_dropped_bytes; - if (Cfg::RX_OVERRUNS && B_DOR && !++rx_buffer_overruns) --rx_buffer_overruns; - if (Cfg::RX_FRAMING_ERRORS && B_FE && !++rx_framing_errors) --rx_framing_errors; - - // Read the character from the USART - uint8_t c = R_UDR; - if (Cfg::EMERGENCYPARSER) emergency_parser.update(emergency_state, c); // If the character is to be stored at the index just before the tail diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 73f936bc05ec..2434df0ad493 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -59,6 +59,10 @@ #include "gcode/parser.h" #include "gcode/queue.h" +#if ENABLED(DIRECT_STEPPING) + #include "feature/direct_stepping.h" +#endif + #if ENABLED(TOUCH_BUTTONS) #include "feature/touch/xpt2046.h" #endif @@ -713,6 +717,9 @@ void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep/*=false*/)) { // Handle Joystick jogging TERN_(POLL_JOG, joystick.inject_jog_moves()); + + // Direct Stepping + TERN_(DIRECT_STEPPING, page_manager.write_responses()); } /** @@ -1124,6 +1131,10 @@ void setup() { SETUP_RUN(max7219.init()); #endif + #if ENABLED(DIRECT_STEPPING) + SETUP_RUN(page_manager.init()); + #endif + marlin_state = MF_RUNNING; SETUP_LOG("setup() completed."); diff --git a/Marlin/src/core/language.h b/Marlin/src/core/language.h index d7b50a52ceff..bc81f78cd311 100644 --- a/Marlin/src/core/language.h +++ b/Marlin/src/core/language.h @@ -125,7 +125,7 @@ #define STR_INVALID_E_STEPPER "Invalid E stepper" #define STR_E_STEPPER_NOT_SPECIFIED "E stepper not specified" #define STR_INVALID_SOLENOID "Invalid solenoid" -#define STR_M115_REPORT "FIRMWARE_NAME:Marlin " DETAILED_BUILD_VERSION " SOURCE_CODE_URL:" SOURCE_CODE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" MACHINE_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" MACHINE_UUID +#define STR_M115_REPORT "FIRMWARE_NAME:Marlin " DETAILED_BUILD_VERSION " (" __DATE__ " " __TIME__ ") SOURCE_CODE_URL:" SOURCE_CODE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" MACHINE_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" MACHINE_UUID #define STR_COUNT_X " Count X:" #define STR_COUNT_A " Count A:" #define STR_WATCHDOG_FIRED "Watchdog timeout. Reset required." diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index edab6ae5bc44..ebcb9ebcfb89 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -102,7 +102,7 @@ #define SBI32(n,b) (n |= _BV32(b)) #define CBI32(n,b) (n &= ~_BV32(b)) -#define cu(x) ((x)*(x)*(x)) +#define cu(x) ({__typeof__(x) _x = (x); (_x)*(_x)*(_x);}) #define RADIANS(d) ((d)*float(M_PI)/180.0f) #define DEGREES(r) ((r)*180.0f/float(M_PI)) #define HYPOT2(x,y) (sq(x)+sq(y)) @@ -110,7 +110,7 @@ #define CIRCLE_AREA(R) (float(M_PI) * sq(float(R))) #define CIRCLE_CIRC(R) (2 * float(M_PI) * float(R)) -#define SIGN(a) ((a>0)-(a<0)) +#define SIGN(a) ({__typeof__(a) _a = (a); (_a>0)-(_a<0);}) #define IS_POWER_OF_2(x) ((x) && !((x) & ((x) - 1))) // Macros to constrain values @@ -130,8 +130,6 @@ #else - // Using GCC extensions, but Travis GCC version does not like it and gives - // "error: statement-expressions are not allowed outside functions nor in template-argument lists" #define NOLESS(v, n) \ do{ \ __typeof__(n) _n = (n); \ @@ -269,7 +267,7 @@ #define NEAR(x,y) NEAR_ZERO((x)-(y)) #define RECIPROCAL(x) (NEAR_ZERO(x) ? 0 : (1 / float(x))) -#define FIXFLOAT(f) (f + (f < 0 ? -0.00005f : 0.00005f)) +#define FIXFLOAT(f) ({__typeof__(f) _f = (f); _f + (_f < 0 ? -0.00005f : 0.00005f);}) // // Maths macros that can be overridden by HAL @@ -482,3 +480,14 @@ #define RREPEAT(N,OP) RREPEAT_S(0,N,OP) #define RREPEAT2_S(S,N,OP,V...) EVAL1024(_RREPEAT2(S,SUB##S(N),OP,V)) #define RREPEAT2(N,OP,V...) RREPEAT2_S(0,N,OP,V) + +// See https://github.com/swansontec/map-macro +#define MAP_OUT +#define MAP_END(...) +#define MAP_GET_END() 0, MAP_END +#define MAP_NEXT0(test, next, ...) next MAP_OUT +#define MAP_NEXT1(test, next) MAP_NEXT0 (test, next, 0) +#define MAP_NEXT(test, next) MAP_NEXT1 (MAP_GET_END test, next) +#define MAP0(f, x, peek, ...) f(x) MAP_NEXT (peek, MAP1) (f, peek, __VA_ARGS__) +#define MAP1(f, x, peek, ...) f(x) MAP_NEXT (peek, MAP0) (f, peek, __VA_ARGS__) +#define MAP(f, ...) EVAL512 (MAP1 (f, __VA_ARGS__, (), 0)) diff --git a/Marlin/src/feature/direct_stepping.cpp b/Marlin/src/feature/direct_stepping.cpp new file mode 100644 index 000000000000..7bed075b8762 --- /dev/null +++ b/Marlin/src/feature/direct_stepping.cpp @@ -0,0 +1,273 @@ +/** + * 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 . + * + */ +#include "../inc/MarlinConfigPre.h" + +#if ENABLED(DIRECT_STEPPING) + +#include "direct_stepping.h" + +#include "../MarlinCore.h" + +#define CHECK_PAGE(I, R) do{ \ + if (I >= sizeof(page_states) / sizeof(page_states[0])) { \ + fatal_error = true; \ + return R; \ + } \ +}while(0) + +#define CHECK_PAGE_STATE(I, R, S) do { \ + CHECK_PAGE(I, R); \ + if (page_states[I] != S) { \ + fatal_error = true; \ + return R; \ + } \ +}while(0) + +namespace DirectStepping { + + template + State SerialPageManager::state; + + template + volatile bool SerialPageManager::fatal_error; + + template + volatile PageState SerialPageManager::page_states[Cfg::NUM_PAGES]; + + template + volatile bool SerialPageManager::page_states_dirty; + + template + millis_t SerialPageManager::next_response; + + template + uint8_t SerialPageManager::pages[Cfg::NUM_PAGES][Cfg::PAGE_SIZE]; + + template + uint8_t SerialPageManager::checksum; + + template + typename Cfg::write_byte_idx_t SerialPageManager::write_byte_idx; + + template + typename Cfg::page_idx_t SerialPageManager::write_page_idx; + + template + typename Cfg::write_byte_idx_t SerialPageManager::write_page_size; + + template + void SerialPageManager::init() { + for (int i = 0 ; i < Cfg::NUM_PAGES ; i++) + page_states[i] = PageState::FREE; + + fatal_error = false; + next_response = 0; + state = State::NEWLINE; + + page_states_dirty = false; + + SERIAL_ECHOLNPGM("pages_ready"); + } + + template + FORCE_INLINE bool SerialPageManager::maybe_store_rxd_char(uint8_t c) { + switch (state) { + default: + case State::MONITOR: + switch (c) { + case '\n': + case '\r': + state = State::NEWLINE; + default: + return false; + } + case State::NEWLINE: + switch (c) { + case Cfg::CONTROL_CHAR: + state = State::ADDRESS; + return true; + case '\n': + case '\r': + state = State::NEWLINE; + return false; + default: + state = State::MONITOR; + return false; + } + case State::ADDRESS: + //TODO: 16 bit address, State::ADDRESS2 + write_page_idx = c; + write_byte_idx = 0; + checksum = 0; + + CHECK_PAGE(write_page_idx, true); + + if (page_states[write_page_idx] == PageState::FAIL) { + // Special case for fail + state = State::UNFAIL; + return true; + } + + set_page_state(write_page_idx, PageState::WRITING); + + state = Cfg::DIRECTIONAL ? State::COLLECT : State::SIZE; + + return true; + case State::SIZE: + // Zero means full page size + write_page_size = c; + state = State::COLLECT; + return true; + case State::COLLECT: + pages[write_page_idx][write_byte_idx++] = c; + checksum ^= c; + + // check if still collecting + if (Cfg::PAGE_SIZE == 256) { + // special case for 8-bit, check if rolled back to 0 + if (Cfg::DIRECTIONAL || !write_page_size) { // full 256 bytes + if (write_byte_idx) return true; + } else { + if (write_byte_idx < write_page_size) return true; + } + } else if (Cfg::DIRECTIONAL) { + if (write_byte_idx != Cfg::PAGE_SIZE) return true; + } else { + if (write_byte_idx < write_page_size) return true; + } + + state = State::CHECKSUM; + return true; + case State::CHECKSUM: { + const PageState page_state = (checksum == c) ? PageState::OK : PageState::FAIL; + set_page_state(write_page_idx, page_state); + state = State::MONITOR; + return true; + } + case State::UNFAIL: + if (c == 0) { + set_page_state(write_page_idx, PageState::FREE); + } else { + fatal_error = true; + } + state = State::MONITOR; + return true; + } + } + + template + void SerialPageManager::write_responses() { + if (fatal_error) { + kill(GET_TEXT(MSG_BAD_PAGE)); + return; + } + + // Runs on a set interval also, as responses may get lost. + if (next_response && next_response < millis()) { + page_states_dirty = true; + } + + if (!page_states_dirty) return; + + page_states_dirty = false; + next_response = millis() + Cfg::RESPONSE_INTERVAL_MS; + + SERIAL_ECHO(Cfg::CONTROL_CHAR); + constexpr int state_bits = 2; + constexpr int n_bytes = Cfg::NUM_PAGES >> state_bits; + volatile uint8_t bits_b[n_bytes] = { 0 }; + + for (page_idx_t i = 0 ; i < Cfg::NUM_PAGES ; i++) { + bits_b[i >> state_bits] |= page_states[i] << ((i * state_bits) & 0x7); + } + + uint8_t crc = 0; + for (uint8_t i = 0 ; i < n_bytes ; i++) { + crc ^= bits_b[i]; + SERIAL_ECHO(bits_b[i]); + } + + SERIAL_ECHO(crc); + SERIAL_EOL(); + } + + template + FORCE_INLINE void SerialPageManager::set_page_state(const page_idx_t page_idx, const PageState page_state) { + CHECK_PAGE(page_idx,); + + page_states[page_idx] = page_state; + page_states_dirty = true; + } + + template <> + FORCE_INLINE uint8_t *PageManager::get_page(const page_idx_t page_idx) { + CHECK_PAGE(page_idx, nullptr); + + return pages[page_idx]; + } + + template <> + FORCE_INLINE void PageManager::free_page(const page_idx_t page_idx) { + set_page_state(page_idx, PageState::FREE); + } + +}; + +DirectStepping::PageManager page_manager; + +const uint8_t segment_table[DirectStepping::Config::NUM_SEGMENTS][DirectStepping::Config::SEGMENT_STEPS] PROGMEM = { + + #if STEPPER_PAGE_FORMAT == SP_4x4D_128 + + { 1, 1, 1, 1, 1, 1, 1, 0 }, // 0 = -7 + { 1, 1, 1, 0, 1, 1, 1, 0 }, // 1 = -6 + { 0, 1, 1, 0, 1, 0, 1, 1 }, // 2 = -5 + { 0, 1, 0, 1, 0, 1, 0, 1 }, // 3 = -4 + { 0, 1, 0, 0, 1, 0, 0, 1 }, // 4 = -3 + { 0, 0, 1, 0, 0, 0, 1, 0 }, // 5 = -2 + { 0, 0, 0, 0, 1, 0, 0, 0 }, // 6 = -1 + { 0, 0, 0, 0, 0, 0, 0, 0 }, // 7 = 0 + { 0, 0, 0, 0, 1, 0, 0, 0 }, // 8 = 1 + { 0, 0, 1, 0, 0, 0, 1, 0 }, // 9 = 2 + { 0, 1, 0, 0, 1, 0, 0, 1 }, // 10 = 3 + { 0, 1, 0, 1, 0, 1, 0, 1 }, // 11 = 4 + { 0, 1, 1, 0, 1, 0, 1, 1 }, // 12 = 5 + { 1, 1, 1, 0, 1, 1, 1, 0 }, // 13 = 6 + { 1, 1, 1, 1, 1, 1, 1, 0 }, // 14 = 7 + { 0 } + + #elif STEPPER_PAGE_FORMAT == SP_4x2_256 + + { 0, 0, 0, 0 }, // 0 + { 0, 1, 0, 0 }, // 1 + { 1, 0, 1, 0 }, // 2 + { 1, 1, 1, 0 }, // 3 + + #elif STEPPER_PAGE_FORMAT == SP_4x1_512 + + {0} // Uncompressed format, table not used + + #endif + +}; + +#endif // DIRECT_STEPPING diff --git a/Marlin/src/feature/direct_stepping.h b/Marlin/src/feature/direct_stepping.h new file mode 100644 index 000000000000..4d12f83db766 --- /dev/null +++ b/Marlin/src/feature/direct_stepping.h @@ -0,0 +1,137 @@ +/** + * 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 . + * + */ +#pragma once + +#include "../inc/MarlinConfig.h" + +namespace DirectStepping { + + enum State : char { + MONITOR, NEWLINE, ADDRESS, SIZE, COLLECT, CHECKSUM, UNFAIL + }; + + enum PageState : uint8_t { + FREE, WRITING, OK, FAIL + }; + + // Static state used for stepping through direct stepping pages + struct page_step_state_t { + // Current page + uint8_t *page; + // Current segment + uint16_t segment_idx; + // Current steps within segment + uint8_t segment_steps; + // Segment delta + xyze_uint8_t sd; + // Block delta + xyze_int_t bd; + }; + + template + class SerialPageManager { + public: + + typedef typename Cfg::page_idx_t page_idx_t; + + static bool maybe_store_rxd_char(uint8_t c); + static void write_responses(); + + // common methods for page managers + static void init(); + static uint8_t *get_page(const page_idx_t page_idx); + static void free_page(const page_idx_t page_idx); + + protected: + + typedef typename Cfg::write_byte_idx_t write_byte_idx_t; + + static State state; + static volatile bool fatal_error; + + static volatile PageState page_states[Cfg::NUM_PAGES]; + static volatile bool page_states_dirty; + static millis_t next_response; + + static uint8_t pages[Cfg::NUM_PAGES][Cfg::PAGE_SIZE]; + static uint8_t checksum; + static write_byte_idx_t write_byte_idx; + static page_idx_t write_page_idx; + static write_byte_idx_t write_page_size; + + static void set_page_state(const page_idx_t page_idx, const PageState page_state); + }; + + template struct TypeSelector { typedef T type;} ; + template struct TypeSelector { typedef F type; }; + + template + struct config_t { + static constexpr char CONTROL_CHAR = '!'; + + static constexpr int NUM_PAGES = num_pages; + static constexpr int NUM_AXES = num_axes; + static constexpr int BITS_SEGMENT = bits_segment; + static constexpr int DIRECTIONAL = dir ? 1 : 0; + static constexpr int SEGMENTS = segments; + + static constexpr int RAW = (BITS_SEGMENT == 1) ? 1 : 0; + static constexpr int NUM_SEGMENTS = 1 << BITS_SEGMENT; + static constexpr int SEGMENT_STEPS = 1 << (BITS_SEGMENT - DIRECTIONAL - RAW); + static constexpr int TOTAL_STEPS = SEGMENT_STEPS * SEGMENTS; + static constexpr int PAGE_SIZE = (NUM_AXES * BITS_SEGMENT * SEGMENTS) / 8; + + static constexpr millis_t RESPONSE_INTERVAL_MS = 50; + + typedef typename TypeSelector<(PAGE_SIZE>256), uint16_t, uint8_t>::type write_byte_idx_t; + typedef typename TypeSelector<(NUM_PAGES>256), uint16_t, uint8_t>::type page_idx_t; + }; + + template + using SP_4x4D_128 = config_t; + + template + using SP_4x2_256 = config_t; + + template + using SP_4x1_512 = config_t; + + // configured types + typedef STEPPER_PAGE_FORMAT Config; + + template class PAGE_MANAGER; + typedef PAGE_MANAGER PageManager; +}; + +#define SP_4x4D_128 1 +//#define SP_4x4_128 2 +//#define SP_4x2D_256 3 +#define SP_4x2_256 4 +#define SP_4x1_512 5 + +typedef typename DirectStepping::Config::page_idx_t page_idx_t; + +// TODO: use config +typedef DirectStepping::page_step_state_t page_step_state_t; + +extern const uint8_t segment_table[DirectStepping::Config::NUM_SEGMENTS][DirectStepping::Config::SEGMENT_STEPS]; +extern DirectStepping::PageManager page_manager; diff --git a/Marlin/src/feature/host_actions.h b/Marlin/src/feature/host_actions.h index 07309274b0d4..81ef8227aebc 100644 --- a/Marlin/src/feature/host_actions.h +++ b/Marlin/src/feature/host_actions.h @@ -21,7 +21,8 @@ */ #pragma once -#include "../inc/MarlinConfig.h" +#include "../inc/MarlinConfigPre.h" +#include "../HAL/shared/Marduino.h" void host_action(PGM_P const pstr, const bool eol=true); diff --git a/Marlin/src/feature/spindle_laser.h b/Marlin/src/feature/spindle_laser.h index 0c2e569aa6f5..2e8639509833 100644 --- a/Marlin/src/feature/spindle_laser.h +++ b/Marlin/src/feature/spindle_laser.h @@ -137,7 +137,7 @@ class SpindleLaser { #if ENABLED(LASER_POWER_INLINE) // Force disengage planner power control - static inline void inline_disable() { planner.settings.laser.status = 0; planner.settings.laser.power = 0; isOn = false;} + static inline void inline_disable() { planner.laser.status = 0; planner.laser.power = 0; isOn = false;} // Inline modes of all other functions; all enable planner inline power control static inline void inline_enabled(const bool enable) { enable ? inline_power(SPEED_POWER_STARTUP) : inline_ocr_power(0); } @@ -146,8 +146,8 @@ class SpindleLaser { #if ENABLED(SPINDLE_LASER_PWM) inline_ocr_power(translate_power(pwr)); #else - planner.settings.laser.status = enabled(pwr) ? 0x03 : 0x01; - planner.settings.laser.power = pwr; + planner.laser.status = enabled(pwr) ? 0x03 : 0x01; + planner.laser.power = pwr; #endif } @@ -155,8 +155,8 @@ class SpindleLaser { #if ENABLED(SPINDLE_LASER_PWM) static inline void inline_ocr_power(const uint8_t pwr) { - planner.settings.laser.status = pwr ? 0x03 : 0x01; - planner.settings.laser.power = pwr; + planner.laser.status = pwr ? 0x03 : 0x01; + planner.laser.power = pwr; } #endif #endif diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index ac5a60ed9364..14f2eea7d996 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -261,6 +261,10 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 5: G5(); break; // G5: Cubic B_spline #endif + #if ENABLED(DIRECT_STEPPING) + case 6: G6(); break; // G6: Direct Stepper Move + #endif + #if ENABLED(FWRETRACT) case 10: G10(); break; // G10: Retract / Swap Retract case 11: G11(); break; // G11: Recover / Swap Recover diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 92292f609ba3..573ef0f6250f 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -402,6 +402,8 @@ class GcodeSuite { TERN_(BEZIER_CURVE_SUPPORT, static void G5()); + TERN_(DIRECT_STEPPING, static void G6()); + #if ENABLED(FWRETRACT) static void G10(); static void G11(); diff --git a/Marlin/src/gcode/geometry/G92.cpp b/Marlin/src/gcode/geometry/G92.cpp index 91a746dd7610..16717de14de6 100644 --- a/Marlin/src/gcode/geometry/G92.cpp +++ b/Marlin/src/gcode/geometry/G92.cpp @@ -99,5 +99,7 @@ void GcodeSuite::G92() { if (sync_XYZ) sync_plan_position(); else if (sync_E) sync_plan_position_e(); - report_current_position(); + #if DISABLED(DIRECT_STEPPING) + report_current_position(); + #endif } diff --git a/Marlin/src/gcode/host/M114.cpp b/Marlin/src/gcode/host/M114.cpp index 2e6fff71821d..8a31f248bf06 100644 --- a/Marlin/src/gcode/host/M114.cpp +++ b/Marlin/src/gcode/host/M114.cpp @@ -38,11 +38,12 @@ char str[12]; LOOP_L_N(a, n) { SERIAL_CHAR(' ', axis_codes[a], ':'); + if (pos[a] >= 0) SERIAL_CHAR(' '); SERIAL_ECHO(dtostrf(pos[a], 1, precision, str)); } SERIAL_EOL(); } - inline void report_xyz(const xyze_pos_t &pos) { report_xyze(pos, 3); } + inline void report_xyz(const xyze_pos_t &pos) { report_xyze(pos, XYZ); } void report_xyz(const xyz_pos_t &pos, const uint8_t precision=3) { char str[12]; diff --git a/Marlin/src/gcode/motion/G6.cpp b/Marlin/src/gcode/motion/G6.cpp new file mode 100644 index 000000000000..4405ff6b9cc1 --- /dev/null +++ b/Marlin/src/gcode/motion/G6.cpp @@ -0,0 +1,61 @@ +/** + * 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 . + * + */ +#include "../../inc/MarlinConfig.h" + +#if ENABLED(DIRECT_STEPPING) + +#include "../../feature/direct_stepping.h" + +#include "../gcode.h" +#include "../../module/planner.h" + +/** + * G6: Direct Stepper Move + */ +void GcodeSuite::G6() { + // TODO: feedrate support? + if (parser.seen('R')) + planner.last_page_step_rate = parser.value_ulong(); + + if (!DirectStepping::Config::DIRECTIONAL) { + if (parser.seen('X')) planner.last_page_dir.x = !!parser.value_byte(); + if (parser.seen('Y')) planner.last_page_dir.y = !!parser.value_byte(); + if (parser.seen('Z')) planner.last_page_dir.z = !!parser.value_byte(); + if (parser.seen('E')) planner.last_page_dir.e = !!parser.value_byte(); + } + + // No index means we just set the state + if (!parser.seen('I')) return; + + // No speed is set, can't schedule the move + if (!planner.last_page_step_rate) return; + + const page_idx_t page_idx = (page_idx_t) parser.value_ulong(); + + uint16_t num_steps = DirectStepping::Config::TOTAL_STEPS; + if (parser.seen('S')) num_steps = parser.value_ushort(); + + planner.buffer_page(page_idx, 0, num_steps); + reset_stepper_timeout(); +} + +#endif // DIRECT_STEPPING diff --git a/Marlin/src/gcode/queue.cpp b/Marlin/src/gcode/queue.cpp index 4d7d107ebd06..4b974113fb3f 100644 --- a/Marlin/src/gcode/queue.cpp +++ b/Marlin/src/gcode/queue.cpp @@ -216,13 +216,12 @@ bool GCodeQueue::process_injected_command() { gcode.process_parsed_command(); } - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wrestrict" - // Copy the next command into place - strcpy(injected_commands, &injected_commands[i + (c != '\0')]); - - #pragma GCC diagnostic pop + for ( + uint8_t d = 0, s = i + !!c; // dst, src + (injected_commands[d] = injected_commands[s]); // copy, exit if 0 + d++, s++ // next dst, src + ); return true; } diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 2ab3f426e2a0..47a94d00745e 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -570,7 +570,7 @@ #if defined(Z_PROBE_SERVO_NR) && Z_PROBE_SERVO_NR >= 0 #define HAS_Z_SERVO_PROBE 1 #endif -#if HAS_Z_SERVO_PROBE || EITHER(SWITCHING_EXTRUDER, SWITCHING_NOZZLE) +#if ANY(HAS_Z_SERVO_PROBE, SWITCHING_EXTRUDER, SWITCHING_NOZZLE) #define HAS_SERVO_ANGLES 1 #endif #if !HAS_SERVO_ANGLES @@ -584,7 +584,7 @@ #define HAS_BED_PROBE 1 #endif -#if HAS_BED_PROBE || EITHER(PROBE_MANUALLY, MESH_BED_LEVELING) +#if ANY(HAS_BED_PROBE, PROBE_MANUALLY, MESH_BED_LEVELING) #define PROBE_SELECTED 1 #endif @@ -682,7 +682,7 @@ #endif // This flag indicates some kind of jerk storage is needed -#if ENABLED(CLASSIC_JERK) || IS_KINEMATIC +#if EITHER(CLASSIC_JERK, IS_KINEMATIC) #define HAS_CLASSIC_JERK 1 #endif diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index 2009e7c9659b..70a13330384d 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -323,6 +323,18 @@ #endif #endif +#if ENABLED(DIRECT_STEPPING) + #ifndef STEPPER_PAGES + #define STEPPER_PAGES 16 + #endif + #ifndef STEPPER_PAGE_FORMAT + #define STEPPER_PAGE_FORMAT SP_4x2_256 + #endif + #ifndef PAGE_MANAGER + #define PAGE_MANAGER SerialPageManager + #endif +#endif + // // SD Card connection methods // Defined here so pins and sanity checks can use them diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index fe8778590aaa..7d5cb060b99d 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -1784,7 +1784,7 @@ #define HAS_AUTO_CHAMBER_FAN 1 #endif -#if HAS_AUTO_FAN_0 || HAS_AUTO_FAN_1 || HAS_AUTO_FAN_2 || HAS_AUTO_FAN_3 || HAS_AUTO_FAN_4 || HAS_AUTO_FAN_5 || HAS_AUTO_FAN_6 || HAS_AUTO_FAN_7 || HAS_AUTO_CHAMBER_FAN +#if ANY(HAS_AUTO_FAN_0, HAS_AUTO_FAN_1, HAS_AUTO_FAN_2, HAS_AUTO_FAN_3, HAS_AUTO_FAN_4, HAS_AUTO_FAN_5, HAS_AUTO_FAN_6, HAS_AUTO_FAN_7, HAS_AUTO_CHAMBER_FAN) #define HAS_AUTO_FAN 1 #endif #define _FANOVERLAP(A,B) (A##_AUTO_FAN_PIN == E##B##_AUTO_FAN_PIN) @@ -1892,13 +1892,13 @@ #define HAS_MOTOR_CURRENT_PWM 1 #endif -#if HAS_Z_MS_PINS || HAS_Z2_MS_PINS || HAS_Z3_MS_PINS || HAS_Z4_MS_PINS +#if ANY(HAS_Z_MS_PINS, HAS_Z2_MS_PINS, HAS_Z3_MS_PINS, HAS_Z4_MS_PINS) #define HAS_SOME_Z_MS_PINS 1 #endif -#if HAS_E0_MS_PINS || HAS_E1_MS_PINS || HAS_E2_MS_PINS || HAS_E3_MS_PINS || HAS_E4_MS_PINS || HAS_E5_MS_PINS || HAS_E6_MS_PINS || HAS_E7_MS_PINS +#if ANY(HAS_E0_MS_PINS, HAS_E1_MS_PINS, HAS_E2_MS_PINS, HAS_E3_MS_PINS, HAS_E4_MS_PINS, HAS_E5_MS_PINS, HAS_E6_MS_PINS, HAS_E7_MS_PINS) #define HAS_SOME_E_MS_PINS 1 #endif -#if HAS_X_MS_PINS || HAS_X2_MS_PINS || HAS_Y_MS_PINS || HAS_Y2_MS_PINS || HAS_SOME_Z_MICROSTEPS || HAS_SOME_E_MS_PINS +#if ANY(HAS_X_MS_PINS, HAS_X2_MS_PINS, HAS_Y_MS_PINS, HAS_Y2_MS_PINS, HAS_SOME_Z_MS_PINS, HAS_SOME_E_MS_PINS) #define HAS_MICROSTEPS 1 #endif diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 11cc7060d4ff..c8f8907e88b2 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -2923,3 +2923,12 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #if SAVED_POSITIONS > 256 #error "SAVED_POSITIONS must be an integer from 0 to 256." #endif + +/** + * Sanity checks for stepper chunk support + */ +#if ENABLED(DIRECT_STEPPING) + #if ENABLED(LIN_ADVANCE) + #error "DIRECT_STEPPING is incompatible with LIN_ADVANCE. Enable in external planner if possible." + #endif +#endif diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 83be7f72e696..84ae351cc4cd 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -33,7 +33,7 @@ * vendor name, download location, GitHub account, etc. */ #ifndef DETAILED_BUILD_VERSION - #define DETAILED_BUILD_VERSION SHORT_BUILD_VERSION " (GitHub)" + #define DETAILED_BUILD_VERSION SHORT_BUILD_VERSION #endif /** @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-05-11" + #define STRING_DISTRIBUTION_DATE "2020-05-13" #endif /** diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index 8c67ff10ab32..ee0b90bebf7b 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -597,15 +597,15 @@ void MarlinUI::draw_status_screen() { // Progress bar frame // - if (PAGE_CONTAINS(49, 52)) + if (PAGE_CONTAINS(PROGRESS_BAR_Y, PROGRESS_BAR_Y + 3)) u8g.drawFrame(PROGRESS_BAR_X, PROGRESS_BAR_Y, PROGRESS_BAR_WIDTH, 4); // // Progress bar solid part // - if (PAGE_CONTAINS(50, 51)) // 50-51 (or just 50) - u8g.drawBox(PROGRESS_BAR_X + 1, 50, progress_bar_solid_width, 2); + if (PAGE_CONTAINS(PROGRESS_BAR_Y + 1, PROGRESS_BAR_Y + 2)) + u8g.drawBox(PROGRESS_BAR_X + 1, PROGRESS_BAR_Y + 1, progress_bar_solid_width, 2); if (PAGE_CONTAINS(EXTRAS_BASELINE - INFO_FONT_ASCENT, EXTRAS_BASELINE - 1)) { diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h index 7476a1108da2..236ecf49c65d 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h @@ -163,18 +163,3 @@ #define CLCD_MOD_RESET BTN_EN1 #define CLCD_SPI_CS LCD_PINS_RS #endif - -#ifdef CHEETAH_TFT_PINMAP - #ifndef __MARLIN_FIRMWARE__ - #error "This pin mapping requires Marlin." - #endif - - #define CLCD_MOD_RESET BTN_EN1 - #define CLCD_SPI_CS LCD_PINS_RS - - #if ENABLED(CLCD_USE_SOFT_SPI) - #define CLCD_SOFT_SPI_MOSI LCD_PINS_ENABLE - #define CLCD_SOFT_SPI_MISO LCD_PINS_SCK - #define CLCD_SOFT_SPI_SCLK LCD_PINS_D4 - #endif -#endif diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index df27de57a569..3ee5bea6e410 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -577,6 +577,9 @@ namespace Language_en { PROGMEM Language_Str MSG_SNAKE = _UxGT("Sn4k3"); PROGMEM Language_Str MSG_MAZE = _UxGT("Maze"); + PROGMEM Language_Str MSG_BAD_PAGE = _UxGT("Bad page index"); + PROGMEM Language_Str MSG_BAD_PAGE_SPEED = _UxGT("Bad page speed"); + // // Filament Change screens show up to 3 lines on a 4-line display // ...or up to 2 lines on a 3-line display diff --git a/Marlin/src/lcd/language/language_hu.h b/Marlin/src/lcd/language/language_hu.h index e07dd4c64e58..da647de1bcbf 100644 --- a/Marlin/src/lcd/language/language_hu.h +++ b/Marlin/src/lcd/language/language_hu.h @@ -35,7 +35,7 @@ namespace Language_hu { using namespace Language_en; // A fordítás az örökölt Amerikai Angol (English) karakterláncokat használja. -namespace Language_hu { + constexpr uint8_t CHARSIZE = 2; PROGMEM Language_Str LANGUAGE = _UxGT("Magyar"); @@ -74,20 +74,20 @@ namespace Language_hu { PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Kezdöpont eltolás"); PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Eltolás beállítva."); PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Eredeti Be"); - PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Preheat ") PREHEAT_1_LABEL; - PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Preheat ") PREHEAT_1_LABEL " ~"; - PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("Preheat ") PREHEAT_1_LABEL _UxGT(" Fej"); - PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("Preheat ") PREHEAT_1_LABEL _UxGT(" Fej ~"); - PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("Preheat ") PREHEAT_1_LABEL _UxGT(" Mind"); - PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("Preheat ") PREHEAT_1_LABEL _UxGT(" Ágy"); - PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("Preheat ") PREHEAT_1_LABEL _UxGT(" Beáll"); - PROGMEM Language_Str MSG_PREHEAT_2 = _UxGT("Preheat ") PREHEAT_2_LABEL; - PROGMEM Language_Str MSG_PREHEAT_2_H = _UxGT("Preheat ") PREHEAT_2_LABEL " ~"; - PROGMEM Language_Str MSG_PREHEAT_2_END = _UxGT("Preheat ") PREHEAT_2_LABEL _UxGT(" Fej"); - PROGMEM Language_Str MSG_PREHEAT_2_END_E = _UxGT("Preheat ") PREHEAT_2_LABEL _UxGT(" Fej ~"); - PROGMEM Language_Str MSG_PREHEAT_2_ALL = _UxGT("Preheat ") PREHEAT_2_LABEL _UxGT(" Mind"); - PROGMEM Language_Str MSG_PREHEAT_2_BEDONLY = _UxGT("Preheat ") PREHEAT_2_LABEL _UxGT(" Ágy"); - PROGMEM Language_Str MSG_PREHEAT_2_SETTINGS = _UxGT("Preheat ") PREHEAT_2_LABEL _UxGT(" Beáll"); + PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Fütés ") PREHEAT_1_LABEL; + PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Fütés ") PREHEAT_1_LABEL " ~"; + PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("Fütés ") PREHEAT_1_LABEL _UxGT(" Fej"); + PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("Fütés ") PREHEAT_1_LABEL _UxGT(" Fej ~"); + PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("Fütés ") PREHEAT_1_LABEL _UxGT(" Mind"); + PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("Fütés ") PREHEAT_1_LABEL _UxGT(" Ágy"); + PROGMEM Language_Str MSG_PREHEAT_1_SETTINGS = _UxGT("Fütés ") PREHEAT_1_LABEL _UxGT(" Beáll"); + PROGMEM Language_Str MSG_PREHEAT_2 = _UxGT("Fütés ") PREHEAT_2_LABEL; + PROGMEM Language_Str MSG_PREHEAT_2_H = _UxGT("Fütés ") PREHEAT_2_LABEL " ~"; + PROGMEM Language_Str MSG_PREHEAT_2_END = _UxGT("Fütés ") PREHEAT_2_LABEL _UxGT(" Fej"); + PROGMEM Language_Str MSG_PREHEAT_2_END_E = _UxGT("Fütés ") PREHEAT_2_LABEL _UxGT(" Fej ~"); + PROGMEM Language_Str MSG_PREHEAT_2_ALL = _UxGT("Fütés ") PREHEAT_2_LABEL _UxGT(" Mind"); + PROGMEM Language_Str MSG_PREHEAT_2_BEDONLY = _UxGT("Fütés ") PREHEAT_2_LABEL _UxGT(" Ágy"); + PROGMEM Language_Str MSG_PREHEAT_2_SETTINGS = _UxGT("Fütés ") PREHEAT_2_LABEL _UxGT(" Beáll"); PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Egyedi Elömelegítés"); PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Visszahütés"); PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Frekvencia"); @@ -208,7 +208,7 @@ namespace Language_hu { PROGMEM Language_Str MSG_LED_CONTROL = _UxGT("LED Vezérlés"); PROGMEM Language_Str MSG_LEDS = _UxGT("Világítás"); - PROGMEM Language_Str MSG_LED_PRESETS = _UxGT("Beállított Fény"); + PROGMEM Language_Str MSG_LED_PRESETS = _UxGT("Beállított Színek"); PROGMEM Language_Str MSG_SET_LEDS_RED = _UxGT("Piros"); PROGMEM Language_Str MSG_SET_LEDS_ORANGE = _UxGT("Narancs"); PROGMEM Language_Str MSG_SET_LEDS_YELLOW = _UxGT("Sárga"); @@ -218,7 +218,7 @@ namespace Language_hu { PROGMEM Language_Str MSG_SET_LEDS_VIOLET = _UxGT("Viola"); PROGMEM Language_Str MSG_SET_LEDS_WHITE = _UxGT("Fehér"); PROGMEM Language_Str MSG_SET_LEDS_DEFAULT = _UxGT("Alapérték"); - PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Egyéni Fény"); + PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Egyéni Szín"); PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("Piros Intenzitás"); PROGMEM Language_Str MSG_INTENSITY_G = _UxGT("Zöld Intenzitás"); PROGMEM Language_Str MSG_INTENSITY_B = _UxGT("Kék Intenzitás"); @@ -258,14 +258,18 @@ namespace Language_hu { PROGMEM Language_Str MSG_FLOW = _UxGT("Folyás"); PROGMEM Language_Str MSG_FLOW_N = _UxGT("Folyás ~"); PROGMEM Language_Str MSG_CONTROL = _UxGT("Konfiguráció"); - PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); - PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); - PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Tény"); + PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Minimum"); + PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Maximum"); + PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Tényezö"); PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Automata Höfok"); PROGMEM Language_Str MSG_LCD_ON = _UxGT("Be"); PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Ki"); PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("PID Hangolás"); PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("PID Hangolás *"); + PROGMEM Language_Str MSG_PID_AUTOTUNE_DONE = _UxGT("PID hangolás kész"); + PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Hangolási hiba. Rossz Adagoló."); + PROGMEM Language_Str MSG_PID_TEMP_TOO_HIGH = _UxGT("Hangolási hiba. Magas hömérséklet."); + PROGMEM Language_Str MSG_PID_TIMEOUT = _UxGT("Hangolási hiba! Idötúllépés."); PROGMEM Language_Str MSG_PID_P = _UxGT("PID-P"); PROGMEM Language_Str MSG_PID_P_E = _UxGT("PID-P *"); PROGMEM Language_Str MSG_PID_I = _UxGT("PID-I"); @@ -280,10 +284,10 @@ namespace Language_hu { PROGMEM Language_Str MSG_SELECT_E = _UxGT("Kiválaszt *"); PROGMEM Language_Str MSG_ACC = _UxGT("Gyorsítás"); PROGMEM Language_Str MSG_JERK = _UxGT("Rántás"); - PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-Jerk"); - PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-Jerk"); - PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-Jerk"); - PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve-Rántás"); + PROGMEM Language_Str MSG_VA_JERK = LCD_STR_A _UxGT(" Ránt. Seb."); + PROGMEM Language_Str MSG_VB_JERK = LCD_STR_B _UxGT(" Ránt. Seb."); + PROGMEM Language_Str MSG_VC_JERK = LCD_STR_C _UxGT(" Ránt. Seb."); + PROGMEM Language_Str MSG_VE_JERK = _UxGT("E Ránt. Seb."); PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Csomopont Eltérés"); PROGMEM Language_Str MSG_VELOCITY = _UxGT("Sebesség"); PROGMEM Language_Str MSG_VMAX_A = _UxGT("Max Sebesség ") LCD_STR_A; @@ -292,19 +296,21 @@ namespace Language_hu { PROGMEM Language_Str MSG_VMAX_E = _UxGT("Max Sebesség ") LCD_STR_E; PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Max Sebesség *"); PROGMEM Language_Str MSG_VMIN = _UxGT("Min Sebesség"); - PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("Min Utazó.Seb."); + PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("Min Utazó.seb."); PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Gyorsulás"); - PROGMEM Language_Str MSG_AMAX_A = _UxGT("Max Gyorsulás ") LCD_STR_A; - PROGMEM Language_Str MSG_AMAX_B = _UxGT("Max Gyorsulás ") LCD_STR_B; - PROGMEM Language_Str MSG_AMAX_C = _UxGT("Max Gyorsulás ") LCD_STR_C; - PROGMEM Language_Str MSG_AMAX_E = _UxGT("Max Gyorsulás ") LCD_STR_E; + PROGMEM Language_Str MSG_AMAX_A = _UxGT("Max Gyors. ") LCD_STR_A; + PROGMEM Language_Str MSG_AMAX_B = _UxGT("Max Gyors. ") LCD_STR_B; + PROGMEM Language_Str MSG_AMAX_C = _UxGT("Max Gyors. ") LCD_STR_C; + PROGMEM Language_Str MSG_AMAX_E = _UxGT("Max Gyors. ") LCD_STR_E; PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Max Gyorsulás *"); - PROGMEM Language_Str MSG_A_RETRACT = _UxGT("Szál visszahúzás"); + PROGMEM Language_Str MSG_A_RETRACT = _UxGT("Visszahúzás"); PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("Utazás"); + PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("Max Frekvencia"); + PROGMEM Language_Str MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Min Elötolás"); PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Lépés/mm"); - PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT("lépés/mm"); - PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT("lépés/mm"); - PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT("lépés/mm"); + PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" lépés/mm"); + PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" lépés/mm"); + PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" lépés/mm"); PROGMEM Language_Str MSG_E_STEPS = _UxGT("E lépés/mm"); PROGMEM Language_Str MSG_EN_STEPS = _UxGT("*lépés/mm"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Höfok"); @@ -318,18 +324,18 @@ namespace Language_hu { PROGMEM Language_Str MSG_ADVANCE_K = _UxGT("Haladó K"); PROGMEM Language_Str MSG_ADVANCE_K_E = _UxGT("Haladó K *"); PROGMEM Language_Str MSG_CONTRAST = _UxGT("LCD kontraszt"); - PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Tárolás EEPROM"); + PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Mentés EEPROM"); PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Betöltés EEPROM"); PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Alapértelmezett"); PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("EEPROM Inicializálás"); - PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("Err: EEPROM CRC"); - PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("Err: EEPROM Index"); - PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("Err: EEPROM Verzió"); + PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("Hiba: EEPROM CRC"); + PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("Hiba: EEPROM Index"); + PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("Hiba: EEPROM Verzió"); PROGMEM Language_Str MSG_SETTINGS_STORED = _UxGT("Beállítások Mentve"); PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Tároló Frissítés"); PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Nyomtató Újraindítása"); PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Frissítés"); - PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Infó Képernyö"); + PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT(""); PROGMEM Language_Str MSG_PREPARE = _UxGT("Vezérlés"); PROGMEM Language_Str MSG_TUNE = _UxGT("Hangolás"); PROGMEM Language_Str MSG_START_PRINT = _UxGT("Nyomtatás Indítása"); @@ -371,11 +377,22 @@ namespace Language_hu { PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("S UnRet V"); PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("AutoVisszah."); PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("Visszahúzás Távolság"); + PROGMEM Language_Str MSG_FILAMENT_SWAP_EXTRA = _UxGT("Extra Csere"); PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Tisztítási Távolság"); PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Szerszámcsere"); PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Z Emelés"); - PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPD = _UxGT("Fösebesség"); - PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPD = _UxGT("Visszah. Sebesség"); + PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Fösebesség"); + PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Visszah. Sebesség"); + PROGMEM Language_Str MSG_FILAMENT_PARK_ENABLED = _UxGT("Fej Parkolás"); + PROGMEM Language_Str MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Visszahúzás Sebesség"); + PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("FAN Sebesség"); + PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_TIME = _UxGT("FAN idö"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_ON = _UxGT("Auto BE"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_OFF = _UxGT("Auto KI"); + PROGMEM Language_Str MSG_TOOL_MIGRATION = _UxGT("Szerszámcsere"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_AUTO = _UxGT("Automata Csere"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_END = _UxGT("Utolsó Adagoló"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_SWAP = _UxGT("Csere *"); PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Szál csere"); PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Szál csere *"); PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Szál betöltés"); @@ -462,10 +479,10 @@ namespace Language_hu { PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Bilineáris Szintezés"); PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Egységes Ágy Szintezés"); PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Háló Szintezés"); - PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Nyomtató Statisztika"); + PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Statisztikák"); PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Alaplap Infó"); PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Termisztorok"); - PROGMEM Language_Str MSG_INFO_EXTRUDERS = _UxGT("Extruderek"); + PROGMEM Language_Str MSG_INFO_EXTRUDERS = _UxGT("Adagolók"); PROGMEM Language_Str MSG_INFO_BAUDRATE = _UxGT("Átviteli sebesség"); PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Protokoll"); PROGMEM Language_Str MSG_INFO_RUNAWAY_OFF = _UxGT("Futáselemzés: KI"); @@ -593,7 +610,7 @@ namespace Language_hu { PROGMEM Language_Str MSG_TMC_HYBRID_THRS = _UxGT("Hibrid Küszöbérték"); PROGMEM Language_Str MSG_TMC_HOMING_THRS = _UxGT("Motoros Kezdöpont"); PROGMEM Language_Str MSG_TMC_STEPPING_MODE = _UxGT("Léptetö Mód"); - PROGMEM Language_Str MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop Aktív"); + PROGMEM Language_Str MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop Mód"); PROGMEM Language_Str MSG_SERVICE_RESET = _UxGT("Újraindítás"); PROGMEM Language_Str MSG_SERVICE_IN = _UxGT(" be:"); PROGMEM Language_Str MSG_BACKLASH = _UxGT("Holtjáték"); diff --git a/Marlin/src/lcd/menu/menu.cpp b/Marlin/src/lcd/menu/menu.cpp index dfd55ae682e3..9d406c1a3740 100644 --- a/Marlin/src/lcd/menu/menu.cpp +++ b/Marlin/src/lcd/menu/menu.cpp @@ -224,7 +224,7 @@ void MarlinUI::goto_screen(screenFunc_t screen, const uint16_t encoder/*=0*/, co if (on_status_screen()) doubleclick_expire_ms = millis() + DOUBLECLICK_MAX_INTERVAL; } - else if (on_status_screen() && currentScreen == menu_main && PENDING(millis(), doubleclick_expire_ms)) { + else if (screen == status_screen && currentScreen == menu_main && PENDING(millis(), doubleclick_expire_ms)) { if ( (ENABLED(BABYSTEP_WITHOUT_HOMING) || all_axes_known()) && (ENABLED(BABYSTEP_ALWAYS_AVAILABLE) || printer_busy()) ) screen = TERN(BABYSTEP_ZPROBE_OFFSET, lcd_babystep_zoffset, lcd_babystep_z); diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 7d23789df1f7..605848651091 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -128,6 +128,10 @@ uint8_t Planner::delay_before_delivering; // This counter delays delivery planner_settings_t Planner::settings; // Initialized by settings.load() +#if ENABLED(LASER_POWER_INLINE) + laser_state_t Planner::laser; // Current state for blocks +#endif + uint32_t Planner::max_acceleration_steps_per_s2[XYZE_N]; // (steps/s^2) Derived from mm_per_s2 float Planner::steps_to_mm[XYZE_N]; // (mm) Millimeters per step @@ -151,6 +155,11 @@ float Planner::steps_to_mm[XYZE_N]; // (mm) Millimeters per step uint8_t Planner::last_extruder = 0; // Respond to extruder change #endif +#if ENABLED(DIRECT_STEPPING) + uint32_t Planner::last_page_step_rate = 0; + xyze_bool_t Planner::last_page_dir{0}; +#endif + #if EXTRUDERS int16_t Planner::flow_percentage[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(100); // Extrusion factor for each extruder float Planner::e_factor[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(1.0f); // The flow percentage and volumetric multiplier combine to scale E movement @@ -235,6 +244,10 @@ void Planner::init() { TERN_(ABL_PLANAR, bed_level_matrix.set_to_identity()); clear_block_buffer(); delay_before_delivering = 0; + #if ENABLED(DIRECT_STEPPING) + last_page_step_rate = 0; + last_page_dir.reset(); + #endif } #if ENABLED(S_CURVE_ACCELERATION) @@ -906,7 +919,7 @@ void Planner::calculate_trapezoid_for_block(block_t* const block, const float &e streaming operating conditions. Use for planning optimizations by avoiding recomputing parts of the planner buffer that don't change with the addition of a new block, as describe above. In addition, this block can never be less than block_buffer_tail and will always be pushed forward and maintain - this requirement when encountered by the Planner::discard_current_block() routine during a cycle. + this requirement when encountered by the Planner::release_current_block() routine during a cycle. NOTE: Since the planner only computes on what's in the planner buffer, some motions with lots of short line segments, like G2/3 arcs or complex curves, may seem to move slow. This is because there simply isn't @@ -994,8 +1007,8 @@ void Planner::reverse_pass() { // Perform the reverse pass block_t *current = &block_buffer[block_index]; - // Only consider non sync blocks - if (!TEST(current->flag, BLOCK_BIT_SYNC_POSITION)) { + // Only consider non sync and page blocks + if (!TEST(current->flag, BLOCK_BIT_SYNC_POSITION) && !IS_PAGE(current)) { reverse_pass_kernel(current, next); next = current; } @@ -1089,8 +1102,8 @@ void Planner::forward_pass() { // Perform the forward pass block = &block_buffer[block_index]; - // Skip SYNC blocks - if (!TEST(block->flag, BLOCK_BIT_SYNC_POSITION)) { + // Skip SYNC and page blocks + if (!TEST(block->flag, BLOCK_BIT_SYNC_POSITION) && !IS_PAGE(block)) { // If there's no previous block or the previous block is not // BUSY (thus, modifiable) run the forward_pass_kernel. Otherwise, // the previous block became BUSY, so assume the current block's @@ -1139,8 +1152,8 @@ void Planner::recalculate_trapezoids() { next = &block_buffer[block_index]; - // Skip sync blocks - if (!TEST(next->flag, BLOCK_BIT_SYNC_POSITION)) { + // Skip sync and page blocks + if (!TEST(next->flag, BLOCK_BIT_SYNC_POSITION) && !IS_PAGE(next)) { next_entry_speed = SQRT(next->entry_speed_sqr); if (block) { @@ -1790,8 +1803,8 @@ bool Planner::_populate_block(block_t * const block, bool split_move, // Update block laser power #if ENABLED(LASER_POWER_INLINE) - block->laser.status = settings.laser.status; - block->laser.power = settings.laser.power; + block->laser.status = laser.status; + block->laser.power = laser.power; #endif // Number of steps for each axis @@ -2488,9 +2501,9 @@ bool Planner::_populate_block(block_t * const block, bool split_move, previous_safe_speed = safe_speed; #if HAS_JUNCTION_DEVIATION - vmax_junction_sqr = _MIN(vmax_junction_sqr, sq(vmax_junction)); + NOMORE(vmax_junction_sqr, sq(vmax_junction)); // Throttle down to max speed #else - vmax_junction_sqr = sq(vmax_junction); + vmax_junction_sqr = sq(vmax_junction); // Go up or down to the new speed #endif #endif // Classic Jerk Limiting @@ -2717,6 +2730,69 @@ bool Planner::buffer_line(const float &rx, const float &ry, const float &rz, con #endif } // buffer_line() +#if ENABLED(DIRECT_STEPPING) + + void Planner::buffer_page(const page_idx_t page_idx, const uint8_t extruder, const uint16_t num_steps) { + if (!last_page_step_rate) { + kill(GET_TEXT(MSG_BAD_PAGE_SPEED)); + return; + } + + uint8_t next_buffer_head; + block_t * const block = get_next_free_block(next_buffer_head); + + block->flag = BLOCK_FLAG_IS_PAGE; + + #if FAN_COUNT > 0 + FANS_LOOP(i) block->fan_speed[i] = thermalManager.fan_speed[i]; + #endif + + #if EXTRUDERS > 1 + block->extruder = extruder; + #endif + + block->page_idx = page_idx; + + block->step_event_count = num_steps; + block->initial_rate = + block->final_rate = + block->nominal_rate = last_page_step_rate; // steps/s + + block->accelerate_until = 0; + block->decelerate_after = block->step_event_count; + + // Will be set to last direction later if directional format. + block->direction_bits = 0; + + #define PAGE_UPDATE_DIR(AXIS) \ + if (!last_page_dir[_AXIS(AXIS)]) SBI(block->direction_bits, _AXIS(AXIS)); + + if (!DirectStepping::Config::DIRECTIONAL) { + PAGE_UPDATE_DIR(X); + PAGE_UPDATE_DIR(Y); + PAGE_UPDATE_DIR(Z); + PAGE_UPDATE_DIR(E); + } + + // If this is the first added movement, reload the delay, otherwise, cancel it. + if (block_buffer_head == block_buffer_tail) { + // If it was the first queued block, restart the 1st block delivery delay, to + // give the planner an opportunity to queue more movements and plan them + // As there are no queued movements, the Stepper ISR will not touch this + // variable, so there is no risk setting this here (but it MUST be done + // before the following line!!) + delay_before_delivering = BLOCK_DELAY_FOR_1ST_MOVE; + } + + // Move buffer head + block_buffer_head = next_buffer_head; + + enable_all_steppers(); + stepper.wake_up(); + } + +#endif // DIRECT_STEPPING + /** * Directly set the planner ABC position (and stepper positions) * converting mm (or angles for SCARA) into steps. diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 60dbb612c7ec..6c5218cd6ff4 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -66,6 +66,13 @@ #include "../feature/spindle_laser_types.h" #endif +#if ENABLED(DIRECT_STEPPING) + #include "../feature/direct_stepping.h" + #define IS_PAGE(B) TEST(B->flag, BLOCK_BIT_IS_PAGE) +#else + #define IS_PAGE(B) false +#endif + // Feedrate for manual moves #ifdef MANUAL_FEEDRATE constexpr xyze_feedrate_t _mf = MANUAL_FEEDRATE, @@ -90,13 +97,21 @@ enum BlockFlagBit : char { // Sync the stepper counts from the block BLOCK_BIT_SYNC_POSITION + + // Direct stepping page + #if ENABLED(DIRECT_STEPPING) + , BLOCK_BIT_IS_PAGE + #endif }; enum BlockFlag : char { - BLOCK_FLAG_RECALCULATE = _BV(BLOCK_BIT_RECALCULATE), - BLOCK_FLAG_NOMINAL_LENGTH = _BV(BLOCK_BIT_NOMINAL_LENGTH), - BLOCK_FLAG_CONTINUED = _BV(BLOCK_BIT_CONTINUED), - BLOCK_FLAG_SYNC_POSITION = _BV(BLOCK_BIT_SYNC_POSITION) + BLOCK_FLAG_RECALCULATE = _BV(BLOCK_BIT_RECALCULATE) + , BLOCK_FLAG_NOMINAL_LENGTH = _BV(BLOCK_BIT_NOMINAL_LENGTH) + , BLOCK_FLAG_CONTINUED = _BV(BLOCK_BIT_CONTINUED) + , BLOCK_FLAG_SYNC_POSITION = _BV(BLOCK_BIT_SYNC_POSITION) + #if ENABLED(DIRECT_STEPPING) + , BLOCK_FLAG_IS_PAGE = _BV(BLOCK_BIT_IS_PAGE) + #endif }; #if ENABLED(LASER_POWER_INLINE) @@ -180,6 +195,10 @@ typedef struct block_t { final_rate, // The minimal rate at exit acceleration_steps_per_s2; // acceleration steps/sec^2 + #if ENABLED(DIRECT_STEPPING) + page_idx_t page_idx; // Page index used for direct stepping + #endif + #if HAS_CUTTER cutter_power_t cutter_power; // Power level for Spindle, Laser, etc. #endif @@ -229,7 +248,7 @@ typedef struct block_t { * as it avoids floating points during move loop */ uint8_t power; - } settings_laser_t; + } laser_state_t; #endif typedef struct { @@ -242,9 +261,6 @@ typedef struct { travel_acceleration; // (mm/s^2) M204 T - Travel acceleration. DEFAULT ACCELERATION for all NON printing moves. feedRate_t min_feedrate_mm_s, // (mm/s) M205 S - Minimum linear feedrate min_travel_feedrate_mm_s; // (mm/s) M205 T - Minimum travel feedrate - #if ENABLED(LASER_POWER_INLINE) - settings_laser_t laser; - #endif } planner_settings_t; #if DISABLED(SKEW_CORRECTION) @@ -296,6 +312,11 @@ class Planner { static uint8_t last_extruder; // Respond to extruder change #endif + #if ENABLED(DIRECT_STEPPING) + static uint32_t last_page_step_rate; // Last page step rate given + static xyze_bool_t last_page_dir; // Last page direction given + #endif + #if EXTRUDERS static int16_t flow_percentage[EXTRUDERS]; // Extrusion factor for each extruder static float e_factor[EXTRUDERS]; // The flow percentage and volumetric multiplier combine to scale E movement @@ -310,6 +331,10 @@ class Planner { static planner_settings_t settings; + #if ENABLED(LASER_POWER_INLINE) + static laser_state_t laser; + #endif + static uint32_t max_acceleration_steps_per_s2[XYZE_N]; // (steps/s^2) Derived from mm_per_s2 static float steps_to_mm[XYZE_N]; // Millimeters per step @@ -726,6 +751,10 @@ class Planner { ); } + #if ENABLED(DIRECT_STEPPING) + static void buffer_page(const page_idx_t page_idx, const uint8_t extruder, const uint16_t num_steps); + #endif + /** * Set the planner.position and individual stepper positions. * Used by G92, G28, G29, and other procedures. @@ -811,10 +840,10 @@ class Planner { static block_t* get_current_block(); /** - * "Discard" the block and "release" the memory. + * "Release" the current block so its slot can be reused. * Called when the current block is no longer needed. */ - FORCE_INLINE static void discard_current_block() { + FORCE_INLINE static void release_current_block() { if (has_blocks_queued()) block_buffer_tail = next_block_index(block_buffer_tail); } diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 92ee753392c8..63fee87d0011 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -230,6 +230,10 @@ uint32_t Stepper::advance_divisor = 0, uint32_t Stepper::nextBabystepISR = BABYSTEP_NEVER; #endif +#if ENABLED(DIRECT_STEPPING) + page_step_state_t Stepper::page_step_state; +#endif + int32_t Stepper::ticks_nominal = -1; #if DISABLED(S_CURVE_ACCELERATION) uint32_t Stepper::acc_step_rate; // needed for deceleration start point @@ -1520,11 +1524,7 @@ void Stepper::pulse_phase_isr() { // If we must abort the current block, do so! if (abort_current_block) { abort_current_block = false; - if (current_block) { - axis_did_move = 0; - current_block = nullptr; - planner.discard_current_block(); - } + if (current_block) discard_current_block(); } // If there is no current block, do nothing @@ -1558,46 +1558,160 @@ void Stepper::pulse_phase_isr() { } \ }while(0) - // Start an active pulse, if Bresenham says so, and update position + // Start an active pulse if needed #define PULSE_START(AXIS) do{ \ if (step_needed[_AXIS(AXIS)]) { \ _APPLY_STEP(AXIS, !_INVERT_STEP_PIN(AXIS), 0); \ } \ }while(0) - // Stop an active pulse, if any, and adjust error term + // Stop an active pulse if needed #define PULSE_STOP(AXIS) do { \ if (step_needed[_AXIS(AXIS)]) { \ _APPLY_STEP(AXIS, _INVERT_STEP_PIN(AXIS), 0); \ } \ }while(0) - // Determine if pulses are needed - #if HAS_X_STEP - PULSE_PREP(X); - #endif - #if HAS_Y_STEP - PULSE_PREP(Y); - #endif - #if HAS_Z_STEP - PULSE_PREP(Z); - #endif + // Direct Stepping page? + const bool is_page = IS_PAGE(current_block); + + #if ENABLED(DIRECT_STEPPING) + + if (is_page) { + + #if STEPPER_PAGE_FORMAT == SP_4x4D_128 + + #define PAGE_SEGMENT_UPDATE(AXIS, VALUE, MID) do{ \ + if ((VALUE) == MID) {} \ + else if ((VALUE) < MID) SBI(dm, _AXIS(AXIS)); \ + else CBI(dm, _AXIS(AXIS)); \ + page_step_state.sd[_AXIS(AXIS)] = VALUE; \ + page_step_state.bd[_AXIS(AXIS)] += VALUE; \ + }while(0) + + #define PAGE_PULSE_PREP(AXIS) do{ \ + step_needed[_AXIS(AXIS)] = \ + pgm_read_byte(&segment_table[page_step_state.sd[_AXIS(AXIS)]][page_step_state.segment_steps & 0x7]); \ + }while(0) + + switch (page_step_state.segment_steps) { + case 8: + page_step_state.segment_idx += 2; + page_step_state.segment_steps = 0; + // fallthru + case 0: { + const uint8_t low = page_step_state.page[page_step_state.segment_idx], + high = page_step_state.page[page_step_state.segment_idx + 1]; + uint8_t dm = last_direction_bits; + + PAGE_SEGMENT_UPDATE(X, low >> 4, 7); + PAGE_SEGMENT_UPDATE(Y, low & 0xF, 7); + PAGE_SEGMENT_UPDATE(Z, high >> 4, 7); + PAGE_SEGMENT_UPDATE(E, high & 0xF, 7); + + if (dm != last_direction_bits) { + last_direction_bits = dm; + set_directions(); + } + } break; + + default: break; + } + + PAGE_PULSE_PREP(X), + PAGE_PULSE_PREP(Y), + PAGE_PULSE_PREP(Z), + PAGE_PULSE_PREP(E); + + page_step_state.segment_steps++; + + #elif STEPPER_PAGE_FORMAT == SP_4x2_256 + + #define PAGE_SEGMENT_UPDATE(AXIS, VALUE) \ + page_step_state.sd[_AXIS(AXIS)] = VALUE; \ + page_step_state.bd[_AXIS(AXIS)] += VALUE; + + #define PAGE_PULSE_PREP(AXIS) do{ \ + step_needed[_AXIS(AXIS)] = \ + pgm_read_byte(&segment_table[page_step_state.sd[_AXIS(AXIS)]][page_step_state.segment_steps & 0x3]); \ + }while(0) + + switch (page_step_state.segment_steps) { + case 4: + page_step_state.segment_idx++; + page_step_state.segment_steps = 0; + // fallthru + case 0: { + const uint8_t b = page_step_state.page[page_step_state.segment_idx]; + PAGE_SEGMENT_UPDATE(X, (b >> 6) & 0x3); + PAGE_SEGMENT_UPDATE(Y, (b >> 4) & 0x3); + PAGE_SEGMENT_UPDATE(Z, (b >> 2) & 0x3); + PAGE_SEGMENT_UPDATE(E, (b >> 0) & 0x3); + } break; + default: break; + } + + PAGE_PULSE_PREP(X); + PAGE_PULSE_PREP(Y); + PAGE_PULSE_PREP(Z); + PAGE_PULSE_PREP(E); + + page_step_state.segment_steps++; + + #elif STEPPER_PAGE_FORMAT == SP_4x1_512 + + #define PAGE_PULSE_PREP(AXIS, BITS) do{ \ + step_needed[_AXIS(AXIS)] = (steps >> BITS) & 0x1; \ + if (step_needed[_AXIS(AXIS)]) \ + page_step_state.bd[_AXIS(AXIS)]++; \ + }while(0) + + uint8_t steps = page_step_state.page[page_step_state.segment_idx >> 1]; + + if (page_step_state.segment_idx & 0x1) steps >>= 4; + + PAGE_PULSE_PREP(X, 3); + PAGE_PULSE_PREP(Y, 2); + PAGE_PULSE_PREP(Z, 1); + PAGE_PULSE_PREP(E, 0); + + page_step_state.segment_idx++; - #if EITHER(LIN_ADVANCE, MIXING_EXTRUDER) - delta_error.e += advance_dividend.e; - if (delta_error.e >= 0) { - count_position.e += count_direction.e; - #if ENABLED(LIN_ADVANCE) - delta_error.e -= advance_divisor; - // Don't step E here - But remember the number of steps to perform - motor_direction(E_AXIS) ? --LA_steps : ++LA_steps; #else - step_needed.e = true; + #error "Unknown direct stepping page format!" #endif } - #elif HAS_E0_STEP - PULSE_PREP(E); - #endif + + #endif // DIRECT_STEPPING + + if (!is_page) { + // Determine if pulses are needed + #if HAS_X_STEP + PULSE_PREP(X); + #endif + #if HAS_Y_STEP + PULSE_PREP(Y); + #endif + #if HAS_Z_STEP + PULSE_PREP(Z); + #endif + + #if EITHER(LIN_ADVANCE, MIXING_EXTRUDER) + delta_error.e += advance_dividend.e; + if (delta_error.e >= 0) { + count_position.e += count_direction.e; + #if ENABLED(LIN_ADVANCE) + delta_error.e -= advance_divisor; + // Don't step E here - But remember the number of steps to perform + motor_direction(E_AXIS) ? --LA_steps : ++LA_steps; + #else + step_needed.e = true; + #endif + } + #elif HAS_E0_STEP + PULSE_PREP(E); + #endif + } #if ISR_MULTI_STEPS if (firstStep) @@ -1676,14 +1790,28 @@ uint32_t Stepper::block_phase_isr() { // If there is a current block if (current_block) { - // If current block is finished, reset pointer + // If current block is finished, reset pointer and finalize state if (step_events_completed >= step_event_count) { + #if ENABLED(DIRECT_STEPPING) + #if STEPPER_PAGE_FORMAT == SP_4x4D_128 + #define PAGE_SEGMENT_UPDATE_POS(AXIS) \ + count_position[_AXIS(AXIS)] += page_step_state.bd[_AXIS(AXIS)] - 128 * 7; + #elif STEPPER_PAGE_FORMAT == SP_4x1_512 || STEPPER_PAGE_FORMAT == SP_4x2_256 + #define PAGE_SEGMENT_UPDATE_POS(AXIS) \ + count_position[_AXIS(AXIS)] += page_step_state.bd[_AXIS(AXIS)] * count_direction[_AXIS(AXIS)]; + #endif + + if (IS_PAGE(current_block)) { + PAGE_SEGMENT_UPDATE_POS(X); + PAGE_SEGMENT_UPDATE_POS(Y); + PAGE_SEGMENT_UPDATE_POS(Z); + PAGE_SEGMENT_UPDATE_POS(E); + } + #endif #ifdef FILAMENT_RUNOUT_DISTANCE_MM runout.block_completed(current_block); #endif - axis_did_move = 0; - current_block = nullptr; - planner.discard_current_block(); + discard_current_block(); } else { // Step events not completed yet... @@ -1867,7 +1995,7 @@ uint32_t Stepper::block_phase_isr() { // Sync block? Sync the stepper counts and return while (TEST(current_block->flag, BLOCK_BIT_SYNC_POSITION)) { _set_position(current_block->position); - planner.discard_current_block(); + discard_current_block(); // Try to get a new block if (!(current_block = planner.get_current_block())) @@ -1878,6 +2006,23 @@ uint32_t Stepper::block_phase_isr() { TERN_(POWER_LOSS_RECOVERY, recovery.info.sdpos = current_block->sdpos); + #if ENABLED(DIRECT_STEPPING) + if (IS_PAGE(current_block)) { + page_step_state.segment_steps = 0; + page_step_state.segment_idx = 0; + page_step_state.page = page_manager.get_page(current_block->page_idx); + page_step_state.bd.reset(); + + if (DirectStepping::Config::DIRECTIONAL) + current_block->direction_bits = last_direction_bits; + + if (!page_step_state.page) { + discard_current_block(); + return interval; + } + } + #endif + // Flag all moving axes for proper endstop handling #if IS_CORE @@ -2094,11 +2239,11 @@ uint32_t Stepper::block_phase_isr() { #if ENABLED(LASER_POWER_INLINE_CONTINUOUS) else { // No new block found; so apply inline laser parameters // This should mean ending file with 'M5 I' will stop the laser; thus the inline flag isn't needed - const uint8_t stat = planner.settings.laser.status; + const uint8_t stat = planner.laser.status; if (TEST(stat, 0)) { // Planner controls the laser #if ENABLED(SPINDLE_LASER_PWM) if (TEST(stat, 1)) // Laser is on - cutter.set_ocr_power(planner.settings.laser.power); + cutter.set_ocr_power(planner.laser.power); else cutter.set_power(0); #else @@ -3275,95 +3420,76 @@ void Stepper::report_positions() { } void Stepper::microstep_readings() { - SERIAL_ECHOLNPGM("MS1|MS2|MS3 Pins"); + #define PIN_CHAR(P) SERIAL_CHAR('0' + READ(P##_PIN)) + #define MS_LINE(A) do{ SERIAL_ECHOPGM(" " STRINGIFY(A) ":"); PIN_CHAR(A##_MS1); PIN_CHAR(A##_MS2); }while(0) + SERIAL_ECHOPGM("MS1|2|3 Pins"); #if HAS_X_MS_PINS - SERIAL_ECHOPGM("X: "); - SERIAL_CHAR('0' + READ(X_MS1_PIN), '0' + READ(X_MS2_PIN) - #if PIN_EXISTS(X_MS3) - , '0' + READ(X_MS3_PIN) - #endif - ); + MS_LINE(X); + #if PIN_EXISTS(X_MS3) + PIN_CHAR(X_MS3); + #endif #endif #if HAS_Y_MS_PINS - SERIAL_ECHOPGM("Y: "); - SERIAL_CHAR('0' + READ(Y_MS1_PIN), '0' + READ(Y_MS2_PIN) - #if PIN_EXISTS(Y_MS3) - , '0' + READ(Y_MS3_PIN) - #endif - ); + MS_LINE(Y); + #if PIN_EXISTS(Y_MS3) + PIN_CHAR(Y_MS3); + #endif #endif #if HAS_Z_MS_PINS - SERIAL_ECHOPGM("Z: "); - SERIAL_CHAR('0' + READ(Z_MS1_PIN), '0' + READ(Z_MS2_PIN) - #if PIN_EXISTS(Z_MS3) - , '0' + READ(Z_MS3_PIN) - #endif - ); + MS_LINE(Z); + #if PIN_EXISTS(Z_MS3) + PIN_CHAR(Z_MS3); + #endif #endif #if HAS_E0_MS_PINS - SERIAL_ECHOPGM("E0: "); - SERIAL_CHAR('0' + READ(E0_MS1_PIN), '0' + READ(E0_MS2_PIN) - #if PIN_EXISTS(E0_MS3) - , '0' + READ(E0_MS3_PIN) - #endif - ); + MS_LINE(E0); + #if PIN_EXISTS(E0_MS3) + PIN_CHAR(E0_MS3); + #endif #endif #if HAS_E1_MS_PINS - SERIAL_ECHOPGM("E1: "); - SERIAL_CHAR('0' + READ(E1_MS1_PIN), '0' + READ(E1_MS2_PIN) - #if PIN_EXISTS(E1_MS3) - , '0' + READ(E1_MS3_PIN) - #endif - ); + MS_LINE(E1); + #if PIN_EXISTS(E1_MS3) + PIN_CHAR(E1_MS3); + #endif #endif #if HAS_E2_MS_PINS - SERIAL_ECHOPGM("E2: "); - SERIAL_CHAR('0' + READ(E2_MS1_PIN), '0' + READ(E2_MS2_PIN) - #if PIN_EXISTS(E2_MS3) - , '0' + READ(E2_MS3_PIN) - #endif - ); + MS_LINE(E2); + #if PIN_EXISTS(E2_MS3) + PIN_CHAR(E2_MS3); + #endif #endif #if HAS_E3_MS_PINS - SERIAL_ECHOPGM("E3: "); - SERIAL_CHAR('0' + READ(E3_MS1_PIN), '0' + READ(E3_MS2_PIN) - #if PIN_EXISTS(E3_MS3) - , '0' + READ(E3_MS3_PIN) - #endif - ); + MS_LINE(E3); + #if PIN_EXISTS(E3_MS3) + PIN_CHAR(E3_MS3); + #endif #endif #if HAS_E4_MS_PINS - SERIAL_ECHOPGM("E4: "); - SERIAL_CHAR('0' + READ(E4_MS1_PIN), '0' + READ(E4_MS2_PIN) - #if PIN_EXISTS(E4_MS3) - , '0' + READ(E4_MS3_PIN) - #endif - ); + MS_LINE(E4); + #if PIN_EXISTS(E4_MS3) + PIN_CHAR(E4_MS3); + #endif #endif #if HAS_E5_MS_PINS - SERIAL_ECHOPGM("E5: "); - SERIAL_CHAR('0' + READ(E5_MS1_PIN), '0' + READ(E5_MS2_PIN) - #if PIN_EXISTS(E5_MS3) - , '0' + READ(E5_MS3_PIN) - #endif - ); + MS_LINE(E5); + #if PIN_EXISTS(E5_MS3) + PIN_CHAR(E5_MS3); + #endif #endif #if HAS_E6_MS_PINS - SERIAL_ECHOPGM("E6: "); - SERIAL_CHAR('0' + READ(E6_MS1_PIN), '0' + READ(E6_MS2_PIN) - #if PIN_EXISTS(E6_MS3) - , '0' + READ(E6_MS3_PIN) - #endif - ); + MS_LINE(E6); + #if PIN_EXISTS(E6_MS3) + PIN_CHAR(E6_MS3); + #endif #endif #if HAS_E7_MS_PINS - SERIAL_ECHOPGM("E7: "); - SERIAL_CHAR('0' + READ(E7_MS1_PIN), '0' + READ(E7_MS2_PIN) - #if PIN_EXISTS(E7_MS3) - , '0' + READ(E7_MS3_PIN) - #endif - ); + MS_LINE(E7); + #if PIN_EXISTS(E7_MS3) + PIN_CHAR(E7_MS3); + #endif #endif + SERIAL_EOL(); } #endif // HAS_MICROSTEPS diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h index 793dc8745bdf..38af36db5194 100644 --- a/Marlin/src/module/stepper.h +++ b/Marlin/src/module/stepper.h @@ -334,6 +334,10 @@ class Stepper { static uint32_t nextBabystepISR; #endif + #if ENABLED(DIRECT_STEPPING) + static page_step_state_t page_step_state; + #endif + static int32_t ticks_nominal; #if DISABLED(S_CURVE_ACCELERATION) static uint32_t acc_step_rate; // needed for deceleration start point @@ -426,6 +430,17 @@ class Stepper { static void report_a_position(const xyz_long_t &pos); static void report_positions(); + // Discard current block and free any resources + FORCE_INLINE static void discard_current_block() { + #if ENABLED(DIRECT_STEPPING) + if (IS_PAGE(current_block)) + page_manager.free_page(current_block->page_idx); + #endif + current_block = nullptr; + axis_did_move = 0; + planner.release_current_block(); + } + // Quickly stop all steppers FORCE_INLINE static void quick_stop() { abort_current_block = true; } @@ -437,11 +452,7 @@ class Stepper { // The extruder associated to the last movement FORCE_INLINE static uint8_t movement_extruder() { - return (0 - #if EXTRUDERS > 1 && DISABLED(MIXING_EXTRUDER) - + last_moved_extruder - #endif - ); + return (EXTRUDERS > 1 && DISABLED(MIXING_EXTRUDER)) ? last_moved_extruder : 0; } // Handle a triggered endstop diff --git a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h index a663061f6ca5..52444008bee3 100644 --- a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h +++ b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h @@ -29,6 +29,7 @@ #define BOARD_INFO_NAME "FYSETC Cheetah" #define BOARD_WEBSITE_URL "fysetc.com" +// https://github.com/FYSETC/Cheetah // Ignore temp readings during development. //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 @@ -103,39 +104,41 @@ // Misc. Functions // #define SDSS PA4 +#define SD_DETECT_PIN PC3 -// -// LCD Pins -// -/** - * _____ - * 5V | 1 2 | GND - * (MOSI) PB15 | 3 4 | PB12 (LCD_EN) - * (SCK) PB13 | 5 6 PC11 (BTN_EN1) - * (LCD_RS) PB14 | 7 8 | PC10 (BTN_EN2) - * (BTN_ENC) PC12 | 9 10| PC9 (BEEPER) - * ----- - * EXP1 - */ +#ifndef RGB_LED_R_PIN + #define RGB_LED_R_PIN PB0 +#endif +#ifndef RGB_LED_G_PIN + #define RGB_LED_G_PIN PB7 +#endif +#ifndef RGB_LED_B_PIN + #define RGB_LED_B_PIN PB6 +#endif -#define EXPA1_03_PIN PB15 -#define EXPA1_04_PIN PB12 -#define EXPA1_05_PIN PB13 -#define EXPA1_06_PIN PC11 -#define EXPA1_07_PIN PB14 -#define EXPA1_08_PIN PC10 -#define EXPA1_09_PIN PC12 -#define EXPA1_10_PIN PC9 +/* +* EXP1 pinout for the LCD according to Fysetcs schematic for the Cheetah board +* _____ +* (Beeper) PC9 | 1 2 | PC12 (BTN_ENC) +* (BTN_EN2) PC11 | 3 4 | PB14 (LCD_RS / MISO) +* (BTN_EN1) PC10 5 6 | PB13 (SCK) +* (LCD_EN) PB12 | 7 8 | PB15 (MOSI) +* GND | 9 10| 5V +* ----- +* EXP1 +* Note: The pin-numbers match the connector correctly and are not in reverse order like on the Ender-3 board. +* Note: Functionally the pins are assigned in the same order as on the Ender-3 board. +* Note: Pin 4 on the Cheetah board is assigned to an I/O, it is assigned to RESET on the Ender-3 board. +*/ #if HAS_SPI_LCD - - #define BEEPER_PIN EXPA1_10_PIN + #define BEEPER_PIN PC9 #if HAS_GRAPHICAL_LCD - #define DOGLCD_A0 EXPA1_07_PIN - #define DOGLCD_CS EXPA1_04_PIN - #define DOGLCD_SCK EXPA1_05_PIN - #define DOGLCD_MOSI EXPA1_03_PIN + #define DOGLCD_A0 PB14 + #define DOGLCD_CS PB12 + #define DOGLCD_SCK PB13 + #define DOGLCD_MOSI PB15 //#define LCD_SCREEN_ROT_90 //#define LCD_SCREEN_ROT_180 //#define LCD_SCREEN_ROT_270 @@ -145,45 +148,31 @@ #endif #endif - #define LCD_PINS_RS EXPA1_04_PIN // CS -- SOFT SPI for ENDER3 LCD - #define LCD_PINS_D4 EXPA1_05_PIN // SCLK - #define LCD_PINS_ENABLE EXPA1_03_PIN // DATA MOSI - - // not connected to a pin - #define SD_DETECT_PIN PC3 - - #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN PB0 - #endif - #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN PB7 - #endif - #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN PB6 - #endif + #define LCD_PINS_RS PB12 // CS -- SOFT SPI for ENDER3 LCD + #define LCD_PINS_D4 PB13 // SCLK + #define LCD_PINS_ENABLE PB15 // DATA MOSI //#define LCD_CONTRAST_INIT 190 #if ENABLED(NEWPANEL) - #define BTN_EN1 EXPA1_06_PIN - #define BTN_EN2 EXPA1_08_PIN - #define BTN_ENC EXPA1_09_PIN + #define BTN_EN1 PC10 + #define BTN_EN2 PC11 + #define BTN_ENC PC12 #endif - #endif #if ENABLED(TOUCH_UI_FTDI_EVE) - #define BEEPER_PIN EXPA1_10_PIN - - #define BTN_EN1 EXPA1_06_PIN + #define BEEPER_PIN PC9 + #define CLCD_MOD_RESET PC11 + #define CLCD_SPI_CS PB12 - #define LCD_PINS_RS EXPA1_04_PIN + //#define CLCD_USE_SOFT_SPI // the Cheetah can use hardware-SPI so we do not really need this - #define CLCD_SPI_BUS 2 - //#define CLCD_USE_SOFT_SPI #if ENABLED(CLCD_USE_SOFT_SPI) - #define LCD_PINS_ENABLE EXPA1_03_PIN - #define LCD_PINS_SCK EXPA1_07_PIN - #define LCD_PINS_D4 EXPA1_05_PIN + #define CLCD_SOFT_SPI_MOSI PB15 + #define CLCD_SOFT_SPI_MISO PB14 + #define CLCD_SOFT_SPI_SCLK PB13 + #else + #define CLCD_SPI_BUS 2 #endif #endif diff --git a/buildroot/share/PlatformIO/boards/BigTree_GTR_v1.json b/buildroot/share/PlatformIO/boards/BigTree_GTR_v1.json new file mode 100644 index 000000000000..669a7520bbce --- /dev/null +++ b/buildroot/share/PlatformIO/boards/BigTree_GTR_v1.json @@ -0,0 +1,46 @@ +{ + "build": { + "core": "stm32", + "cpu": "cortex-m4", + "extra_flags": "-DSTM32F4 -DSTM32F407xx -DSTM32F40_41xxx", + "f_cpu": "168000000L", + "hwids": [ + [ + "0x1EAF", + "0x0003" + ], + [ + "0x0483", + "0x3748" + ] + ], + "mcu": "stm32f407zgt6", + "variant": "BIGTREE_GTR_V1" + }, + "debug": { + "jlink_device": "STM32F407ZG", + "openocd_target": "stm32f4x", + "svd_path": "STM32F40x.svd" + }, + "frameworks": [ + "arduino" + ], + "name": "STM32F407ZG (192k RAM. 1024k Flash)", + "upload": { + "disable_flushing": false, + "maximum_ram_size": 196608, + "maximum_size": 1048576, + "protocol": "stlink", + "protocols": [ + "stlink", + "dfu", + "jlink" + ], + "offset_address": "0x8008000", + "require_upload_port": true, + "use_1200bps_touch": false, + "wait_for_upload_port": false + }, + "url": "http://www.st.com/en/microcontrollers/stm32f407zg.html", + "vendor": "Generic" +} diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/PeripheralPins.c b/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/PeripheralPins.c new file mode 100644 index 000000000000..4014a519a305 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/PeripheralPins.c @@ -0,0 +1,373 @@ +/* + ******************************************************************************* + * Copyright (c) 2019, 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. + ******************************************************************************* + * Automatically generated from STM32F407Z(E-G)Tx.xml + */ +#include +#include + +/* ===== + * Note: Commented lines are alternative possibilities which are not used by default. + * If you change them, you should know what you're doing first. + * ===== + */ + +//*** ADC *** + +#ifdef HAL_ADC_MODULE_ENABLED +const PinMap PinMap_ADC[] = { + {PA_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC1_IN0 E0_DIR + {PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1 BLTOUCH_2 + {PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2 BLTOUCH_4 + {PA_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3 E1_EN + {PA_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4 TF_SS + {PA_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_IN5 TF_SCLK + {PA_6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6 TF_MISO + {PA_7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7 LED + {PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8 HEATER2 + {PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9 HEATER0 + {PC_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10 Z_EN + {PC_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC1_IN11 EXP_14 + {PC_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC1_IN12 Z_DIR + {PC_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC1_IN13 E0_EN + {PC_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_IN14 EXP_8 + {PC_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15 EXP_7 + + #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio, 24 ADC + {PF_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC3_IN9 TH_0 + {PF_4, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC3_IN14 TH_1 + {PF_5, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC3_IN15 TH_2 + {PF_6, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC3_IN4 TH_3 + {PF_7, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC3_IN5 EXP_13 + {PF_8, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC3_IN6 EXP_3 + {PF_9, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC3_IN7 EXP_6 + {PF_10, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC3_IN8 EXP_5 + #endif + {NC, NP, 0} +}; +#endif + +//*** DAC *** + +#ifdef HAL_DAC_MODULE_ENABLED +const PinMap PinMap_DAC[] = { + {PA_4, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // DAC_OUT1 + {PA_5, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // DAC_OUT2 + {NC, NP, 0} +}; +#endif + +//*** I2C *** + +#ifdef HAL_I2C_MODULE_ENABLED +const PinMap PinMap_I2C_SDA[] = { + {PB_7, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, + {PB_9, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, + {PB_11, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + {PC_9, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, + #if STM32F4X_PIN_NUM >= 144 // 144 pins mcu, 114 gpio + #if STM32F4X_PIN_NUM >= 176 + {PH_5, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + {PH_8, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, + #else + {PF_0, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + #endif + #endif + {NC, NP, 0} +}; +#endif + +#ifdef HAL_I2C_MODULE_ENABLED +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)}, + #if STM32F4X_PIN_NUM >= 144 // 144 pins mcu, 114 gpio + #if STM32F4X_PIN_NUM >= 176 + //{PF_1, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + {PH_4, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + {PH_7, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, + #else + {PF_1, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + #endif + #endif + {NC, NP, 0} +}; +#endif + +//*** PWM *** + +#ifdef HAL_TIM_MODULE_ENABLED +const PinMap PinMap_PWM[] = { + {PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 HEATER0 + {PD_14, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 HEATER1 + {PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 HEATER2 + {PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 BED + {PC_8, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 0)}, // TIM8_CH3 FAN0 + {PE_5, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 FAN1 + {PE_6, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2 FAN2 + {PC_9, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 4, 0)}, // TIM8_CH4 EXTENSION1-4 + {PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 BL-TOUCH-SERVO + + // These pins have been defined for something else on the board but they MIGHT be + // used by the user as PWM pins if they aren't used for their primary purpose. + {PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 ESP8266 connector. Available if 8266 isn't used + {PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 ESP8266 connector. Available if 8266 isn't used + {PB_7, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 I2C connector, SDA pin. Available if I2C isn't used. + // TIM5_CH1 is used by the Servo Library + {PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3 BL-TOUCH port. Available if Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN + + /** + * Unused by specifications on SKR-Pro. + * Uncomment the corresponding line if you want to have HardwarePWM on some pins. + * WARNING: check timers' usage first to avoid conflicts. + * If you don't know what you're doing leave things as they are or you WILL break something (including hardware) + * If you alter this section DO NOT report bugs to Marlin team since they are most likely caused by you. Thank you. + */ + //{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 BLTOUCH is a "servo" + {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 BLTOUCH is a "servo" + //{PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 + //{PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3 + //{PA_2, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 + //{PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 + //{PA_3, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 4, 0)}, // TIM5_CH4 + //{PA_3, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2 + //{PA_5, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 + //{PA_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N + //{PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + //{PA_6, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 + //{PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + //{PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + //{PA_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N + //{PA_7, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 + //{PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 + //{PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 + //{PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 + //{PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 + //{PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 + //{PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + //{PB_0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N + //{PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + //{PB_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N + //{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_8, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 + //{PB_8, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1 + //{PB_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 + //{PB_9, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1 + //{PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 + {PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 + //{PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + //{PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + //{PB_14, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N + //{PB_14, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 1, 0)}, // TIM12_CH1 + //{PB_15, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + //{PB_15, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N + //{PB_15, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 2, 0)}, // TIM12_CH2 + //{PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1 + //{PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + //{PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 + //{PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 + //{PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 + {PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 + {PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 + //{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 + #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + //{PF_6, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1 + //{PF_7, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1 + //{PF_8, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 + //{PF_9, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 + #endif + #if STM32F4X_PIN_NUM >= 176 //176 pins mcu, 140 gpio + {PH_10, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1 + {PH_6, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 1, 0)}, // TIM12_CH1 + //{PH_11, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 + {PI_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1 + {PI_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 + #endif + {NC, NP, 0} +}; +#endif + +//*** SERIAL *** + +#ifdef HAL_UART_MODULE_ENABLED +const PinMap PinMap_UART_TX[] = { + {PA_9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PD_8, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PC_6, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + //{PG_14, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + #endif + //{PB_6, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + //{PA_2, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + //{PD_5, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + //{PB_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + //{PC_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + //{PA_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PC_10, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PC_12, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, + {NC, NP, 0} +}; + +const PinMap PinMap_UART_RX[] = { + {PA_10, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PD_9, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PC_7, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + //{PA_1, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PA_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + //{PB_7, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + //{PB_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + //{PC_11, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + //{PC_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + //{PD_2, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, + //{PD_6, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + //{PG_9, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + #endif + {NC, NP, 0} +}; + +const PinMap PinMap_UART_RTS[] = { + //{PA_1, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + //{PA_12, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + //{PB_14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + //{PD_4, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + //{PD_12, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + //{PG_8, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + //{PG_12, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + #endif + {NC, NP, 0} +}; + +const PinMap PinMap_UART_CTS[] = { + //{PA_0, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + //{PA_11, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + //{PB_13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + //{PD_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + //{PD_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + //{PG_13, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + //{PG_15, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + #endif + {NC, NP, 0} +}; +#endif + +//*** SPI *** + +#ifdef HAL_SPI_MODULE_ENABLED +const PinMap PinMap_SPI_MOSI[] = { + //{PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, + {PA_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, + {PB_15, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PC_12, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {NC, NP, 0} +}; + +const PinMap PinMap_SPI_MISO[] = { + {PA_6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, + {PB_14, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PC_11, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {NC, NP, 0} +}; + +const PinMap PinMap_SPI_SCLK[] = { + {PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, + {PB_13, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PC_10, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {NC, NP, 0} +}; + +const PinMap PinMap_SPI_SSEL[] = { + {PA_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, + {PB_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PA_15, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {NC, NP, 0} +}; +#endif + +//*** CAN *** + +#ifdef HAL_CAN_MODULE_ENABLED +#error "CAN bus isn't available on this board. Driver should be disabled." +#endif + +//*** ETHERNET *** +#ifdef HAL_ETH_MODULE_ENABLED +#error "Ethernet port isn't available on this board. Driver should be disabled." +#endif + +//*** No QUADSPI *** + +//*** USB *** +#ifdef HAL_PCD_MODULE_ENABLED +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 used by LCD + //{PA_9, USB_OTG_FS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_FS_VBUS available on wifi port, if empty + //{PA_10, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_ID available on UART1_RX if not used + {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} +}; + +const PinMap PinMap_USB_OTG_HS[] = { /* + #ifdef USE_USB_HS_IN_FS + {PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_ID + {PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_HS_VBUS + {PB_14, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DM + {PB_15, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DP + #else + #error "USB in HS mode isn't supported by the board" + {PA_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D0 + {PB_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D1 + {PB_1, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D2 + {PB_5, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D7 + {PB_10, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D3 + {PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D5 + {PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D6 + {PC_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_STP + {PC_2, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_DIR + {PC_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_NXT + #endif // USE_USB_HS_IN_FS + */ + {NC, NP, 0} +}; +#endif diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/PinNamesVar.h b/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/PinNamesVar.h new file mode 100644 index 000000000000..b4bb9d45f8ac --- /dev/null +++ b/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/PinNamesVar.h @@ -0,0 +1,50 @@ +/* SYS_WKUP */ +#ifdef PWR_WAKEUP_PIN1 + SYS_WKUP1 = PA_0, +#endif +#ifdef PWR_WAKEUP_PIN2 + SYS_WKUP2 = NC, +#endif +#ifdef PWR_WAKEUP_PIN3 + SYS_WKUP3 = NC, +#endif +#ifdef PWR_WAKEUP_PIN4 + SYS_WKUP4 = NC, +#endif +#ifdef PWR_WAKEUP_PIN5 + SYS_WKUP5 = NC, +#endif +#ifdef PWR_WAKEUP_PIN6 + SYS_WKUP6 = NC, +#endif +#ifdef PWR_WAKEUP_PIN7 + SYS_WKUP7 = NC, +#endif +#ifdef PWR_WAKEUP_PIN8 + SYS_WKUP8 = NC, +#endif +/* USB */ +#ifdef USBCON + USB_OTG_FS_SOF = PA_8, + USB_OTG_FS_VBUS = PA_9, + USB_OTG_FS_ID = PA_10, + USB_OTG_FS_DM = PA_11, + USB_OTG_FS_DP = PA_12, + USB_OTG_HS_ULPI_D0 = PA_3, + USB_OTG_HS_SOF = PA_4, + USB_OTG_HS_ULPI_CK = PA_5, + USB_OTG_HS_ULPI_D1 = PB_0, + USB_OTG_HS_ULPI_D2 = PB_1, + USB_OTG_HS_ULPI_D7 = PB_5, + USB_OTG_HS_ULPI_D3 = PB_10, + USB_OTG_HS_ULPI_D4 = PB_11, + USB_OTG_HS_ID = PB_12, + USB_OTG_HS_ULPI_D5 = PB_12, + USB_OTG_HS_ULPI_D6 = PB_13, + USB_OTG_HS_VBUS = PB_13, + USB_OTG_HS_DM = PB_14, + USB_OTG_HS_DP = PB_15, + USB_OTG_HS_ULPI_STP = PC_0, + USB_OTG_HS_ULPI_DIR = PC_2, + USB_OTG_HS_ULPI_NXT = PC_3, +#endif diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/hal_conf_extra.h b/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/hal_conf_extra.h new file mode 100644 index 000000000000..e0e8239aac08 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/hal_conf_extra.h @@ -0,0 +1,52 @@ +#pragma once + +#define HAL_MODULE_ENABLED +#define HAL_ADC_MODULE_ENABLED +#define HAL_CRC_MODULE_ENABLED +#define HAL_DMA_MODULE_ENABLED +#define HAL_GPIO_MODULE_ENABLED +#define HAL_I2C_MODULE_ENABLED +#define HAL_PWR_MODULE_ENABLED +#define HAL_RCC_MODULE_ENABLED +//#define HAL_RTC_MODULE_ENABLED Real Time Clock...do we use it? +#define HAL_SPI_MODULE_ENABLED +#define HAL_TIM_MODULE_ENABLED +#define HAL_USART_MODULE_ENABLED +#define HAL_CORTEX_MODULE_ENABLED +//#define HAL_UART_MODULE_ENABLED // by default +//#define HAL_PCD_MODULE_ENABLED // Since STM32 v3.10700.191028 this is automatically added if any type of USB is enabled (as in Arduino IDE) + +#undef HAL_SD_MODULE_ENABLED +#undef HAL_DAC_MODULE_ENABLED +#undef HAL_FLASH_MODULE_ENABLED +#undef HAL_CAN_MODULE_ENABLED +#undef HAL_CAN_LEGACY_MODULE_ENABLED +#undef HAL_CEC_MODULE_ENABLED +#undef HAL_CRYP_MODULE_ENABLED +#undef HAL_DCMI_MODULE_ENABLED +#undef HAL_DMA2D_MODULE_ENABLED +#undef HAL_ETH_MODULE_ENABLED +#undef HAL_NAND_MODULE_ENABLED +#undef HAL_NOR_MODULE_ENABLED +#undef HAL_PCCARD_MODULE_ENABLED +#undef HAL_SRAM_MODULE_ENABLED +#undef HAL_SDRAM_MODULE_ENABLED +#undef HAL_HASH_MODULE_ENABLED +#undef HAL_EXTI_MODULE_ENABLED +#undef HAL_SMBUS_MODULE_ENABLED +#undef HAL_I2S_MODULE_ENABLED +#undef HAL_IWDG_MODULE_ENABLED +#undef HAL_LTDC_MODULE_ENABLED +#undef HAL_DSI_MODULE_ENABLED +#undef HAL_QSPI_MODULE_ENABLED +#undef HAL_RNG_MODULE_ENABLED +#undef HAL_SAI_MODULE_ENABLED +#undef HAL_IRDA_MODULE_ENABLED +#undef HAL_SMARTCARD_MODULE_ENABLED +#undef HAL_WWDG_MODULE_ENABLED +#undef HAL_HCD_MODULE_ENABLED +#undef HAL_FMPI2C_MODULE_ENABLED +#undef HAL_SPDIFRX_MODULE_ENABLED +#undef HAL_DFSDM_MODULE_ENABLED +#undef HAL_LPTIM_MODULE_ENABLED +#undef HAL_MMC_MODULE_ENABLED diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/ldscript.ld b/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/ldscript.ld new file mode 100644 index 000000000000..0c060d175180 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/ldscript.ld @@ -0,0 +1,204 @@ +/* +***************************************************************************** +** + +** File : LinkerScript.ld +** +** Abstract : Linker script for STM32F407ZGTx Device with +** 1024KByte FLASH, 128KByte 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 +** +**

© COPYRIGHT(c) 2014 Ac6

+** +** 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 = 0x20020000; /* 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 = 0x8008000, LENGTH = 1024K +RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K +CCMRAM (rw) : ORIGIN = 0x10000000, LENGTH = 64K +} + +/* 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): + { + . = 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): + { + . = ALIGN(4); + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + . = ALIGN(4); + } >FLASH + + .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH + .ARM : { + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + } >FLASH + + .preinit_array : + { + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + } >FLASH + .init_array : + { + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + } >FLASH + .fini_array : + { + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(SORT(.fini_array.*))) + KEEP (*(.fini_array*)) + PROVIDE_HIDDEN (__fini_array_end = .); + } >FLASH + + /* used by the startup to initialize data */ + _sidata = LOADADDR(.data); + + /* Initialized data sections goes into RAM, load LMA copy after code */ + .data : + { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + + . = ALIGN(4); + _edata = .; /* define a global symbol at data end */ + } >RAM AT> FLASH + + _siccmram = LOADADDR(.ccmram); + + /* CCM-RAM section + * + * IMPORTANT NOTE! + * If initialized variables will be placed in this section, + * the startup code needs to be modified to copy the init-values. + */ + .ccmram : + { + . = ALIGN(4); + _sccmram = .; /* create a global symbol at ccmram start */ + *(.ccmram) + *(.ccmram*) + + . = ALIGN(4); + _eccmram = .; /* create a global symbol at ccmram end */ + } >CCMRAM AT> FLASH + + + /* Uninitialized data section */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss secion */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* User_heap_stack section, used to check that there is enough RAM left */ + ._user_heap_stack : + { + . = ALIGN(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) } +} diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/variant.cpp b/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/variant.cpp new file mode 100644 index 000000000000..1486b21830a1 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/variant.cpp @@ -0,0 +1,260 @@ +/* + ******************************************************************************* + * 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 + +// Pin number +// This array allows to wrap Arduino pin number(Dx or x) +// to STM32 PinName (PX_n) +const PinName digitalPin[] = { +#if STM32F4X_PIN_NUM >= 64 //64 pins mcu, 51 gpio + PC_13, //D0 + PC_14, //D1 - OSC32_IN + PC_15, //D2 - OSC32_OUT + PH_0, //D3 - OSC_IN + PH_1, //D4 - OSC_OUT + PB_2, //D5 - BOOT1 + PB_10, //D6 - 1:SPI2_SCK / I2C2_SCL / USART3_TX / TIM2_CH3 + PB_11, //D7 - 1:I2C2_SDA / USART3_RX / TIM2_CH4 + PB_12, //D8 - 1:SPI2_NSS / OTG_HS_ID + PB_13, //D9 - 1:SPI2_SCK 2:OTG_HS_VBUS + PB_14, //D10 - 1:SPI2_MISO / TIM12_CH1 / OTG_HS_DM + PB_15, //D11 - SPI2_MOSI / TIM12_CH2 / OTG_HS_DP + PC_6, //D12 - 1:TIM8_CH1 / SDIO_D6 / USART6_TX / TIM3_CH1 + PC_7, //D13 - 1:TIM8_CH2 / SDIO_D7 / USART6_RX / TIM3_CH2 + PC_8, //D14 - 1:TIM8_CH3 / SDIO_D0 / TIM3_CH3 + PC_9, //D15 - 1:TIM8_CH4 / SDIO_D1 / TIM3_CH4 + PA_8, //D16 - 1:TIM1_CH1 / I2C3_SCL / OTG_FS_SOF + PA_9, //D17 - 1:USART1_TX / TIM1_CH2 2:OTG_FS_VBUS + PA_10, //D18 - 1:USART1_RX / TIM1_CH3 / OTG_FS_ID + PA_11, //D19 - 1:TIM1_CH4 / OTG_FS_DM + PA_12, //D20 - 1:OTG_FS_DP + PA_13, //D21 - 0:JTMS-SWDIO + PA_14, //D22 - 0:JTCK-SWCLK + PA_15, //D23 - 0:JTDI 1:SPI3_NSS / SPI1_NSS + PC_10, //D24 - 1:UART4_TX / SPI3_SCK / SDIO_D2 / USART3_TX + PC_11, //D25 - 1:UART4_RX / SPI3_MISO / SDIO_D3 / USART3_RX + PC_12, //D26 - 1:UART5_TX / SPI3_MOSI / SDIO_CK + PD_2, //D27 - 1:UART5_RX / SDIO_CMD + PB_3, //D28 - 0:JTDO 1:SPI3_SCK / TIM2_CH2 / SPI1_SCK + PB_4, //D29 - 0:NJTRST 1:SPI3_MISO / TIM3_CH1 / SPI1_MISO + PB_5, //D30 - 1:TIM3_CH2 / SPI1_MOSI / SPI3_MOSI + PB_6, //D31 - 1:I2C1_SCL / TIM4_CH1 / USART1_TX + PB_7, //D32 - 1:I2C1_SDA / TIM4_CH2 / USART1_RX + PB_8, //D33 - 1:I2C1_SCL / TIM4_CH3 / SDIO_D4 / TIM10_CH1 + PB_9, //D34 - 1:I2C1_SDA / TIM4_CH4 / SDIO_D5 / TIM11_CH1 / SPI2_NSS + PA_0, //D35/A0 - 1:UART4_TX / TIM5_CH1 2:ADC123_IN0 + PA_1, //D36/A1 - 1:UART4_RX / TIM5_CH2 / TIM2_CH2 2:ADC123_IN1 + PA_2, //D37/A2 - 1:USART2_TX /TIM5_CH3 / TIM9_CH1 / TIM2_CH3 2:ADC123_IN2 + PA_3, //D38/A3 - 1:USART2_RX /TIM5_CH4 / TIM9_CH2 / TIM2_CH4 2:ADC123_IN3 + PA_4, //D39/A4 - NOT FT 1:SPI1_NSS / SPI3_NSS / USART2_CK 2:ADC12_IN4 / DAC_OUT1 + PA_5, //D40/A5 - NOT FT 1:SPI1_SCK 2:ADC12_IN5 / DAC_OUT2 + PA_6, //D41/A6 - 1:SPI1_MISO / TIM13_CH1 / TIM3_CH1 2:ADC12_IN6 + PA_7, //D42/A7 - 1:SPI1_MOSI / TIM14_CH1 / TIM3_CH2 2:ADC12_IN7 + PB_0, //D43/A8 - 1:TIM3_CH3 2:ADC12_IN8 + PB_1, //D44/A9 - 1:TIM3_CH4 2:ADC12_IN9 + PC_0, //D45/A10 - 1: 2:ADC123_IN10 + PC_1, //D46/A11 - 1: 2:ADC123_IN11 + PC_2, //D47/A12 - 1:SPI2_MISO 2:ADC123_IN12 + PC_3, //D48/A13 - 1:SPI2_MOSI 2:ADC123_IN13 + PC_4, //D49/A14 - 1: 2:ADC12_IN14 + PC_5, //D50/A15 - 1: 2:ADC12_IN15 + #if STM32F4X_PIN_NUM >= 144 + PF_3, //D51/A16 - 1:FSMC_A3 2:ADC3_IN9 + PF_4, //D52/A17 - 1:FSMC_A4 2:ADC3_IN14 + PF_5, //D53/A18 - 1:FSMC_A5 2:ADC3_IN15 + PF_6, //D54/A19 - 1:TIM10_CH1 2:ADC3_IN4 + PF_7, //D55/A20 - 1:TIM11_CH1 2:ADC3_IN5 + PF_8, //D56/A21 - 1:TIM13_CH1 2:ADC3_IN6 + PF_9, //D57/A22 - 1;TIM14_CH1 2:ADC3_IN7 + PF_10, //D58/A23 - 2:ADC3_IN8 + #endif +#endif +#if STM32F4X_PIN_NUM >= 100 //100 pins mcu, 82 gpio + PE_2, //D59 - 1:FSMC_A23 + PE_3, //D60 - 1:FSMC_A19 + PE_4, //D61 - 1:FSMC_A20 + PE_5, //D62 - 1:FSMC_A21 + PE_6, //D63 - 1:FSMC_A22 + PE_7, //D64 - 1:FSMC_D4 + PE_8, //D65 - 1:FSMC_D5 + PE_9, //D66 - 1:FSMC_D6 / TIM1_CH1 + PE_10, //D67 - 1:FSMC_D7 + PE_11, //D68 - 1:FSMC_D8 / TIM1_CH2 + PE_12, //D69 - 1:FSMC_D9 + PE_13, //D70 - 1:FSMC_D10 / TIM1_CH3 + PE_14, //D71 - 1:FSMC_D11 / TIM1_CH4 + PE_15, //D72 - 1:FSMC_D12 + PD_8, //D73 - 1:FSMC_D13 / USART3_TX + PD_9, //D74 - 1:FSMC_D14 / USART3_RX + PD_10, //D75 - 1:FSMC_D15 + PD_11, //D76 - 1:FSMC_A16 + PD_12, //D77 - 1:FSMC_A17 / TIM4_CH1 + PD_13, //D78 - 1:FSMC_A18 / TIM4_CH2 + PD_14, //D79 - 1:FSMC_D0 / TIM4_CH3 + PD_15, //D80 - 1:FSMC_D1 / TIM4_CH4 + PD_0, //D81 - 1:FSMC_D2 + PD_1, //D82 - 1:FSMC_D3 + PD_3, //D83 - 1:FSMC_CLK + PD_4, //D84 - 1:FSMC_NOE + PD_5, //D85 - 1:USART2_TX + PD_6, //D86 - 1:USART2_RX + PD_7, //D87 + PE_0, //D88 + PE_1, //D89 +#endif +#if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + PF_0, //D90 - 1:FSMC_A0 / I2C2_SDA + PF_1, //D91 - 1:FSMC_A1 / I2C2_SCL + PF_2, //D92 - 1:FSMC_A2 + PF_11, //D93 + PF_12, //D94 - 1:FSMC_A6 + PF_13, //D95 - 1:FSMC_A7 + PF_14, //D96 - 1:FSMC_A8 + PF_15, //D97 - 1:FSMC_A9 + PG_0, //D98 - 1:FSMC_A10 + PG_1, //D99 - 1:FSMC_A11 + PG_2, //D100 - 1:FSMC_A12 + PG_3, //D101 - 1:FSMC_A13 + PG_4, //D102 - 1:FSMC_A14 + PG_5, //D103 - 1:FSMC_A15 + PG_6, //D104 + PG_7, //D105 + PG_8, //D106 + PG_9, //D107 - 1:USART6_RX + PG_10, //D108 - 1:FSMC_NE3 + PG_11, //D109 + PG_12, //D110 - 1:FSMC_NE4 + PG_13, //D111 - 1:FSMC_A24 + PG_14, //D112 - 1:FSMC_A25 / USART6_TX + PG_15, //D113 +#endif +#if STM32F4X_PIN_NUM >= 176 //176 pins mcu, 140 gpio + PI_8, //D114 + PI_9, //D115 + PI_10, //D116 + PI_11, //D117 + PH_2, //D118 + PH_3, //D119 + PH_4, //D120 - 1:I2C2_SCL + PH_5, //D121 - 1:I2C2_SDA + PH_6, //D122 - 1:TIM12_CH1 + PH_7, //D123 - 1:I2C3_SCL + PH_8, //D124 - 1:I2C3_SDA + PH_9, //D125 - 1:TIM12_CH2 + PH_10, //D126 - 1:TIM5_CH1 + PH_11, //D127 - 1:TIM5_CH2 + PH_12, //D128 - 1:TIM5_CH3 + PH_13, //D129 + PH_14, //D130 + PH_15, //D131 + PI_0, //D132 - 1:TIM5_CH4 / SPI2_NSS + PI_1, //D133 - 1:SPI2_SCK + PI_2, //D134 - 1:TIM8_CH4 /SPI2_MISO + PI_3, //D135 - 1:SPI2_MOS + PI_4, //D136 + PI_5, //D137 - 1:TIM8_CH1 + PI_6, //D138 - 1:TIM8_CH2 + PI_7, //D139 - 1:TIM8_CH3 +#endif +}; + +#ifdef __cplusplus +} +#endif + +// ------------------------ + +#ifdef __cplusplus +extern "C" { +#endif + + /** + * @brief System Clock Configuration + * @param None + * @retval None + */ +WEAK void SystemClock_Config() { + + 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_SCALE1); + + /**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 = 8; + RCC_OscInitStruct.PLL.PLLN = 336; + RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; + RCC_OscInitStruct.PLL.PLLQ = 7; + if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) { + _Error_Handler(__FILE__, __LINE__); + } + + /**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_DIV4; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; + + if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5) != HAL_OK) { + _Error_Handler(__FILE__, __LINE__); + } + + /**Configure the Systick interrupt time + */ + HAL_SYSTICK_Config(HAL_RCC_GetHCLKFreq() / 1000); + + /**Configure the Systick + */ + HAL_SYSTICK_CLKSourceConfig(SYSTICK_CLKSOURCE_HCLK); + + /* SysTick_IRQn interrupt configuration */ + HAL_NVIC_SetPriority(SysTick_IRQn, 0, 0); +} + +#ifdef __cplusplus +} +#endif diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/variant.h b/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/variant.h new file mode 100644 index 000000000000..1ba0a18d6af6 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/variant.h @@ -0,0 +1,322 @@ +/* + ******************************************************************************* + * 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. + ******************************************************************************* + */ +#pragma once + +#ifdef __cplusplus +extern "C" { +#endif // __cplusplus + +/*---------------------------------------------------------------------------- + * Pins + *----------------------------------------------------------------------------*/ + +#ifdef STM32F405RX + #define STM32F4X_PIN_NUM 64 //64 pins mcu, 51 gpio + #define STM32F4X_GPIO_NUM 51 + #define STM32F4X_ADC_NUM 16 +#elif defined(STM32F407_5VX) + #define STM32F4X_PIN_NUM 100 //100 pins mcu, 82 gpio + #define STM32F4X_GPIO_NUM 82 + #define STM32F4X_ADC_NUM 16 +#elif defined(STM32F407_5ZX) + #define STM32F4X_PIN_NUM 144 //144 pins mcu, 114 gpio + #define STM32F4X_GPIO_NUM 114 + #define STM32F4X_ADC_NUM 24 +#elif defined(STM32F407IX) + #define STM32F4X_PIN_NUM 176 //176 pins mcu, 140 gpio + #define STM32F4X_GPIO_NUM 140 + #define STM32F4X_ADC_NUM 24 +#else + #error "no match MCU defined" +#endif + +#if STM32F4X_PIN_NUM >= 64 //64 pins mcu, 51 gpio + #define PC13 0 + #define PC14 1 //OSC32_IN + #define PC15 2 //OSC32_OUT + #define PH0 3 //OSC_IN + #define PH1 4 //OSC_OUT + #define PB2 5 //BOOT1 + #define PB10 6 //1:SPI2_SCK / I2C2_SCL / USART3_TX / TIM2_CH3 + #define PB11 7 //1:I2C2_SDA / USART3_RX / TIM2_CH4 + #define PB12 8 //1:SPI2_NSS / OTG_HS_ID + #define PB13 9 //1:SPI2_SCK 2:OTG_HS_VBUS + #define PB14 10 //1:SPI2_MISO / TIM12_CH1 / OTG_HS_DM + #define PB15 11 //SPI2_MOSI / TIM12_CH2 / OTG_HS_DP + #define PC6 12 //1:TIM8_CH1 / SDIO_D6 / USART6_TX / TIM3_CH1 + #define PC7 13 //1:TIM8_CH2 / SDIO_D7 / USART6_RX / TIM3_CH2 + #define PC8 14 //1:TIM8_CH3 / SDIO_D0 / TIM3_CH3 + #define PC9 15 //1:TIM8_CH4 / SDIO_D1 / TIM3_CH4 + #define PA8 16 //1:TIM1_CH1 / I2C3_SCL / OTG_FS_SOF + #define PA9 17 //1:USART1_TX / TIM1_CH2 2:OTG_FS_VBUS + #define PA10 18 //1:USART1_RX / TIM1_CH3 / OTG_FS_ID + #define PA11 19 //1:TIM1_CH4 / OTG_FS_DM + #define PA12 20 //1:OTG_FS_DP + #define PA13 21 //0:JTMS-SWDIO + #define PA14 22 //0:JTCK-SWCLK + #define PA15 23 //0:JTDI 1:SPI3_NSS / SPI1_NSS + #define PC10 24 //1:UART4_TX / SPI3_SCK / SDIO_D2 / USART3_TX + #define PC11 25 //1:UART4_RX / SPI3_MISO / SDIO_D3 / USART3_RX + #define PC12 26 //1:UART5_TX / SPI3_MOSI / SDIO_CK + #define PD2 27 //1:UART5_RX / SDIO_CMD + #define PB3 28 //0:JTDO 1:SPI3_SCK / TIM2_CH2 / SPI1_SCK + #define PB4 29 //0:NJTRST 1:SPI3_MISO / TIM3_CH1 / SPI1_MISO + #define PB5 30 //1:TIM3_CH2 / SPI1_MOSI / SPI3_MOSI + #define PB6 31 //1:I2C1_SCL / TIM4_CH1 / USART1_TX + #define PB7 32 //1:I2C1_SDA / TIM4_CH2 / USART1_RX + #define PB8 33 //1:I2C1_SCL / TIM4_CH3 / SDIO_D4 / TIM10_CH1 + #define PB9 34 //1:I2C1_SDA / TIM4_CH4 / SDIO_D5 / TIM11_CH1 / SPI2_NSS + #define PA0 35 //1:UART4_TX / TIM5_CH1 2:ADC123_IN0 + #define PA1 36 //1:UART4_RX / TIM5_CH2 / TIM2_CH2 2:ADC123_IN1 + #define PA2 37 //1:USART2_TX /TIM5_CH3 / TIM9_CH1 / TIM2_CH3 2:ADC123_IN2 + #define PA3 38 //1:USART2_RX /TIM5_CH4 / TIM9_CH2 / TIM2_CH4 2:ADC123_IN3 + #define PA4 39 //NOT FT 1:SPI1_NSS / SPI3_NSS / USART2_CK 2:ADC12_IN4 / DAC_OUT1 + #define PA5 40 //NOT FT 1:SPI1_SCK 2:ADC12_IN5 / DAC_OUT2 + #define PA6 41 //1:SPI1_MISO / TIM13_CH1 / TIM3_CH1 2:ADC12_IN6 + #define PA7 42 //1:SPI1_MOSI / TIM14_CH1 / TIM3_CH2 2:ADC12_IN7 + #define PB0 43 //1:TIM3_CH3 2:ADC12_IN8 + #define PB1 44 //1:TIM3_CH4 2:ADC12_IN9 + #define PC0 45 //1: 2:ADC123_IN10 + #define PC1 46 //1: 2:ADC123_IN11 + #define PC2 47 //1:SPI2_MISO 2:ADC123_IN12 + #define PC3 48 //1:SPI2_MOSI 2:ADC123_IN13 + #define PC4 49 //1: 2:ADC12_IN14 + #define PC5 50 //1: 2:ADC12_IN15 + #if STM32F4X_PIN_NUM >= 144 + #define PF3 51 //1:FSMC_A3 2:ADC3_IN9 + #define PF4 52 //1:FSMC_A4 2:ADC3_IN14 + #define PF5 53 //1:FSMC_A5 2:ADC3_IN15 + #define PF6 54 //1:TIM10_CH1 2:ADC3_IN4 + #define PF7 55 //1:TIM11_CH1 2:ADC3_IN5 + #define PF8 56 //1:TIM13_CH1 2:ADC3_IN6 + #define PF9 57 //1;TIM14_CH1 2:ADC3_IN7 + #define PF10 58 //2:ADC3_IN8 + #endif +#endif +#if STM32F4X_PIN_NUM >= 100 //100 pins mcu, 82 gpio + #define PE2 (35+STM32F4X_ADC_NUM) //1:FSMC_A23 + #define PE3 (36+STM32F4X_ADC_NUM) //1:FSMC_A19 + #define PE4 (37+STM32F4X_ADC_NUM) //1:FSMC_A20 + #define PE5 (38+STM32F4X_ADC_NUM) //1:FSMC_A21 + #define PE6 (39+STM32F4X_ADC_NUM) //1:FSMC_A22 + #define PE7 (40+STM32F4X_ADC_NUM) //1:FSMC_D4 + #define PE8 (41+STM32F4X_ADC_NUM) //1:FSMC_D5 + #define PE9 (42+STM32F4X_ADC_NUM) //1:FSMC_D6 / TIM1_CH1 + #define PE10 (43+STM32F4X_ADC_NUM) //1:FSMC_D7 + #define PE11 (44+STM32F4X_ADC_NUM) //1:FSMC_D8 / TIM1_CH2 + #define PE12 (45+STM32F4X_ADC_NUM) //1:FSMC_D9 + #define PE13 (46+STM32F4X_ADC_NUM) //1:FSMC_D10 / TIM1_CH3 + #define PE14 (47+STM32F4X_ADC_NUM) //1:FSMC_D11 / TIM1_CH4 + #define PE15 (48+STM32F4X_ADC_NUM) //1:FSMC_D12 + #define PD8 (49+STM32F4X_ADC_NUM) //1:FSMC_D13 / USART3_TX + #define PD9 (50+STM32F4X_ADC_NUM) //1:FSMC_D14 / USART3_RX + #define PD10 (51+STM32F4X_ADC_NUM) //1:FSMC_D15 + #define PD11 (52+STM32F4X_ADC_NUM) //1:FSMC_A16 + #define PD12 (53+STM32F4X_ADC_NUM) //1:FSMC_A17 / TIM4_CH1 + #define PD13 (54+STM32F4X_ADC_NUM) //1:FSMC_A18 / TIM4_CH2 + #define PD14 (55+STM32F4X_ADC_NUM) //1:FSMC_D0 / TIM4_CH3 + #define PD15 (56+STM32F4X_ADC_NUM) //1:FSMC_D1 / TIM4_CH4 + #define PD0 (57+STM32F4X_ADC_NUM) //1:FSMC_D2 + #define PD1 (58+STM32F4X_ADC_NUM) //1:FSMC_D3 + #define PD3 (59+STM32F4X_ADC_NUM) //1:FSMC_CLK + #define PD4 (60+STM32F4X_ADC_NUM) //1:FSMC_NOE + #define PD5 (61+STM32F4X_ADC_NUM) //1:USART2_TX + #define PD6 (62+STM32F4X_ADC_NUM) //1:USART2_RX + #define PD7 (63+STM32F4X_ADC_NUM) + #define PE0 (64+STM32F4X_ADC_NUM) + #define PE1 (65+STM32F4X_ADC_NUM) +#endif +#if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio + #define PF0 (66+STM32F4X_ADC_NUM) //1:FSMC_A0 / I2C2_SDA + #define PF1 (67+STM32F4X_ADC_NUM) //1:FSMC_A1 / I2C2_SCL + #define PF2 (68+STM32F4X_ADC_NUM) //1:FSMC_A2 + #define PF11 (69+STM32F4X_ADC_NUM) + #define PF12 (70+STM32F4X_ADC_NUM) //1:FSMC_A6 + #define PF13 (71+STM32F4X_ADC_NUM) //1:FSMC_A7 + #define PF14 (72+STM32F4X_ADC_NUM) //1:FSMC_A8 + #define PF15 (73+STM32F4X_ADC_NUM) //1:FSMC_A9 + #define PG0 (74+STM32F4X_ADC_NUM) //1:FSMC_A10 + #define PG1 (75+STM32F4X_ADC_NUM) //1:FSMC_A11 + #define PG2 (76+STM32F4X_ADC_NUM) //1:FSMC_A12 + #define PG3 (77+STM32F4X_ADC_NUM) //1:FSMC_A13 + #define PG4 (78+STM32F4X_ADC_NUM) //1:FSMC_A14 + #define PG5 (79+STM32F4X_ADC_NUM) //1:FSMC_A15 + #define PG6 (80+STM32F4X_ADC_NUM) + #define PG7 (81+STM32F4X_ADC_NUM) + #define PG8 (82+STM32F4X_ADC_NUM) + #define PG9 (83+STM32F4X_ADC_NUM) //1:USART6_RX + #define PG10 (84+STM32F4X_ADC_NUM) //1:FSMC_NE3 + #define PG11 (85+STM32F4X_ADC_NUM) + #define PG12 (86+STM32F4X_ADC_NUM) //1:FSMC_NE4 + #define PG13 (87+STM32F4X_ADC_NUM) //1:FSMC_A24 + #define PG14 (88+STM32F4X_ADC_NUM) //1:FSMC_A25 / USART6_TX + #define PG15 (89+STM32F4X_ADC_NUM) +#endif +#if STM32F4X_PIN_NUM >= 176 //176 pins mcu, 140 gpio + #define PI8 (90+STM32F4X_ADC_NUM) + #define PI9 (91+STM32F4X_ADC_NUM) + #define PI10 (92+STM32F4X_ADC_NUM) + #define PI11 (93+STM32F4X_ADC_NUM) + #define PH2 (94+STM32F4X_ADC_NUM) + #define PH3 (95+STM32F4X_ADC_NUM) + #define PH4 (96+STM32F4X_ADC_NUM) //1:I2C2_SCL + #define PH5 (97+STM32F4X_ADC_NUM) //1:I2C2_SDA + #define PH6 (98+STM32F4X_ADC_NUM) //1:TIM12_CH1 + #define PH7 (99+STM32F4X_ADC_NUM) //1:I2C3_SCL + #define PH8 (100+STM32F4X_ADC_NUM) //1:I2C3_SDA + #define PH9 (101+STM32F4X_ADC_NUM) //1:TIM12_CH2 + #define PH10 (102+STM32F4X_ADC_NUM) //1:TIM5_CH1 + #define PH11 (103+STM32F4X_ADC_NUM) //1:TIM5_CH2 + #define PH12 (104+STM32F4X_ADC_NUM) //1:TIM5_CH3 + #define PH13 (105+STM32F4X_ADC_NUM) + #define PH14 (106+STM32F4X_ADC_NUM) + #define PH15 (107+STM32F4X_ADC_NUM) + #define PI0 (108+STM32F4X_ADC_NUM) //1:TIM5_CH4 / SPI2_NSS + #define PI1 (109+STM32F4X_ADC_NUM) //1:SPI2_SCK + #define PI2 (110+STM32F4X_ADC_NUM) //1:TIM8_CH4 /SPI2_MISO + #define PI3 (111+STM32F4X_ADC_NUM) //1:SPI2_MOS + #define PI4 (112+STM32F4X_ADC_NUM) + #define PI5 (113+STM32F4X_ADC_NUM) //1:TIM8_CH1 + #define PI6 (114+STM32F4X_ADC_NUM) //1:TIM8_CH2 + #define PI7 (115+STM32F4X_ADC_NUM) //1:TIM8_CH3 +#endif + + +// This must be a literal +#define NUM_DIGITAL_PINS (STM32F4X_GPIO_NUM) +// This must be a literal with a value less than or equal to MAX_ANALOG_INPUTS +#define NUM_ANALOG_INPUTS (STM32F4X_ADC_NUM) +#define NUM_ANALOG_FIRST 35 + +// Below ADC, DAC and PWM definitions already done in the core +// Could be redefined here if needed +// ADC resolution is 12bits +//#define ADC_RESOLUTION 12 +//#define DACC_RESOLUTION 12 + +// PWM resolution +/* + * BEWARE: + * Changing this value from the default (1000) will affect the PWM output value of analogWrite (to a PWM pin) + * Since the pin is toggled on capture, if you change the frequency of the timer you have to adapt the compare value (analogWrite thinks you did) + */ +//#define PWM_FREQUENCY 20000 +//The bottom values are the default and don't need to be redefined +//#define PWM_RESOLUTION 8 +//#define PWM_MAX_DUTY_CYCLE 255 + +// On-board LED pin number +#define LED_BUILTIN PA7 +#define LED_GREEN LED_BUILTIN + +// Below SPI and I2C definitions already done in the core +// Could be redefined here if differs from the default one +// SPI Definitions +#define PIN_SPI_MOSI PB15 +#define PIN_SPI_MISO PB14 +#define PIN_SPI_SCK PB13 +#define PIN_SPI_SS PB12 + +// I2C Definitions +#if STM32F4X_PIN_NUM >= 176 + #define PIN_WIRE_SDA PH5 + #define PIN_WIRE_SCL PH4 +#else + #define PIN_WIRE_SDA PB7 + #define PIN_WIRE_SCL PB6 +#endif + +// Timer Definitions +//Do not use timer used by PWM pins when possible. See PinMap_PWM in PeripheralPins.c +#define TIMER_TONE TIM2 +#define TIMER_SERVO TIM5 // Only 1 Servo PIN on SKR-PRO, so use the same timer as defined in PeripheralPins +#define TIMER_SERIAL TIM7 + +// UART Definitions +//#define ENABLE_HWSERIAL1 done automatically by the #define SERIAL_UART_INSTANCE below +#define ENABLE_HWSERIAL3 +#define ENABLE_HWSERIAL6 + +// Define here Serial instance number to map on Serial generic name (if not already used by SerialUSB) +#define SERIAL_UART_INSTANCE 1 //1 for Serial = Serial1 (USART1) + +// DEBUG_UART could be redefined to print on another instance than 'Serial' +//#define DEBUG_UART ((USART_TypeDef *) U(S)ARTX) // ex: USART3 +// DEBUG_UART baudrate, default: 9600 if not defined +//#define DEBUG_UART_BAUDRATE x +// DEBUG_UART Tx pin name, default: the first one found in PinMap_UART_TX for DEBUG_UART +//#define DEBUG_PINNAME_TX PX_n // PinName used for TX + +// Default pin used for 'Serial' instance (ex: ST-Link) +// Mandatory for Firmata +#define PIN_SERIAL_RX PA10 +#define PIN_SERIAL_TX PA9 + +// Optional PIN_SERIALn_RX and PIN_SERIALn_TX where 'n' is the U(S)ART number +// Used when user instanciate a hardware Serial using its peripheral name. +// Example: HardwareSerial mySerial(USART3); +// will use PIN_SERIAL3_RX and PIN_SERIAL3_TX if defined. +#define PIN_SERIAL1_RX PA10 +#define PIN_SERIAL1_TX PA9 +#define PIN_SERIAL3_RX PD9 +#define PIN_SERIAL3_TX PD8 +#define PIN_SERIAL6_RX PC7 +#define PIN_SERIAL6_TX PC6 +//#define PIN_SERIALLP1_RX x // For LPUART1 RX +//#define PIN_SERIALLP1_TX x // For LPUART1 TX + +#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 +#define SERIAL_PORT_HARDWARE_OPEN Serial3 +#define SERIAL_PORT_HARDWARE_OPEN1 Serial6 +#endif diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/PeripheralPins.c b/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/PeripheralPins.c index a28e712e0d39..6dc8b05158b3 100644 --- a/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/PeripheralPins.c +++ b/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/PeripheralPins.c @@ -94,7 +94,7 @@ const PinMap PinMap_I2C_SDA[] = { #if STM32F4X_PIN_NUM >= 176 {PH_5, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, {PH_8, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, - #else + #else {PF_0, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, #endif #endif @@ -113,7 +113,7 @@ const PinMap PinMap_I2C_SCL[] = { //{PF_1, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, {PH_4, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, {PH_7, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, - #else + #else {PF_1, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, #endif #endif @@ -152,8 +152,8 @@ 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 BLTOUCH is a "servo" - {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 BLTOUCH is a "servo" + //{PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 BLTOUCH is a "servo" + //{PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 BLTOUCH is a "servo" //{PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 //{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 @@ -186,7 +186,7 @@ const PinMap PinMap_PWM[] = { //{PB_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 //{PB_9, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1 //{PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 - {PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 + //{PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 //{PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N //{PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N //{PB_14, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N @@ -199,15 +199,15 @@ const PinMap PinMap_PWM[] = { //{PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 //{PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 //{PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 - {PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 - {PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 + //{PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 + //{PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 //{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_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_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 + //{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 #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio //{PF_6, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1 //{PF_7, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1 @@ -295,8 +295,7 @@ const PinMap PinMap_UART_CTS[] = { #ifdef HAL_SPI_MODULE_ENABLED const PinMap PinMap_SPI_MOSI[] = { - //{PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, - {PA_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, + {PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)}, {PB_15, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, {PC_12, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, {NC, NP, 0} diff --git a/buildroot/share/tests/LPC1768-tests b/buildroot/share/tests/LPC1768-tests index 566cbd27a643..332d22396e67 100755 --- a/buildroot/share/tests/LPC1768-tests +++ b/buildroot/share/tests/LPC1768-tests @@ -16,6 +16,7 @@ set -e restore_configs opt_set MOTHERBOARD BOARD_RAMPS_14_RE_ARM_EFB opt_enable VIKI2 SDSUPPORT SERIAL_PORT_2 NEOPIXEL_LED + opt_set NEOPIXEL_PIN P1_16 exec_test $1 $2 "ReARM EFB VIKI2, SDSUPPORT, 2 Serial ports (USB CDC + UART0), NeoPixel" @@ -43,7 +44,8 @@ opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER SDSUPPORT ADAPTIVE_FAN_ BABYSTEPPING BABYSTEP_XY BABYSTEP_ZPROBE_OFFSET BABYSTEP_ZPROBE_GFX_OVERLAY \ PRINTCOUNTER NOZZLE_PARK_FEATURE NOZZLE_CLEAN_FEATURE SLOW_PWM_HEATERS PIDTEMPBED EEPROM_SETTINGS INCH_MODE_SUPPORT TEMPERATURE_UNITS_SUPPORT \ Z_SAFE_HOMING ADVANCED_PAUSE_FEATURE PARK_HEAD_ON_PAUSE \ - LCD_INFO_MENU ARC_SUPPORT BEZIER_CURVE_SUPPORT EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES SDCARD_SORT_ALPHA + HOST_KEEPALIVE_FEATURE HOST_ACTION_COMMANDS HOST_PROMPT_SUPPORT \ + LCD_INFO_MENU ARC_SUPPORT BEZIER_CURVE_SUPPORT EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES SDCARD_SORT_ALPHA EMERGENCY_PARSER opt_set GRID_MAX_POINTS_X 16 opt_set NOZZLE_TO_PROBE_OFFSET "{ 0, 0, 0 }" exec_test $1 $2 "Re-ARM with NOZZLE_AS_PROBE and many features." diff --git a/buildroot/share/tests/LPC1769-tests b/buildroot/share/tests/LPC1769-tests index 1dda5ec417db..53a7b2818908 100755 --- a/buildroot/share/tests/LPC1769-tests +++ b/buildroot/share/tests/LPC1769-tests @@ -22,7 +22,7 @@ opt_enable VIKI2 SDSUPPORT ADAPTIVE_FAN_SLOWING NO_FAN_SLOWING_IN_PID_TUNING \ BABYSTEPPING BABYSTEP_XY BABYSTEP_ZPROBE_OFFSET BABYSTEP_ZPROBE_GFX_OVERLAY \ PRINTCOUNTER NOZZLE_PARK_FEATURE NOZZLE_CLEAN_FEATURE SLOW_PWM_HEATERS PIDTEMPBED EEPROM_SETTINGS INCH_MODE_SUPPORT TEMPERATURE_UNITS_SUPPORT \ Z_SAFE_HOMING ADVANCED_PAUSE_FEATURE PARK_HEAD_ON_PAUSE \ - LCD_INFO_MENU ARC_SUPPORT BEZIER_CURVE_SUPPORT EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES SDCARD_SORT_ALPHA + LCD_INFO_MENU ARC_SUPPORT BEZIER_CURVE_SUPPORT EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES SDCARD_SORT_ALPHA EMERGENCY_PARSER opt_set GRID_MAX_POINTS_X 16 exec_test $1 $2 "Smoothieboard with many features" diff --git a/buildroot/share/tests/mega2560-tests b/buildroot/share/tests/mega2560-tests index b17d60ba895e..ed5713eff8a1 100755 --- a/buildroot/share/tests/mega2560-tests +++ b/buildroot/share/tests/mega2560-tests @@ -71,8 +71,9 @@ opt_set NUM_SERVOS 1 opt_enable ZONESTAR_LCD Z_PROBE_SERVO_NR Z_SERVO_ANGLES DEACTIVATE_SERVOS_AFTER_MOVE BOOT_MARLIN_LOGO_ANIMATED \ AUTO_BED_LEVELING_3POINT DEBUG_LEVELING_FEATURE EEPROM_SETTINGS EEPROM_CHITCHAT M114_DETAIL \ NO_VOLUMETRICS EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES AUTOTEMP G38_PROBE_TARGET JOYSTICK \ - PRUSA_MMU2 MMU2_MENUS PRUSA_MMU2_S_MODE FILAMENT_RUNOUT_SENSOR NOZZLE_PARK_FEATURE ADVANCED_PAUSE_FEATURE Z_SAFE_HOMING -exec_test $1 $2 "RAMPS | ZONESTAR_LCD | MMU2 | Servo Probe | ABL 3-Pt | Debug Leveling | EEPROM | G38 ..." + PRUSA_MMU2 MMU2_MENUS PRUSA_MMU2_S_MODE DIRECT_STEPPING \ + FILAMENT_RUNOUT_SENSOR NOZZLE_PARK_FEATURE ADVANCED_PAUSE_FEATURE Z_SAFE_HOMING +exec_test $1 $2 "RAMPS | ZONESTAR + Chinese | MMU2 | Servo | 3-Point + Debug | G38 ..." # # Test MINIRAMBO with PWM_MOTOR_CURRENT and many features diff --git a/buildroot/share/tests/rambo-tests b/buildroot/share/tests/rambo-tests index 7fab4fc6ca0e..fbe27a265832 100644 --- a/buildroot/share/tests/rambo-tests +++ b/buildroot/share/tests/rambo-tests @@ -6,33 +6,6 @@ # exit on first failure set -e -# -# Build with the default configurations -# -restore_configs -opt_set MOTHERBOARD BOARD_EINSY_RAMBO -opt_set X_DRIVER_TYPE TMC2130 -opt_set Y_DRIVER_TYPE TMC2130 -opt_set Z_DRIVER_TYPE TMC2130 -opt_set E0_DRIVER_TYPE TMC2130 -exec_test $1 $2 "Default Configuration" - -# -# Full size Rambo Dual Endstop CNC -# -restore_configs -opt_set MOTHERBOARD BOARD_RAMBO -opt_set EXTRUDERS 0 -opt_set TEMP_SENSOR_0 999 -opt_set DUMMY_THERMISTOR_999_VALUE 170 -opt_set DIGIPOT_MOTOR_CURRENT '{ 120, 120, 120, 120, 120 }' -opt_enable USE_XMAX_PLUG USE_YMAX_PLUG USE_ZMAX_PLUG \ - REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER REVERSE_ENCODER_DIRECTION SDSUPPORT EEPROM_SETTINGS \ - S_CURVE_ACCELERATION X_DUAL_STEPPER_DRIVERS X_DUAL_ENDSTOPS Y_DUAL_STEPPER_DRIVERS Y_DUAL_ENDSTOPS \ - ADAPTIVE_STEP_SMOOTHING CNC_COORDINATE_SYSTEMS GCODE_MOTION_MODES -opt_disable MIN_SOFTWARE_ENDSTOP_Z MAX_SOFTWARE_ENDSTOPS -exec_test $1 $2 "Rambo CNC Configuration" - # # Lots of options - Formerly the first Mega2560 test # @@ -68,5 +41,32 @@ opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER LCD_PROGRESS_BAR LCD_PROGRESS_BAR_TE HOST_ACTION_COMMANDS HOST_PROMPT_SUPPORT PINS_DEBUGGING MAX7219_DEBUG M114_DETAIL exec_test $1 $2 "RAMBO | EXTRUDERS 2 | CHAR LCD + SD | FIX Probe | ABL-Linear | Advanced Pause | PLR | LEDs ..." +# +# Full size Rambo Dual Endstop CNC +# +restore_configs +opt_set MOTHERBOARD BOARD_RAMBO +opt_set EXTRUDERS 0 +opt_set TEMP_SENSOR_0 999 +opt_set DUMMY_THERMISTOR_999_VALUE 170 +opt_set DIGIPOT_MOTOR_CURRENT '{ 120, 120, 120, 120, 120 }' +opt_enable USE_XMAX_PLUG USE_YMAX_PLUG USE_ZMAX_PLUG \ + REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER REVERSE_ENCODER_DIRECTION SDSUPPORT EEPROM_SETTINGS \ + S_CURVE_ACCELERATION X_DUAL_STEPPER_DRIVERS X_DUAL_ENDSTOPS Y_DUAL_STEPPER_DRIVERS Y_DUAL_ENDSTOPS \ + ADAPTIVE_STEP_SMOOTHING CNC_COORDINATE_SYSTEMS GCODE_MOTION_MODES +opt_disable MIN_SOFTWARE_ENDSTOP_Z MAX_SOFTWARE_ENDSTOPS +exec_test $1 $2 "Rambo CNC Configuration" + +# +# Build with the default configurations +# +restore_configs +opt_set MOTHERBOARD BOARD_EINSY_RAMBO +opt_set X_DRIVER_TYPE TMC2130 +opt_set Y_DRIVER_TYPE TMC2130 +opt_set Z_DRIVER_TYPE TMC2130 +opt_set E0_DRIVER_TYPE TMC2130 +exec_test $1 $2 "Einsy RAMBo with TMC2130" + # clean up restore_configs diff --git a/platformio.ini b/platformio.ini index 81855b3030f1..413b5201dae7 100644 --- a/platformio.ini +++ b/platformio.ini @@ -777,7 +777,7 @@ debug_init_break = [env:BIGTREE_GTR_V1_0] platform = ststm32@>=5.7.0 platform_packages = framework-arduinoststm32@${common.arduinoststm32_ver} -board = BigTree_SKR_Pro +board = BigTree_GTR_v1 extra_scripts = pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py build_flags = ${common.build_flags} -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 -DUSB_PRODUCT=\"STM32F407IG\"