Multi-line comments cleanup (#19535)

This commit is contained in:
qwewer0 2020-09-28 21:53:50 +02:00 committed by Scott Lahteine
parent 3453d2d17a
commit 04a712dacc
131 changed files with 11 additions and 176 deletions

View File

@ -34,7 +34,6 @@
* - Extra features * - Extra features
* *
* Advanced settings can be found in Configuration_adv.h * Advanced settings can be found in Configuration_adv.h
*
*/ */
#define CONFIGURATION_H_VERSION 020007 #define CONFIGURATION_H_VERSION 020007
@ -855,7 +854,6 @@
* - For simple switches connect... * - For simple switches connect...
* - normally-closed switches to GND and D32. * - normally-closed switches to GND and D32.
* - normally-open switches to 5V and D32. * - normally-open switches to 5V and D32.
*
*/ */
//#define Z_MIN_PROBE_PIN 32 // Pin 32 is the RAMPS default //#define Z_MIN_PROBE_PIN 32 // Pin 32 is the RAMPS default
@ -1567,7 +1565,6 @@
* *
* Caveats: The ending Z should be the same as starting Z. * Caveats: The ending Z should be the same as starting Z.
* Attention: EXPERIMENTAL. G-code arguments may change. * Attention: EXPERIMENTAL. G-code arguments may change.
*
*/ */
//#define NOZZLE_CLEAN_FEATURE //#define NOZZLE_CLEAN_FEATURE
@ -1720,7 +1717,6 @@
* *
* SD Card support is disabled by default. If your controller has an SD slot, * SD Card support is disabled by default. If your controller has an SD slot,
* you must uncomment the following option or it won't work. * you must uncomment the following option or it won't work.
*
*/ */
//#define SDSUPPORT //#define SDSUPPORT
@ -2343,7 +2339,6 @@
* *** CAUTION *** * *** CAUTION ***
* *
* LED Type. Enable only one of the following two options. * LED Type. Enable only one of the following two options.
*
*/ */
//#define RGB_LED //#define RGB_LED
//#define RGBW_LED //#define RGBW_LED

View File

@ -29,7 +29,6 @@
* Some of these settings can damage your printer if improperly set! * Some of these settings can damage your printer if improperly set!
* *
* Basic settings can be found in Configuration.h * Basic settings can be found in Configuration.h
*
*/ */
#define CONFIGURATION_ADV_H_VERSION 020007 #define CONFIGURATION_ADV_H_VERSION 020007
@ -738,7 +737,6 @@
* | 4 3 | 1 4 | 2 1 | 3 2 | * | 4 3 | 1 4 | 2 1 | 3 2 |
* | | | | | * | | | | |
* | 1 2 | 2 3 | 3 4 | 4 1 | * | 1 2 | 2 3 | 3 4 | 4 1 |
*
*/ */
#ifndef Z_STEPPER_ALIGN_XY #ifndef Z_STEPPER_ALIGN_XY
//#define Z_STEPPERS_ORIENTATION 0 //#define Z_STEPPERS_ORIENTATION 0
@ -1954,7 +1952,6 @@
* Be sure to turn off auto-retract during filament change. * Be sure to turn off auto-retract during filament change.
* *
* Note that M207 / M208 / M209 settings are saved to EEPROM. * Note that M207 / M208 / M209 settings are saved to EEPROM.
*
*/ */
//#define FWRETRACT //#define FWRETRACT
#if ENABLED(FWRETRACT) #if ENABLED(FWRETRACT)

View File

@ -15,6 +15,7 @@
* *
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>. * along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/ */
#pragma once #pragma once

View File

@ -48,7 +48,6 @@
* readMicroseconds() - Get the last-written servo pulse width in microseconds. * readMicroseconds() - Get the last-written servo pulse width in microseconds.
* attached() - Return true if a servo is attached. * attached() - Return true if a servo is attached.
* detach() - Stop an attached servo from pulsing its i/o pin. * detach() - Stop an attached servo from pulsing its i/o pin.
*
*/ */
#ifdef __AVR__ #ifdef __AVR__

View File

@ -15,6 +15,7 @@
* *
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>. * along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/ */
#pragma once #pragma once

View File

@ -759,7 +759,6 @@
* *
* All of the above can be avoided by defining FORCE_SOFT_SPI to force the * All of the above can be avoided by defining FORCE_SOFT_SPI to force the
* display to use software SPI. * display to use software SPI.
*
*/ */
void spiInit(uint8_t spiRate=6) { // Default to slowest rate if not specified) void spiInit(uint8_t spiRate=6) { // Default to slowest rate if not specified)

View File

@ -52,7 +52,6 @@
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
* ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/ */
#ifdef __SAM3X8E__ #ifdef __SAM3X8E__

View File

@ -53,7 +53,6 @@
* per page. We can't emulate EE endurance with FLASH for all * per page. We can't emulate EE endurance with FLASH for all
* bytes, but we can emulate endurance for a given percent of * bytes, but we can emulate endurance for a given percent of
* bytes. * bytes.
*
*/ */
//#define EE_EMU_DEBUG //#define EE_EMU_DEBUG

View File

@ -179,5 +179,4 @@ void pwm_details(int32_t pin) {
* ----------------+-------- * ----------------+--------
* ID | PB11 * ID | PB11
* VBOF | PB10 * VBOF | PB10
*
*/ */

View File

@ -15,6 +15,7 @@
* *
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>. * along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/ */
#pragma once #pragma once

View File

@ -15,6 +15,7 @@
* *
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>. * along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/ */
#pragma once #pragma once

View File

@ -33,7 +33,6 @@
* Generic RingBuffer * Generic RingBuffer
* T type of the buffer array * T type of the buffer array
* S size of the buffer (must be power of 2) * S size of the buffer (must be power of 2)
*
*/ */
template <typename T, uint32_t S> class RingBuffer { template <typename T, uint32_t S> class RingBuffer {
public: public:

View File

@ -45,7 +45,6 @@
* Version 2 Copyright (c) 2009 Michael Margolis. All right reserved. * Version 2 Copyright (c) 2009 Michael Margolis. All right reserved.
* *
* The only modification was to update/delete macros to match the LPC176x. * The only modification was to update/delete macros to match the LPC176x.
*
*/ */
#include <stdint.h> #include <stdint.h>

View File

@ -46,7 +46,6 @@
* Version 2 Copyright (c) 2009 Michael Margolis. All right reserved. * Version 2 Copyright (c) 2009 Michael Margolis. All right reserved.
* *
* The only modification was to update/delete macros to match the LPC176x. * The only modification was to update/delete macros to match the LPC176x.
*
*/ */
#include <Servo.h> #include <Servo.h>

View File

@ -21,7 +21,6 @@
#pragma once #pragma once
/** /**
*
* HAL For LPC1768 * HAL For LPC1768
*/ */

View File

@ -24,7 +24,6 @@
* THE SOFTWARE. * THE SOFTWARE.
* *
* Derived from Adafruit_SPIFlash class with no SdFat references * Derived from Adafruit_SPIFlash class with no SdFat references
*
*/ */
#pragma once #pragma once

View File

@ -150,5 +150,4 @@ void pwm_details(int32_t pin) {
* 93 | PA10 | QSPI: IO2 * 93 | PA10 | QSPI: IO2
* 94 | PA11 | QSPI: IO3 * 94 | PA11 | QSPI: IO3
* 95 | PB31 | SD: DETECT * 95 | PB31 | SD: DETECT
*
*/ */

View File

@ -9,7 +9,6 @@
* No restriction on use. You can use, modify and redistribute it for * No restriction on use. You can use, modify and redistribute it for
* personal, non-profit or commercial products UNDER YOUR RESPONSIBILITY. * personal, non-profit or commercial products UNDER YOUR RESPONSIBILITY.
* Redistributions of source code must retain the above copyright notice. * Redistributions of source code must retain the above copyright notice.
*
*/ */
#include "../../inc/MarlinConfig.h" #include "../../inc/MarlinConfig.h"

View File

@ -22,7 +22,6 @@
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE. * THE SOFTWARE.
*
*/ */
#if defined(STM32GENERIC) && defined(STM32F7) #if defined(STM32GENERIC) && defined(STM32F7)
@ -662,7 +661,6 @@ boolean TMC26XStepper::isEnabled() { return !!(chopper_config_register & T_OFF_P
/** /**
* reads a value from the TMC26X status register. The value is not obtained directly but can then * reads a value from the TMC26X status register. The value is not obtained directly but can then
* be read by the various status routines. * be read by the various status routines.
*
*/ */
void TMC26XStepper::readStatus(char read_value) { void TMC26XStepper::readStatus(char read_value) {
uint32_t old_driver_configuration_register_value = driver_configuration_register_value; uint32_t old_driver_configuration_register_value = driver_configuration_register_value;

View File

@ -22,7 +22,6 @@
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE. * THE SOFTWARE.
*
*/ */
#pragma once #pragma once

View File

@ -16,6 +16,7 @@
* *
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>. * along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/ */
#pragma once #pragma once

View File

@ -16,6 +16,7 @@
* *
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>. * along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/ */
#pragma once #pragma once

View File

@ -48,7 +48,6 @@
* readMicroseconds() - Get the last-written servo pulse width in microseconds. * readMicroseconds() - Get the last-written servo pulse width in microseconds.
* attached() - Return true if a servo is attached. * attached() - Return true if a servo is attached.
* detach() - Stop an attached servo from pulsing its i/o pin. * detach() - Stop an attached servo from pulsing its i/o pin.
*
*/ */
#include "../../inc/MarlinConfig.h" #include "../../inc/MarlinConfig.h"

View File

@ -41,7 +41,6 @@
*/ */
/** /**
*
* A servo is activated by creating an instance of the Servo class passing the desired pin to the attach() method. * A servo is activated by creating an instance of the Servo class passing the desired pin to the attach() method.
* The servos are pulsed in the background using the value most recently written using the write() method * The servos are pulsed in the background using the value most recently written using the write() method
* *

View File

@ -348,7 +348,6 @@
* However, internal to Marlin E0/T0 is the first tool, and * However, internal to Marlin E0/T0 is the first tool, and
* most board silkscreens say "E0." Zero-based labels will * most board silkscreens say "E0." Zero-based labels will
* make these indexes consistent but this defies expectation. * make these indexes consistent but this defies expectation.
*
*/ */
#if ENABLED(NUMBER_TOOLS_FROM_0) #if ENABLED(NUMBER_TOOLS_FROM_0)
#define LCD_FIRST_TOOL 0 #define LCD_FIRST_TOOL 0

View File

@ -236,9 +236,7 @@
} }
/** /**
*
* Generic case of a line crossing both X and Y Mesh lines. * Generic case of a line crossing both X and Y Mesh lines.
*
*/ */
xy_int8_t cnt = (istart - iend).ABS(); xy_int8_t cnt = (istart - iend).ABS();

View File

@ -816,7 +816,6 @@ int8_t I2CPositionEncodersMgr::parse() {
* Y Report on Y axis encoder, if present. * Y Report on Y axis encoder, if present.
* Z Report on Z axis encoder, if present. * Z Report on Z axis encoder, if present.
* E Report on E axis encoder, if present. * E Report on E axis encoder, if present.
*
*/ */
void I2CPositionEncodersMgr::M860() { void I2CPositionEncodersMgr::M860() {
if (parse()) return; if (parse()) return;
@ -846,7 +845,6 @@ void I2CPositionEncodersMgr::M860() {
* Y Report on Y axis encoder, if present. * Y Report on Y axis encoder, if present.
* Z Report on Z axis encoder, if present. * Z Report on Z axis encoder, if present.
* E Report on E axis encoder, if present. * E Report on E axis encoder, if present.
*
*/ */
void I2CPositionEncodersMgr::M861() { void I2CPositionEncodersMgr::M861() {
if (parse()) return; if (parse()) return;
@ -875,7 +873,6 @@ void I2CPositionEncodersMgr::M861() {
* Y Report on Y axis encoder, if present. * Y Report on Y axis encoder, if present.
* Z Report on Z axis encoder, if present. * Z Report on Z axis encoder, if present.
* E Report on E axis encoder, if present. * E Report on E axis encoder, if present.
*
*/ */
void I2CPositionEncodersMgr::M862() { void I2CPositionEncodersMgr::M862() {
if (parse()) return; if (parse()) return;
@ -905,7 +902,6 @@ void I2CPositionEncodersMgr::M862() {
* Y Report on Y axis encoder, if present. * Y Report on Y axis encoder, if present.
* Z Report on Z axis encoder, if present. * Z Report on Z axis encoder, if present.
* E Report on E axis encoder, if present. * E Report on E axis encoder, if present.
*
*/ */
void I2CPositionEncodersMgr::M863() { void I2CPositionEncodersMgr::M863() {
if (parse()) return; if (parse()) return;

View File

@ -710,13 +710,11 @@ void MMU2::tool_change(const uint8_t index) {
} }
/** /**
*
* Handle special T?/Tx/Tc commands * Handle special T?/Tx/Tc commands
* *
* T? Gcode to extrude shouldn't have to follow, load to extruder wheels is done automatically * T? Gcode to extrude shouldn't have to follow, load to extruder wheels is done automatically
* Tx Same as T?, except nozzle doesn't have to be preheated. Tc must be placed after extruder nozzle is preheated to finish filament load. * Tx Same as T?, except nozzle doesn't have to be preheated. Tc must be placed after extruder nozzle is preheated to finish filament load.
* Tc Load to nozzle after filament was prepared by Tx and extruder nozzle is already heated. * Tc Load to nozzle after filament was prepared by Tx and extruder nozzle is already heated.
*
*/ */
void MMU2::tool_change(const char* special) { void MMU2::tool_change(const char* special) {
if (!enabled) return; if (!enabled) return;
@ -922,9 +920,7 @@ void MMU2::filament_runout() {
} }
/** /**
*
* Switch material and load to nozzle * Switch material and load to nozzle
*
*/ */
bool MMU2::load_filament_to_nozzle(const uint8_t index) { bool MMU2::load_filament_to_nozzle(const uint8_t index) {

View File

@ -48,7 +48,6 @@ typedef void (*twiRequestFunc_t)();
* For more information see * For more information see
* - https://marlinfw.org/docs/gcode/M260.html * - https://marlinfw.org/docs/gcode/M260.html
* - https://marlinfw.org/docs/gcode/M261.html * - https://marlinfw.org/docs/gcode/M261.html
*
*/ */
class TWIBus { class TWIBus {
private: private:

View File

@ -160,7 +160,6 @@
* E By default G29 will engage the Z probe, test the bed, then disengage. * E By default G29 will engage the Z probe, test the bed, then disengage.
* Include "E" to engage/disengage the Z probe for each sample. * Include "E" to engage/disengage the Z probe for each sample.
* There's no extra effect if you have a fixed Z probe. * There's no extra effect if you have a fixed Z probe.
*
*/ */
G29_TYPE GcodeSuite::G29() { G29_TYPE GcodeSuite::G29() {

View File

@ -57,7 +57,6 @@ inline void echo_not_entered(const char c) { SERIAL_CHAR(c); SERIAL_ECHOLNPGM("
* S3 In Jn Zn.nn Manually modify a single point * S3 In Jn Zn.nn Manually modify a single point
* S4 Zn.nn Set z offset. Positive away from bed, negative closer to bed. * S4 Zn.nn Set z offset. Positive away from bed, negative closer to bed.
* S5 Reset and disable mesh * S5 Reset and disable mesh
*
*/ */
void GcodeSuite::G29() { void GcodeSuite::G29() {

View File

@ -192,7 +192,6 @@
* X Home to the X endstop * X Home to the X endstop
* Y Home to the Y endstop * Y Home to the Y endstop
* Z Home to the Z endstop * Z Home to the Z endstop
*
*/ */
void GcodeSuite::G28() { void GcodeSuite::G28() {
DEBUG_SECTION(log_G28, "G28", DEBUGGING(LEVELING)); DEBUG_SECTION(log_G28, "G28", DEBUGGING(LEVELING));

View File

@ -34,7 +34,6 @@
* *
* Sending "M999 S1" will resume printing without flushing the * Sending "M999 S1" will resume printing without flushing the
* existing command buffer. * existing command buffer.
*
*/ */
void GcodeSuite::M999() { void GcodeSuite::M999() {
marlin_state = MF_RUNNING; marlin_state = MF_RUNNING;

View File

@ -33,7 +33,6 @@
#include "../../../core/debug_out.h" #include "../../../core/debug_out.h"
/** /**
*
* M906: report or set KVAL_HOLD which sets the maximum effective voltage provided by the * M906: report or set KVAL_HOLD which sets the maximum effective voltage provided by the
* PWMs to the steppers * PWMs to the steppers
* *
@ -56,7 +55,6 @@
* *
* L6470 is used in the STEP-CLOCK mode. KVAL_HOLD is the only KVAL_xxx * L6470 is used in the STEP-CLOCK mode. KVAL_HOLD is the only KVAL_xxx
* that affects the effective voltage seen by the stepper. * that affects the effective voltage seen by the stepper.
*
*/ */
/** /**

View File

@ -37,7 +37,6 @@
#include "../../../core/debug_out.h" #include "../../../core/debug_out.h"
/** /**
*
* M916: increase KVAL_HOLD until get thermal warning * M916: increase KVAL_HOLD until get thermal warning
* NOTE - on L6474 it is TVAL that is used * NOTE - on L6474 it is TVAL that is used
* *
@ -62,7 +61,6 @@
* *
* D - time (in seconds) to run each setting of KVAL_HOLD/TVAL * D - time (in seconds) to run each setting of KVAL_HOLD/TVAL
* optional - defaults to zero (runs each setting once) * optional - defaults to zero (runs each setting once)
*
*/ */
/** /**
@ -187,7 +185,6 @@ void GcodeSuite::M916() {
} }
/** /**
*
* M917: Find minimum current thresholds * M917: Find minimum current thresholds
* *
* Decrease OCD current until overcurrent error * Decrease OCD current until overcurrent error
@ -214,7 +211,6 @@ void GcodeSuite::M916() {
* *
* K - value for KVAL_HOLD (0 - 255) (ignored for L6474) * K - value for KVAL_HOLD (0 - 255) (ignored for L6474)
* optional - will report current value from driver if not specified * optional - will report current value from driver if not specified
*
*/ */
void GcodeSuite::M917() { void GcodeSuite::M917() {
@ -522,7 +518,6 @@ void GcodeSuite::M917() {
} }
/** /**
*
* M918: increase speed until error or max feedrate achieved (as shown in configuration.h)) * M918: increase speed until error or max feedrate achieved (as shown in configuration.h))
* *
* J - select which driver(s) to monitor on multi-driver axis * J - select which driver(s) to monitor on multi-driver axis
@ -543,7 +538,6 @@ void GcodeSuite::M917() {
* *
* M - value for microsteps (1 - 128) (optional) * M - value for microsteps (1 - 128) (optional)
* optional - will report current value from driver if not specified * optional - will report current value from driver if not specified
*
*/ */
void GcodeSuite::M918() { void GcodeSuite::M918() {

View File

@ -42,7 +42,6 @@
* *
* M260 S1 ; Send the buffered data and reset the buffer * M260 S1 ; Send the buffered data and reset the buffer
* M260 R1 ; Reset the buffer without sending data * M260 R1 ; Reset the buffer without sending data
*
*/ */
void GcodeSuite::M260() { void GcodeSuite::M260() {
// Set the target address // Set the target address

View File

@ -39,7 +39,6 @@
* T[toolhead] - Select extruder to configure, active extruder if not specified * T[toolhead] - Select extruder to configure, active extruder if not specified
* U[distance] - Retract distance for removal, for the specified extruder * U[distance] - Retract distance for removal, for the specified extruder
* L[distance] - Extrude distance for insertion, for the specified extruder * L[distance] - Extrude distance for insertion, for the specified extruder
*
*/ */
void GcodeSuite::M603() { void GcodeSuite::M603() {

View File

@ -289,7 +289,6 @@
* "T" Codes * "T" Codes
* *
* T0-T3 - Select an extruder (tool) by index: "T<n> F<units/min>" * T0-T3 - Select an extruder (tool) by index: "T<n> F<units/min>"
*
*/ */
#include "../inc/MarlinConfig.h" #include "../inc/MarlinConfig.h"

View File

@ -38,7 +38,6 @@
* M32 !PATH/TO/FILE.GCO# ; Start FILE.GCO * M32 !PATH/TO/FILE.GCO# ; Start FILE.GCO
* M32 P !PATH/TO/FILE.GCO# ; Start FILE.GCO as a procedure * M32 P !PATH/TO/FILE.GCO# ; Start FILE.GCO as a procedure
* M32 S60 !PATH/TO/FILE.GCO# ; Start FILE.GCO at byte 60 * M32 S60 !PATH/TO/FILE.GCO# ; Start FILE.GCO at byte 60
*
*/ */
void GcodeSuite::M32() { void GcodeSuite::M32() {
if (IS_SD_PRINTING()) planner.synchronize(); if (IS_SD_PRINTING()) planner.synchronize();

View File

@ -512,7 +512,6 @@
* HOTENDS - Number of hotends, whether connected or separate * HOTENDS - Number of hotends, whether connected or separate
* E_STEPPERS - Number of actual E stepper motors * E_STEPPERS - Number of actual E stepper motors
* E_MANUAL - Number of E steppers for LCD move options * E_MANUAL - Number of E steppers for LCD move options
*
*/ */
#if EXTRUDERS == 0 #if EXTRUDERS == 0

View File

@ -11,7 +11,6 @@
* any later version. The code is distributed WITHOUT ANY WARRANTY; * any later version. The code is distributed WITHOUT ANY WARRANTY;
* without even the implied warranty of MERCHANTABILITY or FITNESS * without even the implied warranty of MERCHANTABILITY or FITNESS
* FOR A PARTICULAR PURPOSE. See the GNU GPL for more details. * FOR A PARTICULAR PURPOSE. See the GNU GPL for more details.
*
*/ */
/** /**

View File

@ -11,7 +11,6 @@
* any later version. The code is distributed WITHOUT ANY WARRANTY; * any later version. The code is distributed WITHOUT ANY WARRANTY;
* without even the implied warranty of MERCHANTABILITY or FITNESS * without even the implied warranty of MERCHANTABILITY or FITNESS
* FOR A PARTICULAR PURPOSE. See the GNU GPL for more details. * FOR A PARTICULAR PURPOSE. See the GNU GPL for more details.
*
*/ */
#pragma once #pragma once

View File

@ -51,7 +51,6 @@
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
* ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/ */
#include "../../inc/MarlinConfig.h" #include "../../inc/MarlinConfig.h"

View File

@ -1632,7 +1632,6 @@ void update_variable() {
* TODO: New code can follow the pattern of menu_media.cpp * TODO: New code can follow the pattern of menu_media.cpp
* and rely on Marlin caching for performance. No need to * and rely on Marlin caching for performance. No need to
* cache files here. * cache files here.
*
*/ */
#ifndef strcasecmp_P #ifndef strcasecmp_P

View File

@ -42,7 +42,6 @@ constexpr uint32_t flash_eeprom_version = 1;
* 0 16 DATA STORAGE AREA * 0 16 DATA STORAGE AREA
* 16 1 VERSIONING DATA * 16 1 VERSIONING DATA
* 17 inf MEDIA STORAGE AREA * 17 inf MEDIA STORAGE AREA
*
*/ */
#define DATA_STORAGE_SIZE_64K #define DATA_STORAGE_SIZE_64K

View File

@ -32,7 +32,6 @@
* Selecting an LCD Display * Selecting an LCD Display
* Version 2.1 * Version 2.1
* Issue Date: 2017-11-14 * Issue Date: 2017-11-14
*
*/ */
#define COMPUTE_REGS_FROM_DATASHEET \ #define COMPUTE_REGS_FROM_DATASHEET \
constexpr uint16_t Hoffset = thfp + thb - 1; \ constexpr uint16_t Hoffset = thfp + thb - 1; \

View File

@ -109,7 +109,6 @@ namespace FTDI {
* - Handles auto-repetition by sending onTouchHeld to the active screen periodically. * - Handles auto-repetition by sending onTouchHeld to the active screen periodically.
* - Plays touch feedback "click" sounds when appropriate. * - Plays touch feedback "click" sounds when appropriate.
* - Performs debouncing to supress spurious touch events. * - Performs debouncing to supress spurious touch events.
*
*/ */
void EventLoop::process_events() { void EventLoop::process_events() {
// If the LCD is processing commands, don't check // If the LCD is processing commands, don't check

View File

@ -49,7 +49,6 @@
* ... * ...
* } * }
* } * }
*
*/ */
class PolyReader { class PolyReader {

View File

@ -375,7 +375,6 @@ namespace ExtUI {
* constexpr float increment = 10; * constexpr float increment = 10;
* *
* UI_INCREMENT(TargetTemp_celsius, E0) * UI_INCREMENT(TargetTemp_celsius, E0)
*
*/ */
#define UI_INCREMENT_BY(method, inc, ...) ExtUI::set ## method(ExtUI::get ## method (__VA_ARGS__) + inc, ##__VA_ARGS__) #define UI_INCREMENT_BY(method, inc, ...) ExtUI::set ## method(ExtUI::get ## method (__VA_ARGS__) + inc, ##__VA_ARGS__)
#define UI_DECREMENT_BY(method, inc, ...) ExtUI::set ## method(ExtUI::get ## method (__VA_ARGS__) - inc, ##__VA_ARGS__) #define UI_DECREMENT_BY(method, inc, ...) ExtUI::set ## method(ExtUI::get ## method (__VA_ARGS__) - inc, ##__VA_ARGS__)

View File

@ -26,7 +26,6 @@
* *
* LCD Menu Messages * LCD Menu Messages
* See also https://marlinfw.org/docs/development/lcd_language.html * See also https://marlinfw.org/docs/development/lcd_language.html
*
*/ */
#define DISPLAY_CHARSET_ISO10646_1 #define DISPLAY_CHARSET_ISO10646_1

View File

@ -26,7 +26,6 @@
* *
* LCD Menu Messages * LCD Menu Messages
* See also https://marlinfw.org/docs/development/lcd_language.html * See also https://marlinfw.org/docs/development/lcd_language.html
*
*/ */
#define DISPLAY_CHARSET_ISO10646_5 #define DISPLAY_CHARSET_ISO10646_5

View File

@ -26,7 +26,6 @@
* *
* LCD Menu Messages * LCD Menu Messages
* See also https://marlinfw.org/docs/development/lcd_language.html * See also https://marlinfw.org/docs/development/lcd_language.html
*
*/ */
namespace Language_ca { namespace Language_ca {
using namespace Language_en; // Inherit undefined strings from English using namespace Language_en; // Inherit undefined strings from English

View File

@ -31,7 +31,6 @@
* Translated by Petr Zahradnik, Computer Laboratory * Translated by Petr Zahradnik, Computer Laboratory
* Blog and video blog Zahradnik se bavi * Blog and video blog Zahradnik se bavi
* https://www.zahradniksebavi.cz * https://www.zahradniksebavi.cz
*
*/ */
#define DISPLAY_CHARSET_ISO10646_CZ #define DISPLAY_CHARSET_ISO10646_CZ

View File

@ -26,7 +26,6 @@
* *
* LCD Menu Messages * LCD Menu Messages
* See also https://marlinfw.org/docs/development/lcd_language.html * See also https://marlinfw.org/docs/development/lcd_language.html
*
*/ */
#define DISPLAY_CHARSET_ISO10646_1 #define DISPLAY_CHARSET_ISO10646_1

View File

@ -26,7 +26,6 @@
* *
* LCD Menu Messages * LCD Menu Messages
* See also https://marlinfw.org/docs/development/lcd_language.html * See also https://marlinfw.org/docs/development/lcd_language.html
*
*/ */
namespace Language_de { namespace Language_de {

View File

@ -26,7 +26,6 @@
* *
* LCD Menu Messages * LCD Menu Messages
* See also https://marlinfw.org/docs/development/lcd_language.html * See also https://marlinfw.org/docs/development/lcd_language.html
*
*/ */
#define DISPLAY_CHARSET_ISO10646_GREEK #define DISPLAY_CHARSET_ISO10646_GREEK

View File

@ -26,7 +26,6 @@
* *
* LCD Menu Messages * LCD Menu Messages
* See also https://marlinfw.org/docs/development/lcd_language.html * See also https://marlinfw.org/docs/development/lcd_language.html
*
*/ */
#define DISPLAY_CHARSET_ISO10646_GREEK #define DISPLAY_CHARSET_ISO10646_GREEK

View File

@ -26,7 +26,6 @@
* *
* LCD Menu Messages * LCD Menu Messages
* See also https://marlinfw.org/docs/development/lcd_language.html * See also https://marlinfw.org/docs/development/lcd_language.html
*
*/ */
#define en 1234 #define en 1234

View File

@ -26,7 +26,6 @@
* *
* LCD Menu Messages * LCD Menu Messages
* See also https://marlinfw.org/docs/development/lcd_language.html * See also https://marlinfw.org/docs/development/lcd_language.html
*
*/ */
namespace Language_es { namespace Language_es {

View File

@ -26,7 +26,6 @@
* *
* LCD Menu Messages * LCD Menu Messages
* See also https://marlinfw.org/docs/development/lcd_language.html * See also https://marlinfw.org/docs/development/lcd_language.html
*
*/ */
#define DISPLAY_CHARSET_ISO10646_1 #define DISPLAY_CHARSET_ISO10646_1

View File

@ -26,7 +26,6 @@
* *
* LCD Menu Messages * LCD Menu Messages
* See also https://marlinfw.org/docs/development/lcd_language.html * See also https://marlinfw.org/docs/development/lcd_language.html
*
*/ */
#define DISPLAY_CHARSET_ISO10646_1 #define DISPLAY_CHARSET_ISO10646_1

View File

@ -26,7 +26,6 @@
* *
* LCD Menu Messages * LCD Menu Messages
* See also https://marlinfw.org/docs/development/lcd_language.html * See also https://marlinfw.org/docs/development/lcd_language.html
*
*/ */
#define DISPLAY_CHARSET_ISO10646_1 #define DISPLAY_CHARSET_ISO10646_1

View File

@ -26,7 +26,6 @@
* *
* LCD Menu Messages * LCD Menu Messages
* See also https://marlinfw.org/docs/development/lcd_language.html * See also https://marlinfw.org/docs/development/lcd_language.html
*
*/ */
#define DISPLAY_CHARSET_ISO10646_1 #define DISPLAY_CHARSET_ISO10646_1

View File

@ -26,7 +26,6 @@
* *
* LCD Menu Messages * LCD Menu Messages
* See also https://marlinfw.org/docs/development/lcd_language.html * See also https://marlinfw.org/docs/development/lcd_language.html
*
*/ */
#define DISPLAY_CHARSET_ISO10646_1 // use the better font on full graphic displays. #define DISPLAY_CHARSET_ISO10646_1 // use the better font on full graphic displays.

View File

@ -29,7 +29,6 @@
* A Magyar fordítást készítette: AntoszHUN * A Magyar fordítást készítette: AntoszHUN
* *
* *
*
*/ */
namespace Language_hu { namespace Language_hu {

View File

@ -26,7 +26,6 @@
* *
* LCD Menu Messages * LCD Menu Messages
* See also https://marlinfw.org/docs/development/lcd_language.html * See also https://marlinfw.org/docs/development/lcd_language.html
*
*/ */
#define DISPLAY_CHARSET_ISO10646_1 #define DISPLAY_CHARSET_ISO10646_1

View File

@ -27,7 +27,6 @@
* *
* LCD Menu Messages * LCD Menu Messages
* See also https://marlinfw.org/docs/development/lcd_language.html * See also https://marlinfw.org/docs/development/lcd_language.html
*
*/ */
//#define DISPLAY_CHARSET_ISO10646_KANA //#define DISPLAY_CHARSET_ISO10646_KANA

View File

@ -26,7 +26,6 @@
* *
* LCD Menu Messages * LCD Menu Messages
* See also https://marlinfw.org/docs/development/lcd_language.html * See also https://marlinfw.org/docs/development/lcd_language.html
*
*/ */
namespace Language_ko_KR { namespace Language_ko_KR {
using namespace Language_en; // Inherit undefined strings from English using namespace Language_en; // Inherit undefined strings from English

View File

@ -26,7 +26,6 @@
* *
* LCD Menu Messages * LCD Menu Messages
* See also https://marlinfw.org/docs/development/lcd_language.html * See also https://marlinfw.org/docs/development/lcd_language.html
*
*/ */
#define DISPLAY_CHARSET_ISO10646_1 #define DISPLAY_CHARSET_ISO10646_1

View File

@ -26,7 +26,6 @@
* *
* LCD Menu Messages * LCD Menu Messages
* See also https://marlinfw.org/docs/development/lcd_language.html * See also https://marlinfw.org/docs/development/lcd_language.html
*
*/ */
#define DISPLAY_CHARSET_ISO10646_PL #define DISPLAY_CHARSET_ISO10646_PL

View File

@ -27,7 +27,6 @@
* *
* LCD Menu Messages * LCD Menu Messages
* See also https://marlinfw.org/docs/development/lcd_language.html * See also https://marlinfw.org/docs/development/lcd_language.html
*
*/ */
#define DISPLAY_CHARSET_ISO10646_1 #define DISPLAY_CHARSET_ISO10646_1

View File

@ -27,7 +27,6 @@
* *
* LCD Menu Messages * LCD Menu Messages
* See also https://marlinfw.org/docs/development/lcd_language.html * See also https://marlinfw.org/docs/development/lcd_language.html
*
*/ */
namespace Language_pt_br { namespace Language_pt_br {
using namespace Language_en; // Inherit undefined strings from English using namespace Language_en; // Inherit undefined strings from English

View File

@ -26,7 +26,6 @@
* *
* LCD Menu Messages * LCD Menu Messages
* See also https://marlinfw.org/docs/development/lcd_language.html * See also https://marlinfw.org/docs/development/lcd_language.html
*
*/ */
#define DISPLAY_CHARSET_ISO10646_5 #define DISPLAY_CHARSET_ISO10646_5

View File

@ -30,7 +30,6 @@
* *
* Translated by Michal Holeš, Farma MaM * Translated by Michal Holeš, Farma MaM
* https://www.facebook.com/farmamam * https://www.facebook.com/farmamam
*
*/ */
#define DISPLAY_CHARSET_ISO10646_SK #define DISPLAY_CHARSET_ISO10646_SK

View File

@ -26,7 +26,6 @@
* *
* LCD Menu Messages * LCD Menu Messages
* See also https://marlinfw.org/docs/development/lcd_language.html * See also https://marlinfw.org/docs/development/lcd_language.html
*
*/ */
// Select ONE of the following Mappers. // Select ONE of the following Mappers.

View File

@ -30,7 +30,6 @@
* Bu çeviri dosyasındaki sorunlar ve düzeltmeler için iletişim; * Bu çeviri dosyasındaki sorunlar ve düzeltmeler için iletişim;
* Contact for issues and corrections in this translation file; * Contact for issues and corrections in this translation file;
* Yücel Temel - (info@elektromanyetix.com) - https://elektromanyetix.com/ * Yücel Temel - (info@elektromanyetix.com) - https://elektromanyetix.com/
*
*/ */
#define DISPLAY_CHARSET_ISO10646_TR #define DISPLAY_CHARSET_ISO10646_TR

View File

@ -26,7 +26,6 @@
* *
* LCD Menu Messages * LCD Menu Messages
* See also https://marlinfw.org/docs/development/lcd_language.html * See also https://marlinfw.org/docs/development/lcd_language.html
*
*/ */
#define DISPLAY_CHARSET_ISO10646_5 #define DISPLAY_CHARSET_ISO10646_5

View File

@ -26,7 +26,6 @@
* *
* LCD Menu Messages * LCD Menu Messages
* See also https://marlinfw.org/docs/development/lcd_language.html * See also https://marlinfw.org/docs/development/lcd_language.html
*
*/ */
namespace Language_vi { namespace Language_vi {
using namespace Language_en; // Inherit undefined strings from English using namespace Language_en; // Inherit undefined strings from English

View File

@ -26,7 +26,6 @@
* *
* LCD Menu Messages * LCD Menu Messages
* See also https://marlinfw.org/docs/development/lcd_language.html * See also https://marlinfw.org/docs/development/lcd_language.html
*
*/ */
namespace Language_zh_CN { namespace Language_zh_CN {
using namespace Language_en; // Inherit undefined strings from English using namespace Language_en; // Inherit undefined strings from English

View File

@ -26,7 +26,6 @@
* *
* LCD Menu Messages * LCD Menu Messages
* See also https://marlinfw.org/docs/development/lcd_language.html * See also https://marlinfw.org/docs/development/lcd_language.html
*
*/ */
namespace Language_zh_TW { namespace Language_zh_TW {
using namespace Language_en; // Inherit undefined strings from English using namespace Language_en; // Inherit undefined strings from English

View File

@ -101,9 +101,7 @@ void _menu_temp_filament_op(const PauseMode mode, const int8_t extruder) {
} }
/** /**
*
* "Change Filament" submenu * "Change Filament" submenu
*
*/ */
#if E_STEPPERS > 1 || ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) #if E_STEPPERS > 1 || ENABLED(FILAMENT_LOAD_UNLOAD_GCODES)

View File

@ -29,7 +29,6 @@
* it saves roughly 10K of program memory. It also does not require all of * it saves roughly 10K of program memory. It also does not require all of
* coordinates to be present during the calculations. Each point can be * coordinates to be present during the calculations. Each point can be
* probed and then discarded. * probed and then discarded.
*
*/ */
#include "../inc/MarlinConfig.h" #include "../inc/MarlinConfig.h"

View File

@ -30,7 +30,6 @@
* it saves roughly 10K of program memory. And even better... the data * it saves roughly 10K of program memory. And even better... the data
* fed into the algorithm does not need to all be present at the same time. * fed into the algorithm does not need to all be present at the same time.
* A point can be probed and its values fed into the algorithm and then discarded. * A point can be probed and its values fed into the algorithm and then discarded.
*
*/ */
#include "../inc/MarlinConfig.h" #include "../inc/MarlinConfig.h"

View File

@ -339,7 +339,6 @@ void Planner::init() {
* const uint32_t r = _BV(24) - x * d; // Estimate remainder * const uint32_t r = _BV(24) - x * d; // Estimate remainder
* if (r >= d) x++; // Check whether to adjust result * if (r >= d) x++; // Check whether to adjust result
* return uint32_t(x); // x holds the proper estimation * return uint32_t(x); // x holds the proper estimation
*
*/ */
static uint32_t get_period_inverse(uint32_t d) { static uint32_t get_period_inverse(uint32_t d) {
@ -2243,7 +2242,6 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
#define MAX_E_JERK(N) TERN(HAS_LINEAR_E_JERK, max_e_jerk[E_INDEX_N(N)], max_jerk.e) #define MAX_E_JERK(N) TERN(HAS_LINEAR_E_JERK, max_e_jerk[E_INDEX_N(N)], max_jerk.e)
/** /**
*
* Use LIN_ADVANCE for blocks if all these are true: * Use LIN_ADVANCE for blocks if all these are true:
* *
* esteps : This is a print move, because we checked for A, B, C steps before. * esteps : This is a print move, because we checked for A, B, C steps before.

View File

@ -24,7 +24,6 @@
* planner_bezier.cpp * planner_bezier.cpp
* *
* Compute and buffer movement commands for bezier curves * Compute and buffer movement commands for bezier curves
*
*/ */
#include "../inc/MarlinConfig.h" #include "../inc/MarlinConfig.h"

View File

@ -25,7 +25,6 @@
* planner_bezier.h * planner_bezier.h
* *
* Compute and buffer movement commands for Bézier curves * Compute and buffer movement commands for Bézier curves
*
*/ */
#include "../core/types.h" #include "../core/types.h"

View File

@ -729,7 +729,6 @@ float Probe::probe_at_point(const float &rx, const float &ry, const ProbePtRaise
* when starting up the machine or rebooting the board. * when starting up the machine or rebooting the board.
* There's no way to know where the nozzle is positioned until * There's no way to know where the nozzle is positioned until
* homing has been done - no homing with z-probe without init! * homing has been done - no homing with z-probe without init!
*
*/ */
STOW_Z_SERVO(); STOW_Z_SERVO();
} }

View File

@ -33,7 +33,6 @@
* ALSO: Variables in the Store and Retrieve sections must be in the same order. * ALSO: Variables in the Store and Retrieve sections must be in the same order.
* If a feature is disabled, some data must still be written that, when read, * If a feature is disabled, some data must still be written that, when read,
* either sets a Sane Default, or results in No Change to the existing value. * either sets a Sane Default, or results in No Change to the existing value.
*
*/ */
// Change EEPROM version if the structure changes // Change EEPROM version if the structure changes

View File

@ -26,11 +26,11 @@
// Resistance Tolerance + / -1% // Resistance Tolerance + / -1%
// B Value 3950K at 25/50 deg. C // B Value 3950K at 25/50 deg. C
// B Value Tolerance + / - 1% // B Value Tolerance + / - 1%
// Kis3d Silicone Heater 24V 200W/300W with 6mm Precision cast plate (EN AW 5083) // Kis3d Silicone Heater 24V 200W/300W with 6mm Precision cast plate (EN AW 5083)
// Temperature setting time 10 min to determine the 12Bit ADC value on the surface. (le3tspeak) // Temperature setting time 10 min to determine the 12Bit ADC value on the surface. (le3tspeak)
const temp_entry_t temptable_30[] PROGMEM = { const temp_entry_t temptable_30[] PROGMEM = {
{ OV( 1), 938 }, { OV( 1), 938 },
{ OV( 298), 125 }, // 1193 - 125° { OV( 298), 125 }, // 1193 - 125°
{ OV( 321), 121 }, // 1285 - 121° { OV( 321), 121 }, // 1285 - 121°
{ OV( 348), 117 }, // 1392 - 117° { OV( 348), 117 }, // 1392 - 117°
{ OV( 387), 113 }, // 1550 - 113° { OV( 387), 113 }, // 1550 - 113°

View File

@ -27,7 +27,6 @@
* Applies to the following boards: * Applies to the following boards:
* *
* BOARD_BIQU_BQ111_A4 (Hotend, Fan, Bed) * BOARD_BIQU_BQ111_A4 (Hotend, Fan, Bed)
*
*/ */
#if NOT_TARGET(MCU_LPC1768) #if NOT_TARGET(MCU_LPC1768)

View File

@ -27,7 +27,6 @@
* Applies to the following boards: * Applies to the following boards:
* *
* BOARD_BIQU_BQ111_A4 (Hotend, Fan, Bed) * BOARD_BIQU_BQ111_A4 (Hotend, Fan, Bed)
*
*/ */
#if NOT_TARGET(MCU_LPC1768) #if NOT_TARGET(MCU_LPC1768)

View File

@ -372,7 +372,6 @@
* P1_31 - not 5V tolerant - EXP1 * P1_31 - not 5V tolerant - EXP1
* P0_27 - open collector - EXP2 * P0_27 - open collector - EXP2
* P0_28 - open collector - EXP2 * P0_28 - open collector - EXP2
*
*/ */
/** /**
@ -387,5 +386,4 @@
* P0_03 - AUX1 * P0_03 - AUX1
* P0_29 - Port -1 * P0_29 - Port -1
* P0_30 - USB * P0_30 - USB
*
*/ */

View File

@ -31,7 +31,6 @@
* RAMPS_14_EFF (Hotend, Fan0, Fan1) * RAMPS_14_EFF (Hotend, Fan0, Fan1)
* RAMPS_14_EEF (Hotend0, Hotend1, Fan) * RAMPS_14_EEF (Hotend0, Hotend1, Fan)
* RAMPS_14_SF (Spindle, Controller Fan) * RAMPS_14_SF (Spindle, Controller Fan)
*
*/ */
// Numbers in parentheses () are the corresponding mega2560 pin numbers // Numbers in parentheses () are the corresponding mega2560 pin numbers

View File

@ -16,7 +16,7 @@
* GNU General Public License for more details. * GNU General Public License for more details.
* *
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>. * along with this program. If not, see <https://www.gnu.org/licenses/>.
* *
*/ */
#pragma once #pragma once

View File

@ -26,7 +26,6 @@
* *
* The pins diagram can be found and the following URL: * The pins diagram can be found and the following URL:
* https://github.com/makerbase-mks/MKS-SGen/blob/master/Hardware/MKS%20SGEN%20V1.0_001/MKS%20SGEN%20V1.0_001%20PIN.pdf * https://github.com/makerbase-mks/MKS-SGen/blob/master/Hardware/MKS%20SGEN%20V1.0_001/MKS%20SGEN%20V1.0_001%20PIN.pdf
*
*/ */
#if NOT_TARGET(MCU_LPC1769) #if NOT_TARGET(MCU_LPC1769)

View File

@ -166,7 +166,6 @@
* *
* A remote SD card is currently not supported because the pins routed to the EXP2 * A remote SD card is currently not supported because the pins routed to the EXP2
* connector are shared with the onboard SD card. * connector are shared with the onboard SD card.
*
*/ */
#if ENABLED(CR10_STOCKDISPLAY) #if ENABLED(CR10_STOCKDISPLAY)

View File

@ -137,7 +137,6 @@
///////////////////// SPARE HEADERS ////////////// ///////////////////// SPARE HEADERS //////////////
/** /**
*
* J25 * J25
* 1 D54 * 1 D54
* 2 D55 * 2 D55

View File

@ -29,7 +29,6 @@
* Rev B 2 JAN 2017 * Rev B 2 JAN 2017
* *
* Added pin definitions for M3, M4 & M5 spindle control commands * Added pin definitions for M3, M4 & M5 spindle control commands
*
*/ */
#if NOT_TARGET(__AVR_ATmega1281__) #if NOT_TARGET(__AVR_ATmega1281__)

View File

@ -31,7 +31,6 @@
* *
* Both passes use the same pin list. The list contains two macro names. The * Both passes use the same pin list. The list contains two macro names. The
* actual macro definitions are changed depending on which pass is being done. * actual macro definitions are changed depending on which pass is being done.
*
*/ */
// first pass - put the name strings into FLASH // first pass - put the name strings into FLASH

View File

@ -31,7 +31,6 @@
* RAMPS_13_EFF (Extruder, Fan, Fan) * RAMPS_13_EFF (Extruder, Fan, Fan)
* RAMPS_13_EEF (Extruder, Extruder, Fan) * RAMPS_13_EEF (Extruder, Extruder, Fan)
* RAMPS_13_SF (Spindle, Controller Fan) * RAMPS_13_SF (Spindle, Controller Fan)
*
*/ */
#ifndef BOARD_INFO_NAME #ifndef BOARD_INFO_NAME

Some files were not shown because too many files have changed in this diff Show More