Apply #pragma once, misc cleanup (#12322)

* Apply #pragma once in headers
* Adjust some thermistors formatting
* Misc cleanup and formatting
This commit is contained in:
Scott Lahteine 2018-11-04 02:25:55 -06:00 committed by GitHub
parent 8696f882a9
commit f5eab912ed
Signed by: GitHub
GPG key ID: 4AEE18F83AFDEB23
179 changed files with 710 additions and 1343 deletions

View file

@ -16,9 +16,7 @@
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef _HAL_AVR_H_
#define _HAL_AVR_H_
#pragma once
// --------------------------------------------------------------------------
// Includes
@ -374,5 +372,3 @@ inline void HAL_adc_init(void) {
// AVR compatibility
#define strtof strtod
#endif // _HAL_AVR_H_

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* MarlinSerial.h - Hardware serial library for Wiring
@ -30,9 +31,6 @@
* Templatized 01 October 2018 by Eduardo José Tagle to allow multiple instances
*/
#ifndef _MARLINSERIAL_H_
#define _MARLINSERIAL_H_
#include "../shared/MarlinSerial.h"
#include <WString.h>
@ -281,5 +279,3 @@
#if defined(USBCON) && ENABLED(BLUETOOTH)
extern HardwareSerial bluetoothSerial;
#endif
#endif // _MARLINSERIAL_H_

View file

@ -19,9 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef _SANITYCHECK_AVR_8_BIT_H_
#define _SANITYCHECK_AVR_8_BIT_H_
#pragma once
/**
* Test AVR specific configuration values for errors at compile-time.
@ -116,5 +114,3 @@
|| defined(E4_HARDWARE_SERIAL) )
#error "Select hardware UART for TMC2208 to use both TMC2208 and ENDSTOP_INTERRUPTS_FEATURE."
#endif
#endif // _SANITYCHECK_AVR_8_BIT_H_

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* ServoTimers.h - Interrupt driven Servo library for Arduino using 16 bit timers- Version 2
@ -39,9 +40,6 @@
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#ifndef _SERVOTIMERS_H_
#define _SERVOTIMERS_H_
/**
* Defines for 16 bit timers used with Servo library
*
@ -91,5 +89,3 @@ typedef enum {
#endif
_Nbr_16timers
} timer16_Sequence_t;
#endif // _SERVOTIMERS_H_

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Endstop Interrupts
@ -35,9 +36,6 @@
* (Located in Marlin/buildroot/share/pin_interrupt_test/pin_interrupt_test.ino)
*/
#ifndef _ENDSTOP_INTERRUPTS_H_
#define _ENDSTOP_INTERRUPTS_H_
#include "../../core/macros.h"
#include <stdint.h>
#include "../../module/endstops.h"
@ -256,5 +254,3 @@ void setup_endstop_interrupts( void ) {
// If we arrive here without raising an assertion, each pin has either an EXT-interrupt or a PCI.
}
#endif // _ENDSTOP_INTERRUPTS_H_

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Pin mapping for the 1280 and 2560
@ -28,9 +29,6 @@
* Logical Pin : 00 01 02 03 04 05 06 07 08 09 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx
*/
#ifndef _FASTIO_1280_H_
#define _FASTIO_1280_H_
#include "fastio_AVR.h"
// change for your board
@ -1111,5 +1109,3 @@
#define PL7_WPORT PORTL
#define PL7_DDR DDRL
#define PL7_PWM NULL
#endif // _FASTIO_1280_H_

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Pin mapping for the 1281 and 2561
@ -27,9 +28,6 @@
* Port: A0 A1 A2 A3 A4 A5 A6 A7 B0 B1 B2 B3 B4 B5 B6 B7 C0 C1 C2 C3 C4 C5 C6 C7 D0 D1 D2 D3 D4 D5 D6 D7 E0 E1 E2 E3 E4 E5 E6 E7 F0 F1 F2 F3 F4 F5 F6 F7 G0 G1 G2 G3 G4 G5
*/
#ifndef _FASTIO_1281_H_
#define _FASTIO_1281_H_
#include "fastio_AVR.h"
// change for your board
@ -715,5 +713,3 @@
#define PG5_WPORT PORTG
#define PG5_DDR DDRG
#define PG5_PWM &OCR0B
#endif // _FASTIO_1281_H_

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Pin mapping for the 168, 328, and 328P
@ -27,9 +28,6 @@
* Port: B0 B1 B2 B3 B4 B5 C0 C1 C2 C3 C4 C5 C6 C7 D0 D1 D2 D3 D4 D5 D6 D7
*/
#ifndef _FASTIO_168_H_
#define _FASTIO_168_H_
#include "fastio_AVR.h"
#define DEBUG_LED AIO5
@ -357,5 +355,3 @@
#define PD7_WPORT PORTD
#define PD7_DDR DDRD
#define PD7_PWM NULL
#endif // _FASTIO_168_H_

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Pin mapping for the 644, 644p, 644pa, and 1284p
@ -53,9 +54,6 @@
* +--------+
*/
#ifndef _FASTIO_644_H_
#define _FASTIO_644_H_
#include "fastio_AVR.h"
#define DEBUG_LED DIO0
@ -552,5 +550,3 @@
#define PD7_WPORT PORTD
#define PD7_DDR DDRD
#define PD7_PWM OCR2A
#endif // _FASTIO_644_H_

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Pin mapping (Teensy) for AT90USB646, 647, 1286, and 1287
@ -28,9 +29,6 @@
* The logical pins 46 and 47 are not supported by Teensyduino, but are supported below as E2 and E3
*/
#ifndef _FASTIO_AT90USB_H_
#define _FASTIO_AT90USB_H_
#include "fastio_AVR.h"
// change for your board
@ -697,5 +695,3 @@
#define TIMER3A 5
#define TIMER3B 4
#define TIMER3C 3
#endif // _FASTIO_AT90USB_H_

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Fast I/O Routines for AVR
@ -26,9 +27,6 @@
* Contributed by Triffid_Hunter and modified by Kliment, thinkyhead, Bob-the-Kuhn, et.al.
*/
#ifndef _FASTIO_ARDUINO_H_
#define _FASTIO_ARDUINO_H_
#include <avr/io.h>
#include "../../core/macros.h"
@ -312,5 +310,3 @@ enum ClockSource2 : char {
// finally - the macro that tells us if a pin is an available hardware PWM
#define USEABLE_HARDWARE_PWM(p) (PWM_PINS(p) && !PWM_CHK(p))
#endif // _FASTIO_ARDUINO_H_

View file

@ -19,9 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef _MATH_AVR_H_
#define _MATH_AVR_H_
#pragma once
/**
* Optimized math functions for AVR
@ -113,5 +111,3 @@ static FORCE_INLINE uint16_t MultiU16X8toH16(uint8_t charIn1, uint16_t intIn2) {
);
return intRes;
}
#endif // _MATH_AVR_H_

View file

@ -19,14 +19,12 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* PWM print routines for Atmel 8 bit AVR CPUs
*/
#ifndef _PINSDEBUG_AVR_8_BIT_
#define _PINSDEBUG_AVR_8_BIT_
#include "../../inc/MarlinConfig.h"
#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS
@ -406,5 +404,3 @@ static void pwm_details(uint8_t pin) {
#endif
#define PRINT_PIN(p) do {sprintf_P(buffer, PSTR("%3d "), p); SERIAL_ECHO(buffer);} while (0)
#endif // _PINSDEBUG_AVR_8_BIT_

View file

@ -19,9 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef _PINSDEBUG_TEENSYSUINO_H_
#define _PINSDEBUG_TEENSYSUINO_H_
#pragma once
//
// some of the pin mapping functions of the Teensduino extension to the Arduino IDE
@ -111,5 +109,3 @@ const uint8_t PROGMEM digital_pin_to_port_PGM[] = {
// disable the PWMs so we can use it as is
// portModeRegister(pin) is OK
#endif // _PINSDEBUG_TEENSYSUINO_H_

View file

@ -20,14 +20,12 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Structures for 2560 family boards that use more than 70 pins
*/
#ifndef _PINSDEBUG_PLUS_70_H_
#define _PINSDEBUG_PLUS_70_H_
#undef NUM_DIGITAL_PINS
#if MB(BQ_ZUM_MEGA_3D)
#define NUM_DIGITAL_PINS 85
@ -336,6 +334,3 @@ const uint8_t PROGMEM digital_pin_to_timer_PGM_plus_70[] = {
* PCINT14 J5 76
* PCINT15 J6 77
*/
#endif // _PINSDEBUG_PLUS_70_H_

View file

@ -19,9 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef _SPI_PINS_H_
#define _SPI_PINS_H_
#pragma once
/**
* Define SPI Pins: SCK, MISO, MOSI, SS
@ -65,6 +63,3 @@
#ifndef SS_PIN
#define SS_PIN AVR_SS_PIN
#endif
#endif // _SPI_PINS_H_

View file

@ -19,9 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef _WATCHDOG_AVR_H_
#define _WATCHDOG_AVR_H_
#pragma once
#include <avr/wdt.h>
@ -31,5 +29,3 @@ void watchdog_init();
// Reset watchdog. MUST be called at least every 4 seconds after the
// first watchdog_init or AVR will go into emergency procedures.
inline void watchdog_reset() { wdt_reset(); }
#endif // _WATCHDOG_AVR_H_

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Description: HAL for Arduino Due and compatible (SAM3X8E)
@ -26,9 +27,6 @@
* For ARDUINO_ARCH_SAM
*/
#ifndef _HAL_DUE_H
#define _HAL_DUE_H
#define CPU_32_BIT
#include <stdint.h>
@ -189,5 +187,3 @@ char *dtostrf (double __val, signed char __width, unsigned char __prec, char *__
#ifdef __cplusplus
}
#endif
#endif // _HAL_DUE_H

View file

@ -18,6 +18,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* HAL for Arduino Due and compatible (SAM3X8E)
@ -25,9 +26,6 @@
* For ARDUINO_ARCH_SAM
*/
#ifndef _HAL_TIMERS_DUE_H
#define _HAL_TIMERS_DUE_H
// --------------------------------------------------------------------------
// Includes
// --------------------------------------------------------------------------
@ -120,5 +118,3 @@ FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) {
}
#define HAL_timer_isr_epilogue(TIMER_NUM)
#endif // _HAL_TIMERS_DUE_H

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* InterruptVectors_Due.h
@ -35,11 +36,6 @@
* Copyright (c) 2017 Eduardo José Tagle. All right reserved
*/
#ifndef INTERRUPTVECTORS_DUE_H
#define INTERRUPTVECTORS_DUE_H
#include "../../inc/MarlinConfig.h"
#ifdef ARDUINO_ARCH_SAM
// ISR handler type
@ -49,4 +45,3 @@ typedef void (*pfnISR_Handler)(void);
pfnISR_Handler install_isr(IRQn_Type irq, pfnISR_Handler newHandler);
#endif // ARDUINO_ARCH_SAM
#endif // INTERRUPTVECTORS_DUE_H

View file

@ -19,15 +19,13 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* MarlinSerialUSB_Due.h - Hardware Serial over USB (CDC) library for Arduino DUE
* Copyright (c) 2017 Eduardo José Tagle. All right reserved
*/
#ifndef MARLINSERIALUSB_DUE_H
#define MARLINSERIALUSB_DUE_H
#include "../../inc/MarlinConfig.h"
#if SERIAL_PORT == -1
@ -92,4 +90,3 @@ private:
extern MarlinSerialUSB customizedSerial1;
#endif // SERIAL_PORT == -1
#endif // MARLINSERIAL_DUE_H

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Endstop Interrupts
@ -34,9 +35,6 @@
* (Located in Marlin/buildroot/share/pin_interrupt_test/pin_interrupt_test.ino)
*/
#ifndef _ENDSTOP_INTERRUPTS_H_
#define _ENDSTOP_INTERRUPTS_H_
#include "../../module/endstops.h"
// One ISR for all EXT-Interrupts
@ -82,5 +80,3 @@ void setup_endstop_interrupts(void) {
attachInterrupt(digitalPinToInterrupt(Z_MIN_PROBE_PIN), endstop_ISR, CHANGE);
#endif
}
#endif //_ENDSTOP_INTERRUPTS_H_

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Fast I/O Routines for SAM3X8E
@ -36,9 +37,6 @@
* leads to less efficient compiled code!!
*/
#ifndef _FASTIO_DUE_H
#define _FASTIO_DUE_H
#include <pins_arduino.h>
/**
@ -495,5 +493,3 @@
#define DIO100_PIN 11
#define DIO100_WPORT PIOC
#endif
#endif // _FASTIO_DUE_H

View file

@ -19,9 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef SPI_PINS_H_
#define SPI_PINS_H_
#pragma once
/**
* Define SPI Pins: SCK, MISO, MOSI, SS
@ -61,5 +59,3 @@
/* A.28, A.29, B.21, C.26, C.29 */
#define SS_PIN SDSS
#endif /* SPI_PINS_H_ */

View file

@ -40,15 +40,12 @@
* \asf_license_stop
*
*/
/*
#pragma once
/**
* Support and FAQ: visit <a href="http://www.atmel.com/design-support/">Atmel Support</a>
*/
#ifndef ARDUINO_DUE_X_H_INCLUDED
#define ARDUINO_DUE_X_H_INCLUDED
/* ------------------------------------------------------------------------ */
/**
* \page arduino_due_x_opfreq "Arduino Due/X - Operating frequencies"
* This page lists several definition related to the board operating frequency
@ -98,6 +95,3 @@
/*! Active level of the USB_VBOF output pin. */
#define USB_VBOF_ACTIVE_LEVEL LOW
/* ------------------------------------------------------------------------ */
#endif /* ARDUINO_DUE_X_H_INCLUDED */

View file

@ -19,9 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef WATCHDOG_DUE_H
#define WATCHDOG_DUE_H
#pragma once
// Arduino Due core now has watchdog support
@ -33,5 +31,3 @@ void watchdog_init();
// Reset watchdog. MUST be called at least every 4 seconds after the
// first watchdog_init or AVR will go into emergency procedures.
inline void watchdog_reset() { watchdogReset(); }
#endif // WATCHDOG_DUE_H

View file

@ -16,14 +16,12 @@
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
/**
* Description: HAL for Espressif ESP32 WiFi
*/
#ifndef _HAL_ESP32_H
#define _HAL_ESP32_H
#define CPU_32_BIT
// --------------------------------------------------------------------------
@ -123,5 +121,3 @@ void HAL_adc_start_conversion (uint8_t adc_pin);
#define HAL_INIT 1
void HAL_idletask(void);
void HAL_init(void);
#endif // _HAL_ESP32_H

View file

@ -19,9 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef _HAL_TIMERS_ESP32_H
#define _HAL_TIMERS_ESP32_H
#pragma once
// --------------------------------------------------------------------------
// Includes
@ -104,5 +102,3 @@ bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
#define HAL_timer_isr_prologue(TIMER_NUM)
#define HAL_timer_isr_epilogue(TIMER_NUM)
#endif // _HAL_TIMERS_ESP32_H

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Endstop Interrupts
@ -34,9 +35,6 @@
* (Located in Marlin/buildroot/share/pin_interrupt_test/pin_interrupt_test.ino)
*/
#ifndef _ENDSTOP_INTERRUPTS_H_
#define _ENDSTOP_INTERRUPTS_H_
#include "../../module/endstops.h"
// One ISR for all EXT-Interrupts
@ -77,5 +75,3 @@ void setup_endstop_interrupts(void) {
attachInterrupt(digitalPinToInterrupt(Z_MIN_PROBE_PIN), endstop_ISR, CHANGE);
#endif
}
#endif //_ENDSTOP_INTERRUPTS_H_

View file

@ -19,9 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef _FASTIO_ESP32_H
#define _FASTIO_ESP32_H
#pragma once
/**
* Utility functions
@ -64,9 +62,3 @@
// TWI (I2C)
#define SCL 5
#define SDA 4
//
// pins
//
#endif // _FASTIO_ESP32_H

View file

@ -16,11 +16,7 @@
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef _HAL_OTA_H
#define _HAL_OTA_H
#pragma once
void OTA_init();
void OTA_handle();
#endif

View file

@ -16,13 +16,9 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef SPI_PINS_H_
#define SPI_PINS_H_
#pragma once
#define SS_PIN 5
#define SCK_PIN 18
#define MISO_PIN 19
#define MOSI_PIN 23
#endif // SPI_PINS_H_

View file

@ -19,14 +19,10 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef WATCHDOG_ESP32_H
#define WATCHDOG_ESP32_H
#pragma once
// Initialize watchdog with a 4 second interrupt time
void watchdog_init();
// Reset watchdog.
inline void watchdog_reset() {};
#endif // WATCHDOG_ESP32_H
inline void watchdog_reset() { }

View file

@ -19,15 +19,13 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* HAL_LPC1768/HAL.h
* Hardware Abstraction Layer for NXP LPC1768
*/
#ifndef _HAL_LPC1768_H_
#define _HAL_LPC1768_H_
#define CPU_32_BIT
#define HAL_INIT
@ -156,5 +154,3 @@ int16_t PARSED_PIN_INDEX(const char code, const int16_t dval);
#define HAL_IDLETASK 1
void HAL_idletask(void);
#endif // _HAL_LPC1768_H_

View file

@ -18,15 +18,13 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
*
* HAL For LPC1768
*/
#ifndef _HAL_TIMERS_H
#define _HAL_TIMERS_H
// --------------------------------------------------------------------------
// Includes
// --------------------------------------------------------------------------
@ -166,5 +164,3 @@ FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) {
}
#define HAL_timer_isr_epilogue(TIMER_NUM)
#endif // _HAL_TIMERS_H

View file

@ -19,9 +19,8 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
#ifndef MARLINSERIAL_H
#define MARLINSERIAL_H
#include <HardwareSerial.h>
#include <WString.h>
@ -33,7 +32,6 @@
#ifndef SERIAL_PORT
#define SERIAL_PORT 0
#endif
#ifndef RX_BUFFER_SIZE
#define RX_BUFFER_SIZE 128
#endif
@ -67,5 +65,3 @@ extern MarlinSerial MSerial;
extern MarlinSerial MSerial1;
extern MarlinSerial MSerial2;
extern MarlinSerial MSerial3;
#endif // MARLINSERIAL_H

View file

@ -38,6 +38,7 @@
* License along with this library; if not, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#pragma once
/**
* Based on "servo.h - Interrupt driven Servo library for Arduino using 16 bit timers -
@ -47,12 +48,9 @@
*
*/
#ifndef SERVO_PRIVATE_H
#define SERVO_PRIVATE_H
#include <Servo.h>
class MarlinServo: public Servo {
class MarlinServo: public Servo {
public:
void move(const int value) {
constexpr uint16_t servo_delay[] = SERVO_DELAY;
@ -70,5 +68,3 @@ class MarlinServo: public Servo {
};
#define HAL_SERVO_LIB MarlinServo
#endif // SERVO_PRIVATE_H

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Endstop Interrupts
@ -34,9 +35,6 @@
* (Located in Marlin/buildroot/share/pin_interrupt_test/pin_interrupt_test.ino)
*/
#ifndef _ENDSTOP_INTERRUPTS_H_
#define _ENDSTOP_INTERRUPTS_H_
#include "../../module/endstops.h"
// One ISR for all EXT-Interrupts
@ -104,5 +102,3 @@ void setup_endstop_interrupts(void) {
attachInterrupt(digitalPinToInterrupt(Z_MIN_PROBE_PIN), endstop_ISR, CHANGE);
#endif
}
#endif //_ENDSTOP_INTERRUPTS_H_

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Fast I/O Routines for LPC1768/9
@ -32,9 +33,6 @@
* For TARGET LPC1768
*/
#ifndef _FASTIO_LPC1768_H
#define _FASTIO_LPC1768_H
#include <Arduino.h>
#define USEABLE_HARDWARE_PWM(pin) TRUE // all pins are PWM capable
@ -123,5 +121,3 @@
// Shorthand
#define OUT_WRITE(IO,V) do{ SET_OUTPUT(IO); WRITE(IO,V); }while(0)
#endif // _FASTIO_LPC1768_H

View file

@ -19,13 +19,11 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
// adapted from I2C/master/master.c example
// https://www-users.cs.york.ac.uk/~pcc/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html
#ifndef _DIGIPOT_MCP4451_I2C_ROUTINES_H_
#define _DIGIPOT_MCP4451_I2C_ROUTINES_H_
#define USEDI2CDEV_M 1 // use I2C1 controller
#if USEDI2CDEV_M == 0
@ -53,5 +51,3 @@ uint8_t digipot_mcp4451_send_byte(uint8_t data);
#ifdef __cplusplus
}
#endif
#endif // _DIGIPOT_MCP4451_I2C_ROUTINES_H_

View file

@ -19,9 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef SPI_PINS_LPC1768_H
#define SPI_PINS_LPC1768_H
#pragma once
#include "src/core/macros.h"
@ -54,5 +52,3 @@
#undef SDSS
#define SDSS SS_PIN
#endif
#endif // SPI_PINS_LPC1768_H

View file

@ -19,9 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef WATCHDOG_LPC1768_H
#define WATCHDOG_LPC1768_H
#pragma once
#define RST_POWER_ON 1
#define RST_EXTERNAL 2
@ -34,5 +32,3 @@ void watchdog_init(void);
void watchdog_reset(void);
void HAL_clear_reset_source(void);
uint8_t HAL_get_reset_source(void);
#endif /* WATCHDOG_H */

View file

@ -20,14 +20,12 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* HAL for stm32duino.com based on Libmaple and compatible (STM32F1)
*/
#ifndef _HAL_STM32F1_H
#define _HAL_STM32F1_H
#define CPU_32_BIT
#undef DEBUG_NONE
@ -251,5 +249,3 @@ void HAL_enable_AdcFreerun(void);
#define JTAG_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_SW_ONLY)
#define JTAGSWD_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_NONE)
#endif // _HAL_STM32F1_H

View file

@ -20,9 +20,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef HAL_SERVO_STM32F1_H
#define HAL_SERVO_STM32F1_H
#pragma once
// Pin number of unattached pins
#define NOT_ATTACHED (-1)
@ -53,5 +51,3 @@ class libServo {
int32_t minAngle;
int32_t maxAngle;
};
#endif // HAL_SERVO_STM32F1_H

View file

@ -19,14 +19,12 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* HAL for stm32duino.com based on Libmaple and compatible (STM32F1)
*/
#ifndef _HAL_TIMERS_STM32F1_H
#define _HAL_TIMERS_STM32F1_H
// --------------------------------------------------------------------------
// Includes
// --------------------------------------------------------------------------
@ -167,5 +165,3 @@ FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) {
}
#define HAL_timer_isr_epilogue(TIMER_NUM)
#endif // _HAL_TIMERS_STM32F1_H

View file

@ -20,6 +20,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Endstop interrupts for Libmaple STM32F1 based targets.
@ -46,9 +47,6 @@
* (Located in Marlin/buildroot/share/pin_interrupt_test/pin_interrupt_test.ino)
*/
#ifndef _ENDSTOP_INTERRUPTS_H_
#define _ENDSTOP_INTERRUPTS_H_
#include "../../module/endstops.h"
// One ISR for all EXT-Interrupts
@ -89,5 +87,3 @@ void setup_endstop_interrupts(void) {
attachInterrupt(Z_MIN_PROBE_PIN, endstop_ISR, CHANGE);
#endif
}
#endif //_ENDSTOP_INTERRUPTS_H_

View file

@ -20,15 +20,13 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Fast I/O interfaces for STM32F1
* These use GPIO functions instead of Direct Port Manipulation, as on AVR.
*/
#ifndef _FASTIO_STM32F1_H
#define _FASTIO_STM32F1_H
#include <libmaple/gpio.h>
#define READ(IO) (PIN_MAP[IO].gpio_device->regs->IDR & (1U << PIN_MAP[IO].gpio_bit) ? HIGH : LOW)
@ -52,5 +50,3 @@
#define PWM_PIN(p) true
#define USEABLE_HARDWARE_PWM(p) PWM_PIN(p)
#endif // _FASTIO_STM32F1_H

View file

@ -16,14 +16,12 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* HAL for stm32duino.com based on Libmaple and compatible (STM32F1)
*/
#ifndef SPI_PINS_H_
#define SPI_PINS_H_
/**
* Define SPI Pins: SCK, MISO, MOSI, SS
*
@ -33,5 +31,3 @@
#define MISO_PIN PA6
#define MOSI_PIN PA7
#define SS_PIN PA4
#endif // SPI_PINS_H_

View file

@ -19,14 +19,12 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* HAL for stm32duino.com based on Libmaple and compatible (STM32F1)
*/
#ifndef WATCHDOG_STM32F1_H
#define WATCHDOG_STM32F1_H
#include <libmaple/iwdg.h>
#include "../../inc/MarlinConfig.h"
@ -51,5 +49,3 @@ inline void watchdog_reset() {
#endif
iwdg_feed();
}
#endif // WATCHDOG_STM32F1_H

View file

@ -45,10 +45,7 @@
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __EEEPROM_EMUL_H
#define __EEEPROM_EMUL_H
#pragma once
// --------------------------------------------------------------------------
// Includes
@ -112,6 +109,4 @@ uint16_t EE_Initialize(void);
uint16_t EE_ReadVariable(uint16_t VirtAddress, uint16_t* Data);
uint16_t EE_WriteVariable(uint16_t VirtAddress, uint16_t Data);
#endif /* __EEEPROM_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -20,9 +20,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef _HAL_STM32F4_H
#define _HAL_STM32F4_H
#pragma once
#define CPU_32_BIT
#undef DEBUG_NONE
@ -251,5 +249,3 @@ void HAL_enable_AdcFreerun(void);
#define JTAG_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_SW_ONLY)
#define JTAGSWD_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_NONE)
#endif // _HAL_STM32F4_H

View file

@ -20,22 +20,18 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef HAL_SERVO_STM32F4_H
#define HAL_SERVO_STM32F4_H
#pragma once
#include <Servo.h>
// Inherit and expand on the official library
class libServo : public Servo {
public:
public:
int8_t attach(const int pin);
int8_t attach(const int pin, const int min, const int max);
void move(const int value);
private:
private:
uint16_t min_ticks;
uint16_t max_ticks;
uint8_t servoIndex; // index into the channel data for this servo
};
#endif // HAL_SERVO_STM32F4_H

View file

@ -19,9 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef _HAL_TIMERS_STM32F4_H
#define _HAL_TIMERS_STM32F4_H
#pragma once
// --------------------------------------------------------------------------
// Includes
@ -130,5 +128,3 @@ FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) {
#endif
#define HAL_timer_isr_epilogue(TIMER_NUM)
#endif // _HAL_TIMERS_STM32F4_H

View file

@ -20,9 +20,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef _ENDSTOP_INTERRUPTS_H_
#define _ENDSTOP_INTERRUPTS_H_
#pragma once
#include "../../module/endstops.h"
@ -64,5 +62,3 @@ void setup_endstop_interrupts(void) {
attachInterrupt(Z_MIN_PROBE_PIN, endstop_ISR, CHANGE);
#endif
}
#endif //_ENDSTOP_INTERRUPTS_H_

View file

@ -20,15 +20,13 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Fast I/O interfaces for STM32F4
* These use GPIO functions instead of Direct Port Manipulation, as on AVR.
*/
#ifndef _FASTIO_STM32F4_H
#define _FASTIO_STM32F4_H
#undef _BV
#define _BV(b) (1 << (b))
@ -151,5 +149,3 @@
#define PE13 _STM32_PIN(E, 13)
#define PE14 _STM32_PIN(E, 14)
#define PE15 _STM32_PIN(E, 15)
#endif // _FASTIO_STM32F4_H

View file

@ -19,15 +19,9 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef WATCHDOG_STM32F4_H
#define WATCHDOG_STM32F4_H
#include "../../inc/MarlinConfig.h"
#pragma once
extern IWDG_HandleTypeDef hiwdg;
void watchdog_init();
void watchdog_reset();
#endif // WATCHDOG_STM32F1_H

View file

@ -45,10 +45,7 @@
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __EEEPROM_EMUL_H
#define __EEEPROM_EMUL_H
#pragma once
// --------------------------------------------------------------------------
// Includes
@ -113,6 +110,4 @@ uint16_t EE_Initialize(void);
uint16_t EE_ReadVariable(uint16_t VirtAddress, uint16_t* Data);
uint16_t EE_WriteVariable(uint16_t VirtAddress, uint16_t Data);
#endif /* __EEEPROM_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -20,9 +20,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef _HAL_STM32F7_H
#define _HAL_STM32F7_H
#pragma once
#define CPU_32_BIT
#undef DEBUG_NONE
@ -234,5 +232,3 @@ void HAL_enable_AdcFreerun(void);
#define GET_PIN_MAP_PIN(index) index
#define GET_PIN_MAP_INDEX(pin) pin
#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
#endif // _HAL_STM32F7_H

View file

@ -20,9 +20,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef HAL_SERVO_STM32F7_H
#define HAL_SERVO_STM32F7_H
#pragma once
#include <../../libraries/Servo/src/Servo.h>
@ -37,5 +35,3 @@ private:
uint16_t max_ticks;
uint8_t servoIndex; // index into the channel data for this servo
};
#endif // HAL_SERVO_STM32F7_H

View file

@ -19,9 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef _HAL_TIMERS_STM32F7_H
#define _HAL_TIMERS_STM32F7_H
#pragma once
// --------------------------------------------------------------------------
// Includes
@ -101,5 +99,3 @@ hal_timer_t HAL_timer_get_compare(const uint8_t timer_num);
uint32_t HAL_timer_get_count(const uint8_t timer_num);
void HAL_timer_isr_prologue(const uint8_t timer_num);
#define HAL_timer_isr_epilogue(TIMER_NUM)
#endif // _HAL_TIMERS_STM32F7_H

View file

@ -24,12 +24,9 @@
* THE SOFTWARE.
*
*/
#pragma once
#include "../../inc/MarlinConfig.h"
// ensure this library description is only included once
#ifndef _TMC26XSTEPPER_H_
#define _TMC26XSTEPPER_H_
#include <stdint.h>
//! return value for TMC26XStepper.getOverTemperature() if there is a overtemperature situation in the TMC chip
/*!
@ -601,5 +598,3 @@ class TMC26XStepper {
// SPI sender
inline void send262(uint32_t datagram);
};
#endif // _TMC26XSTEPPER_H_

View file

@ -20,11 +20,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef _ENDSTOP_INTERRUPTS_H_
#define _ENDSTOP_INTERRUPTS_H_
#pragma once
#include "../../module/endstops.h"
@ -66,5 +62,3 @@ void setup_endstop_interrupts(void) {
attachInterrupt(Z_MIN_PROBE_PIN, endstop_ISR, CHANGE);
#endif
}
#endif //_ENDSTOP_INTERRUPTS_H_

View file

@ -20,15 +20,13 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Fast I/O interfaces for STM32F7
* These use GPIO functions instead of Direct Port Manipulation, as on AVR.
*/
#ifndef _FASTIO_STM32F7_H
#define _FASTIO_STM32F7_H
#define _BV(b) (1 << (b))
#define READ(IO) digitalRead(IO)
@ -186,5 +184,3 @@
#define PG13 _STM32_PIN(G, 13)
#define PG14 _STM32_PIN(G, 14)
#define PG15 _STM32_PIN(G, 15)
#endif // _FASTIO_STM32F7_H

View file

@ -19,15 +19,9 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef WATCHDOG_STM32F7_H
#define WATCHDOG_STM32F7_H
#include "../../inc/MarlinConfig.h"
#pragma once
extern IWDG_HandleTypeDef hiwdg;
void watchdog_init();
void watchdog_reset();
#endif // WATCHDOG_STM32F1_H

View file

@ -19,14 +19,12 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Description: HAL for Teensy 3.5 and Teensy 3.6
*/
#ifndef _HAL_TEENSY_H
#define _HAL_TEENSY_H
#define CPU_32_BIT
// --------------------------------------------------------------------------
@ -167,9 +165,3 @@ uint16_t HAL_adc_get_result(void);
#define GET_PIN_MAP_PIN(index) index
#define GET_PIN_MAP_INDEX(pin) pin
#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
// --------------------------------------------------------------------------
//
// --------------------------------------------------------------------------
#endif // _HAL_TEENSY_H

View file

@ -1,5 +1,25 @@
#ifndef _HAL_SERVO_TEENSY_H_
#define _HAL_SERVO_TEENSY_H_
/**
* Marlin 3D Printer Firmware
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
#include <Servo.h>
@ -14,5 +34,3 @@ class libServo : public Servo {
uint16_t max_ticks;
uint8_t servoIndex; // index into the channel data for this servo
};
#endif // _HAL_SERVO_TEENSY_H_

View file

@ -1,23 +1,23 @@
/* **************************************************************************
Marlin 3D Printer Firmware
Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
****************************************************************************/
/**
* Marlin 3D Printer Firmware
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
* Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
/**
* Description: HAL for
@ -25,9 +25,6 @@
* Teensy3.6 (__MK66FX1M0__)
*/
#ifndef _HAL_TIMERS_TEENSY_H
#define _HAL_TIMERS_TEENSY_H
// --------------------------------------------------------------------------
// Includes
// --------------------------------------------------------------------------
@ -108,5 +105,3 @@ bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
void HAL_timer_isr_prologue(const uint8_t timer_num);
#define HAL_timer_isr_epilogue(TIMER_NUM)
#endif // _HAL_TIMERS_TEENSY_H

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Endstop Interrupts
@ -34,9 +35,6 @@
* (Located in Marlin/buildroot/share/pin_interrupt_test/pin_interrupt_test.ino)
*/
#ifndef _ENDSTOP_INTERRUPTS_H_
#define _ENDSTOP_INTERRUPTS_H_
#include "../../module/endstops.h"
// One ISR for all EXT-Interrupts
@ -81,5 +79,3 @@ void setup_endstop_interrupts( void ) {
attachInterrupt(digitalPinToInterrupt(Z_MIN_PROBE_PIN), endstop_ISR, CHANGE);
#endif
}
#endif //_ENDSTOP_INTERRUPTS_H_

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Fast I/O Routines for Teensy 3.5 and Teensy 3.6
@ -26,9 +27,6 @@
* Contributed by Triffid_Hunter and modified by Kliment, thinkyhead, Bob-the-Kuhn, et.al.
*/
#ifndef _FASTIO_TEENSY_H
#define _FASTIO_TEENSY_H
#ifndef MASK
#define MASK(PIN) (1 << PIN)
#endif
@ -91,5 +89,3 @@
*/
#define DIO0_PIN 8
#endif /* _FASTIO_TEENSY_H */

View file

@ -19,13 +19,9 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef SPI_PINS_H_
#define SPI_PINS_H_
#pragma once
#define SCK_PIN 13
#define MISO_PIN 12
#define MOSI_PIN 11
#define SS_PIN 20 //SDSS // A.28, A.29, B.21, C.26, C.29
#endif /* SPI_PINS_H_ */
#define SS_PIN 20 // SDSS // A.28, A.29, B.21, C.26, C.29

View file

@ -19,13 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef WATCHDOG_TEENSY_H
#define WATCHDOG_TEENSY_H
#include "HAL.h"
// Arduino Due core now has watchdog support
#pragma once
void watchdog_init();
@ -34,5 +28,3 @@ inline void watchdog_reset() {
WDOG_REFRESH = 0xA602;
WDOG_REFRESH = 0xB480;
}
#endif // WATCHDOG_TEENSY_H

View file

@ -1,7 +1,25 @@
#ifndef _HAL_PLATFORMS_H_
#define _HAL_PLATFORMS_H_
#ifndef HAL_PLATFORM
/**
* Marlin 3D Printer Firmware
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
#ifdef __AVR__
#define HAL_PLATFORM HAL_AVR
@ -27,10 +45,6 @@
#error "Unsupported Platform!"
#endif
#endif // HAL_PLATFORM
#define XSTR_(M) #M
#define XSTR(M) XSTR_(M)
#define HAL_PATH(PATH, NAME) XSTR(PATH/HAL_PLATFORM/NAME)
#endif // _HAL_PLATFORMS_H_

View file

@ -19,15 +19,13 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* HAL/HAL_SPI.h
* Core Marlin definitions for SPI, implemented in the HALs
*/
#ifndef _HAL_SPI_H_
#define _HAL_SPI_H_
#include <stdint.h>
/**
@ -78,5 +76,3 @@ void spiRead(uint8_t* buf, uint16_t nbyte);
void spiSendBlock(uint8_t token, const uint8_t* buf);
/** Begin SPI transaction, set clock, bit order, data mode */
void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode);
#endif // _HAL_SPI_H_

View file

@ -19,11 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef _BACKTRACE_H_
#define _BACKTRACE_H_
#pragma once
// Perform a backtrace to the serial port
void backtrace(void);
#endif

View file

@ -11,8 +11,7 @@
* File Description: Internal interface between the ARM unwinding sub-modules.
**************************************************************************/
#ifndef UNWARM_H
#define UNWARM_H
#pragma once
#include "unwinder.h"
@ -139,5 +138,3 @@ bool UnwReportRetAddr(UnwState * const state, uint32_t addr);
bool UnwMemWriteRegister(UnwState * const state, const uint32_t addr, const RegData * const reg);
bool UnwMemReadRegister(UnwState * const state, const uint32_t addr, RegData * const reg);
void UnwMemHashGC(UnwState * const state);
#endif // UNWARM_H

View file

@ -12,8 +12,7 @@
* File Description: Interface to the memory tracking sub-system.
**************************************************************************/
#ifndef UNWARMBYTAB_H
#define UNWARMBYTAB_H
#pragma once
#include "unwarm.h"
@ -30,5 +29,3 @@ typedef struct {
} UnwTabEntry;
UnwResult UnwindByTableStart(UnwindFrame* frame, const UnwindCallbacks *cb, void *data);
#endif // UNWARMBYTAB_H

View file

@ -12,14 +12,10 @@
* File Description: Interface to the memory tracking sub-system.
**************************************************************************/
#ifndef UNWARMMEM_H
#define UNWARMMEM_H
#pragma once
#include "unwarm.h"
bool UnwMemHashRead(MemData * const memData, uint32_t addr, uint32_t * const data, bool * const tracked);
bool UnwMemHashWrite(MemData * const memData, uint32_t addr, uint32_t val, bool valValid);
void UnwMemHashGC(UnwState * const state);
#endif

View file

@ -13,8 +13,7 @@
* Interface to the ARM stack unwinding module.
**************************************************************************/
#ifndef UNWINDER_H
#define UNWINDER_H
#pragma once
#include <stdint.h>
@ -171,5 +170,3 @@ typedef struct {
* get function names in the traceback. Otherwise, you will not.
*/
UnwResult UnwindStart(UnwindFrame* frame, const UnwindCallbacks *cb, void *data);
#endif /* UNWINDER_H */

View file

@ -12,8 +12,7 @@
* File Description: Utility functions to access memory
**************************************************************************/
#ifndef UNWMEMACCESS_H
#define UNWMEMACCESS_H
#pragma once
#include "unwarm.h"
#include <stdint.h>
@ -21,6 +20,3 @@
bool UnwReadW(const uint32_t a, uint32_t *v);
bool UnwReadH(const uint32_t a, uint16_t *v);
bool UnwReadB(const uint32_t a, uint8_t *v);
#endif

View file

@ -19,9 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef MATH_32BIT_H
#define MATH_32BIT_H
#pragma once
#include "../../core/macros.h"
@ -31,5 +29,3 @@
static FORCE_INLINE uint32_t MultiU32X24toH32(uint32_t longIn1, uint32_t longIn2) {
return ((uint64_t)longIn1 * longIn2 + 0x00800000) >> 24;
}
#endif // MATH_32BIT_H

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* servo_private.h - Interrupt driven Servo library for Arduino using 16 bit timers- Version 2
@ -39,9 +40,6 @@
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#ifndef SERVO_PRIVATE_H
#define SERVO_PRIVATE_H
#include <stdint.h>
// Architecture specific include
@ -98,5 +96,3 @@ extern ServoInfo_t servo_info[MAX_SERVOS];
extern void initISR(timer16_Sequence_t timer);
extern void finISR(timer16_Sequence_t timer);
#endif // SERVO_PRIVATE_H

View file

@ -19,8 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef __MARLIN_H__
#define __MARLIN_H__
#pragma once
#include "inc/MarlinConfig.h"
@ -242,5 +241,3 @@ void protected_pin_err();
#if HAS_SUICIDE
inline void suicide() { OUT_WRITE(SUICIDE_PIN, LOW); }
#endif
#endif // __MARLIN_H__

View file

@ -19,9 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef BOARDS_H
#define BOARDS_H
#pragma once
#define BOARD_UNKNOWN -1
@ -247,5 +245,3 @@
#define BOARD_ESP32 1900
#define MB(board) (defined(BOARD_##board) && MOTHERBOARD==BOARD_##board)
#endif // __BOARDS_H

View file

@ -19,9 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef __ENUM_H__
#define __ENUM_H__
#pragma once
/**
* Axis indices as enumerated constants
@ -68,5 +66,3 @@ typedef enum {
TEMPUNIT_K,
TEMPUNIT_F
} TempUnit;
#endif // __ENUM_H__

View file

@ -19,9 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef __SERIAL_H__
#define __SERIAL_H__
#pragma once
#include "../inc/MarlinConfigPre.h"
#include HAL_PATH(../HAL, HAL.h)
@ -246,5 +244,3 @@ void serial_error_start();
void print_xyz(PGM_P prefix, PGM_P suffix, const float xyz[]);
#define DEBUG_POS(SUFFIX,VAR) do { print_xyz(PSTR(" " STRINGIFY(VAR) "="), PSTR(" : " SUFFIX "\n"), VAR); } while(0)
#endif
#endif // __SERIAL_H__

View file

@ -19,9 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef __UTILITY_H__
#define __UTILITY_H__
#pragma once
#include "../inc/MarlinConfigPre.h"
@ -102,5 +100,3 @@ void safe_delay(millis_t ms);
#if ENABLED(DEBUG_LEVELING_FEATURE)
void log_machine_info();
#endif
#endif // __UTILITY_H__

View file

@ -19,9 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef I2CPOSENC_H
#define I2CPOSENC_H
#pragma once
#include "../inc/MarlinConfig.h"
@ -331,5 +329,3 @@ class I2CPositionEncodersMgr {
};
extern I2CPositionEncodersMgr I2CPEM;
#endif //I2CPOSENC_H

View file

@ -19,11 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef __BARICUDA_H__
#define __BARICUDA_H__
#pragma once
extern uint8_t baricuda_valve_pressure,
baricuda_e_to_p_pressure;
#endif // __BARICUDA_H__

View file

@ -19,9 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef __ABL_H__
#define __ABL_H__
#pragma once
#include "../../../inc/MarlinConfig.h"
@ -47,5 +45,3 @@
#endif
#endif // AUTO_BED_LEVELING_BILINEAR
#endif // __ABL_H__

View file

@ -19,9 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef __BEDLEVEL_H__
#define __BEDLEVEL_H__
#pragma once
#include "../../inc/MarlinConfigPre.h"
@ -85,5 +83,3 @@ void reset_bed_level();
#elif HAS_ABL
#include "abl/abl.h"
#endif
#endif // __BEDLEVEL_H__

View file

@ -19,9 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef _MESH_BED_LEVELING_H_
#define _MESH_BED_LEVELING_H_
#pragma once
#include "../../../inc/MarlinConfig.h"
@ -120,5 +118,3 @@ public:
};
extern mesh_bed_leveling mbl;
#endif // _MESH_BED_LEVELING_H_

View file

@ -19,9 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef UNIFIED_BED_LEVELING_H
#define UNIFIED_BED_LEVELING_H
#pragma once
//#define UBL_DEVEL_DEBUGGING
@ -372,5 +370,3 @@ class unified_bed_leveling {
}; // class unified_bed_leveling
extern unified_bed_leveling ubl;
#endif // UNIFIED_BED_LEVELING_H

View file

@ -19,9 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef __CASELIGHT_H__
#define __CASELIGHT_H__
#pragma once
extern uint8_t case_light_brightness;
extern bool case_light_on;
@ -29,5 +27,3 @@ extern uint8_t case_light_brightness_sav; // saves brighness info when case_li
extern bool case_light_arg_flag; // flag to notify if S or P argument type
void update_case_light();
#endif // __CASELIGHT_H__

View file

@ -19,10 +19,6 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef __CONTROLLERFAN_H__
#define __CONTROLLERFAN_H__
#pragma once
void controllerfan_update();
#endif // __CONTROLLERFAN_H__

View file

@ -1,5 +1,25 @@
#ifndef DAC084S085_H
#define DAC084S085_H
/**
* Marlin 3D Printer Firmware
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
class dac084s085 {
public:
@ -9,5 +29,3 @@ class dac084s085 {
private:
static void cshigh();
};
#endif // DAC084S085_H

View file

@ -19,14 +19,12 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Arduino library for MicroChip MCP4728 I2C D/A converter.
*/
#ifndef DAC_MCP4728_H
#define DAC_MCP4728_H
#include <Wire.h>
#define defaultVDD DAC_STEPPER_MAX //was 5000 but differs with internal Vref
@ -57,5 +55,3 @@ uint8_t mcp4728_fastWrite();
uint8_t mcp4728_simpleCommand(byte simpleCommand);
uint8_t mcp4728_getDrvPct(uint8_t channel);
void mcp4728_setDrvPct(uint8_t pct[XYZE]);
#endif // DAC_MCP4728_H

View file

@ -19,31 +19,12 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* stepper_dac.h - To set stepper current via DAC
*
* Part of Marlin
*
* Copyright (c) 2016 MarlinFirmware
*
* Marlin 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.
*
* Marlin 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 Marlin. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef STEPPER_DAC_H
#define STEPPER_DAC_H
#include "dac_mcp4728.h"
int dac_init();
@ -53,5 +34,3 @@ void dac_print_values();
void dac_commit_eeprom();
uint8_t dac_current_get_percent(AxisEnum axis);
void dac_current_set_percents(const uint8_t pct[XYZE]);
#endif // STEPPER_DAC_H

View file

@ -19,11 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef __DIGIPOT_H__
#define __DIGIPOT_H__
#pragma once
void digipot_i2c_set_current(const uint8_t channel, const float current);
void digipot_i2c_init();
#endif // __DIGIPOT_H__

View file

@ -19,15 +19,11 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* feature/fanmux.h - Cooling Fan Multiplexer support functions
*/
#ifndef _FANMUX_H_
#define _FANMUX_H_
extern void fanmux_switch(const uint8_t e);
extern void fanmux_init(void);
#endif // _FANMUX_H_

View file

@ -19,9 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef __FILWIDTH_H__
#define __FILWIDTH_H__
#pragma once
#include "../inc/MarlinConfig.h"
@ -31,5 +29,3 @@ extern float filament_width_nominal, // Nominal filament
extern uint8_t meas_delay_cm; // Distance delay setting
extern int8_t measurement_delay[MAX_MEASUREMENT_DELAY + 1], // Ring buffer to delayed measurement. Store extruder factor after subtracting 100
filwidth_delay_index[2]; // Indexes into ring buffer
#endif // __FILWIDTH_H__

View file

@ -19,17 +19,13 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* blinkm.h - Control a BlinkM over i2c
*/
#ifndef _BLINKM_H_
#define _BLINKM_H_
struct LEDColor;
typedef LEDColor LEDColor;
void blinkm_set_led_color(const LEDColor &color);
#endif // _BLINKM_H_

View file

@ -19,14 +19,12 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Neopixel support
*/
#ifndef __NEOPIXEL_H__
#define __NEOPIXEL_H__
#include "../../inc/MarlinConfig.h"
#include <Adafruit_NeoPixel.h>
@ -46,5 +44,3 @@ void set_neopixel_color(const uint32_t color);
//bool neopixel_set_led_color(const uint8_t r, const uint8_t g, const uint8_t b, const uint8_t w, const uint8_t p);
extern Adafruit_NeoPixel pixels;
#endif // __NEOPIXEL_H__

View file

@ -19,18 +19,14 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Driver for the Philips PCA9632 LED driver.
* Written by Robert Mendon Feb 2017.
*/
#ifndef __PCA9632_H__
#define __PCA9632_H__
struct LEDColor;
typedef LEDColor LEDColor;
void pca9632_set_led_color(const LEDColor &color);
#endif // __PCA9632_H__

View file

@ -19,14 +19,10 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Marlin general RGB LED support
*/
#ifndef __TEMPSTAT_H__
#define __TEMPSTAT_H__
void handle_status_leds(void);
#endif // __TEMPSTAT_H__

View file

@ -19,10 +19,6 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef __SNMM_H__
#define __SNMM_H__
#pragma once
void select_multiplexed_stepper(const uint8_t e);
#endif // __SNMM_H__

View file

@ -19,12 +19,8 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef __SOLENOID_H__
#define __SOLENOID_H__
#pragma once
void enable_solenoid_on_active_extruder();
void disable_all_solenoids();
void enable_solenoid(const uint8_t num);
#endif // __SOLENOID_H__

View file

@ -19,9 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef _TMC_UTIL_H_
#define _TMC_UTIL_H_
#pragma once
#include "../inc/MarlinConfig.h"
#if HAS_TRINAMIC
@ -179,5 +177,3 @@ void monitor_tmc_driver();
#if TMC_HAS_SPI
void tmc_init_cs_pins();
#endif
#endif // _TMC_UTIL_H_

View file

@ -19,9 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef TWIBUS_H
#define TWIBUS_H
#pragma once
#include "../core/macros.h"
@ -238,5 +236,3 @@ class TWIBus {
#endif
};
#endif // TWIBUS_H

View file

@ -251,9 +251,7 @@
* T0-T3 - Select an extruder (tool) by index: "T<n> F<units/min>"
*
*/
#ifndef _GCODE_H_
#define _GCODE_H_
#pragma once
#include "../inc/MarlinConfig.h"
#include "parser.h"
@ -829,5 +827,3 @@ private:
};
extern GcodeSuite gcode;
#endif // _GCODE_H_

View file

@ -19,15 +19,13 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* queue.h - The G-code command queue, which holds commands before they
* go to the parser and dispatcher.
*/
#ifndef GCODE_QUEUE_H
#define GCODE_QUEUE_H
#include "../inc/MarlinConfig.h"
/**
@ -125,5 +123,3 @@ void get_available_commands();
* Get the next command in the queue, optionally log it to SD, then dispatch it
*/
void advance_command_queue();
#endif // GCODE_QUEUE_H

View file

@ -19,30 +19,26 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Conditionals_adv.h
* Defines that depend on advanced configuration.
*/
#ifndef CONDITIONALS_ADV_H
#define CONDITIONALS_ADV_H
#if !defined(__AVR__) || !defined(USBCON)
// Define constants and variables for buffering serial data.
// Use only 0 or powers of 2 greater than 1
// : [0, 4, 8, 16, 32, 64, 128, 256, 512, 1024, 2048, ...]
#ifndef RX_BUFFER_SIZE
#define RX_BUFFER_SIZE 128
#endif
// 256 is the max TX buffer limit due to uint8_t head and tail
// : [0, 4, 8, 16, 32, 64, 128, 256]
#ifndef TX_BUFFER_SIZE
#define TX_BUFFER_SIZE 32
#endif
#else
// SERIAL_XON_XOFF not supported on USB-native devices
#undef SERIAL_XON_XOFF
#if !defined(__AVR__) || !defined(USBCON)
// Define constants and variables for buffering serial data.
// Use only 0 or powers of 2 greater than 1
// : [0, 4, 8, 16, 32, 64, 128, 256, 512, 1024, 2048, ...]
#ifndef RX_BUFFER_SIZE
#define RX_BUFFER_SIZE 128
#endif
#endif // CONDITIONALS_ADV_H
// 256 is the max TX buffer limit due to uint8_t head and tail
// : [0, 4, 8, 16, 32, 64, 128, 256]
#ifndef TX_BUFFER_SIZE
#define TX_BUFFER_SIZE 32
#endif
#else
// SERIAL_XON_XOFF not supported on USB-native devices
#undef SERIAL_XON_XOFF
#endif

View file

@ -19,15 +19,13 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Conditionals_post.h
* Defines that depend on configuration but are not editable.
*/
#ifndef CONDITIONALS_POST_H
#define CONDITIONALS_POST_H
#define AVR_ATmega2560_FAMILY_PLUS_70 ( \
MB(BQ_ZUM_MEGA_3D) \
|| MB(MIGHTYBOARD_REVE) \
@ -1637,5 +1635,3 @@
#else
#define Z_STEPPER_COUNT 1
#endif
#endif // CONDITIONALS_POST_H

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Aragonese
@ -27,8 +28,6 @@
* See also http://marlinfw.org/docs/development/lcd_language.html
*
*/
#ifndef LANGUAGE_AN_H
#define LANGUAGE_AN_H
#define DISPLAY_CHARSET_ISO10646_1
#define NOT_EXTENDED_ISO10646_1_5X7
@ -256,5 +255,3 @@
#define MSG_FILAMENT_CHANGE_LOAD_2 _UxGT("cargar filamento")
#define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Aguardando impre.")
#define MSG_FILAMENT_CHANGE_RESUME_2 _UxGT("pa continar")
#endif // LANGUAGE_AN_H

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Bulgarian
@ -27,9 +28,6 @@
* See also http://marlinfw.org/docs/development/lcd_language.html
*
*/
#ifndef LANGUAGE_BG_H
#define LANGUAGE_BG_H
#define DISPLAY_CHARSET_ISO10646_5
#define CHARSIZE 2
@ -146,5 +144,3 @@
#define MSG_DELTA_CALIBRATE_Y _UxGT("Калибровка Y")
#define MSG_DELTA_CALIBRATE_Z _UxGT("Калибровка Z")
#define MSG_DELTA_CALIBRATE_CENTER _UxGT("Калибровка Център")
#endif // LANGUAGE_BG_H

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Catalan
@ -27,8 +28,6 @@
* See also http://marlinfw.org/docs/development/lcd_language.html
*
*/
#ifndef LANGUAGE_CA_H
#define LANGUAGE_CA_H
#define CHARSIZE 2
@ -261,5 +260,3 @@
#define MSG_FILAMENT_CHANGE_LOAD_1 _UxGT("Carregant...")
#define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Reprenent...")
#endif // LCD_HEIGHT < 4
#endif // LANGUAGE_CA_H

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Czech
@ -32,8 +33,6 @@
* http://www.zahradniksebavi.cz
*
*/
#ifndef LANGUAGE_CZ_UTF_H
#define LANGUAGE_CZ_UTF_H
#define DISPLAY_CHARSET_ISO10646_CZ
#define CHARSIZE 2
@ -406,5 +405,3 @@
#define MSG_FILAMENT_CHANGE_PURGE_1 _UxGT("Vytlačování...")
#define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Pokračování...")
#endif // LCD_HEIGHT < 4
#endif // LANGUAGE_CZ_UTF_H

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Danish
@ -27,8 +28,6 @@
* See also http://marlinfw.org/docs/development/lcd_language.html
*
*/
#ifndef LANGUAGE_DA_H
#define LANGUAGE_DA_H
#define DISPLAY_CHARSET_ISO10646_1
#define CHARSIZE 2
@ -250,5 +249,3 @@
#define MSG_FILAMENT_CHANGE_LOAD_1 _UxGT("Indtager...")
#define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Fortsætter...")
#endif // LCD_HEIGHT < 4
#endif // LANGUAGE_DA_H

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* German
@ -27,8 +28,6 @@
* See also http://marlinfw.org/docs/development/lcd_language.html
*
*/
#ifndef LANGUAGE_DE_H
#define LANGUAGE_DE_H
#define CHARSIZE 2
@ -427,5 +426,3 @@
#define MSG_FILAMENT_CHANGE_PURGE_1 _UxGT("Entleeren...")
#define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Fortsetzen...")
#endif // LCD_HEIGHT < 4
#endif // LANGUAGE_DE_H

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Greek (Greece)
@ -27,8 +28,6 @@
* See also http://marlinfw.org/docs/development/lcd_language.html
*
*/
#ifndef LANGUAGE_EL_GR_H
#define LANGUAGE_EL_GR_H
#define DISPLAY_CHARSET_ISO10646_GREEK
#define CHARSIZE 2
@ -186,5 +185,3 @@
#define MSG_DELTA_CALIBRATE_Y _UxGT("Βαθμονόμηση Y")
#define MSG_DELTA_CALIBRATE_Z _UxGT("Βαθμονόμηση Z")
#define MSG_DELTA_CALIBRATE_CENTER _UxGT("Βαθμονόμηση κέντρου")
#endif // LANGUAGE_EL_GR_H

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Greek
@ -27,8 +28,6 @@
* See also http://marlinfw.org/docs/development/lcd_language.html
*
*/
#ifndef LANGUAGE_EL_H
#define LANGUAGE_EL_H
#define DISPLAY_CHARSET_ISO10646_GREEK
#define CHARSIZE 2
@ -187,5 +186,3 @@
#define MSG_DELTA_CALIBRATE_Y _UxGT("Βαθμονόμηση Y")
#define MSG_DELTA_CALIBRATE_Z _UxGT("Βαθμονόμηση Z")
#define MSG_DELTA_CALIBRATE_CENTER _UxGT("Βαθμονόμηση κέντρου")
#endif // LANGUAGE_EL_H

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* English
@ -27,8 +28,6 @@
* See also http://marlinfw.org/docs/development/lcd_language.html
*
*/
#ifndef LANGUAGE_EN_H
#define LANGUAGE_EN_H
#define en 1234
#if LCD_LANGUAGE == en
@ -1149,5 +1148,3 @@
#define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Resuming...")
#endif
#endif // LCD_HEIGHT < 4
#endif // LANGUAGE_EN_H

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Spanish
@ -27,8 +28,6 @@
* See also http://marlinfw.org/docs/development/lcd_language.html
*
*/
#ifndef LANGUAGE_ES_UTF_H
#define LANGUAGE_ES_UTF_H
#define DISPLAY_CHARSET_ISO10646_1
#define CHARSIZE 2
@ -262,5 +261,3 @@
#define MSG_FILAMENT_CHANGE_HEAT_2 _UxGT("Calentar la boquilla")
#define MSG_FILAMENT_CHANGE_HEATING_1 _UxGT("Calentando boquilla")
#define MSG_FILAMENT_CHANGE_HEATING_2 _UxGT("Espere por favor")
#endif // LANGUAGE_ES_UTF_H

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Basque-Euskera
@ -27,8 +28,6 @@
* See also http://marlinfw.org/docs/development/lcd_language.html
*
*/
#ifndef LANGUAGE_EU_H
#define LANGUAGE_EU_H
#define DISPLAY_CHARSET_ISO10646_1
#define NOT_EXTENDED_ISO10646_1_5X7
@ -360,32 +359,30 @@
// ...or up to 2 lines on a 3-line display
//
#if LCD_HEIGHT >= 4
// #define MSG_FILAMENT_CHANGE_INIT_1 _UxGT("Wait for start")
// #define MSG_FILAMENT_CHANGE_INIT_2 _UxGT("of the filament")
// #define MSG_FILAMENT_CHANGE_INIT_3 _UxGT("change")
// #define MSG_FILAMENT_CHANGE_UNLOAD_1 _UxGT("Wait for")
// #define MSG_FILAMENT_CHANGE_UNLOAD_2 _UxGT("filament unload")
// #define MSG_FILAMENT_CHANGE_INSERT_1 _UxGT("Insert filament")
// #define MSG_FILAMENT_CHANGE_INSERT_2 _UxGT("and press button")
// #define MSG_FILAMENT_CHANGE_INSERT_3 _UxGT("to continue...")
// #define MSG_FILAMENT_CHANGE_HEAT_1 _UxGT("Press button to")
// #define MSG_FILAMENT_CHANGE_HEAT_2 _UxGT("heat nozzle.")
// #define MSG_FILAMENT_CHANGE_HEATING_1 _UxGT("Heating nozzle")
// #define MSG_FILAMENT_CHANGE_HEATING_2 _UxGT("Please wait...")
// #define MSG_FILAMENT_CHANGE_LOAD_1 _UxGT("Wait for")
// #define MSG_FILAMENT_CHANGE_LOAD_2 _UxGT("filament load")
// #define MSG_FILAMENT_CHANGE_PURGE_1 _UxGT("Wait for")
// #define MSG_FILAMENT_CHANGE_PURGE_2 _UxGT("filament purge")
// #define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Wait for print")
// #define MSG_FILAMENT_CHANGE_RESUME_2 _UxGT("to resume")
//#define MSG_FILAMENT_CHANGE_INIT_1 _UxGT("Wait for start")
//#define MSG_FILAMENT_CHANGE_INIT_2 _UxGT("of the filament")
//#define MSG_FILAMENT_CHANGE_INIT_3 _UxGT("change")
//#define MSG_FILAMENT_CHANGE_UNLOAD_1 _UxGT("Wait for")
//#define MSG_FILAMENT_CHANGE_UNLOAD_2 _UxGT("filament unload")
//#define MSG_FILAMENT_CHANGE_INSERT_1 _UxGT("Insert filament")
//#define MSG_FILAMENT_CHANGE_INSERT_2 _UxGT("and press button")
//#define MSG_FILAMENT_CHANGE_INSERT_3 _UxGT("to continue...")
//#define MSG_FILAMENT_CHANGE_HEAT_1 _UxGT("Press button to")
//#define MSG_FILAMENT_CHANGE_HEAT_2 _UxGT("heat nozzle.")
//#define MSG_FILAMENT_CHANGE_HEATING_1 _UxGT("Heating nozzle")
//#define MSG_FILAMENT_CHANGE_HEATING_2 _UxGT("Please wait...")
//#define MSG_FILAMENT_CHANGE_LOAD_1 _UxGT("Wait for")
//#define MSG_FILAMENT_CHANGE_LOAD_2 _UxGT("filament load")
//#define MSG_FILAMENT_CHANGE_PURGE_1 _UxGT("Wait for")
//#define MSG_FILAMENT_CHANGE_PURGE_2 _UxGT("filament purge")
//#define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Wait for print")
//#define MSG_FILAMENT_CHANGE_RESUME_2 _UxGT("to resume")
#else // LCD_HEIGHT < 4
#define MSG_FILAMENT_CHANGE_INIT_1 _UxGT("Mesedez, itxaron...")
#define MSG_FILAMENT_CHANGE_UNLOAD_1 _UxGT("Deskargatzen...")
#define MSG_FILAMENT_CHANGE_INSERT_1 _UxGT("Sartu eta click egin")
#define MSG_FILAMENT_CHANGE_HEATING_1 _UxGT("Berotzen...")
#define MSG_FILAMENT_CHANGE_LOAD_1 _UxGT("Kargatzen...")
// #define MSG_FILAMENT_CHANGE_PURGE_1 _UxGT("Purging...")
// #define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Resuming...")
//#define MSG_FILAMENT_CHANGE_PURGE_1 _UxGT("Purging...")
//#define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Resuming...")
#endif // LCD_HEIGHT < 4
#endif // LANGUAGE_EU_H

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Finnish
@ -27,8 +28,6 @@
* See also http://marlinfw.org/docs/development/lcd_language.html
*
*/
#ifndef LANGUAGE_FI_H
#define LANGUAGE_FI_H
#define DISPLAY_CHARSET_ISO10646_1
#define CHARSIZE 2
@ -169,5 +168,3 @@
#define MSG_DELTA_CALIBRATE_Y _UxGT("Kalibroi Y")
#define MSG_DELTA_CALIBRATE_Z _UxGT("Kalibroi Z")
#define MSG_DELTA_CALIBRATE_CENTER _UxGT("Kalibroi Center")
#endif // LANGUAGE_FI_H

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* French
@ -27,8 +28,6 @@
* See also http://marlinfw.org/docs/development/lcd_language.html
*
*/
#ifndef LANGUAGE_FR_UTF_H
#define LANGUAGE_FR_UTF_H
#define DISPLAY_CHARSET_ISO10646_1
#define CHARSIZE 2
@ -392,5 +391,3 @@
#define MSG_FILAMENT_CHANGE_LOAD_1 _UxGT("Chargement...")
#define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Reprise...")
#endif // LCD_HEIGHT < 4
#endif // LANGUAGE_FR_UTF_H

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Galician language (ISO "gl")
@ -27,8 +28,6 @@
* See also http://marlinfw.org/docs/development/lcd_language.html
*
*/
#ifndef LANGUAGE_GL_H
#define LANGUAGE_GL_H
#define DISPLAY_CHARSET_ISO10646_1
#define NOT_EXTENDED_ISO10646_1_5X7
@ -251,5 +250,3 @@
#define MSG_FILAMENT_CHANGE_LOAD_1 _UxGT("Cargando...")
#define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Seguindo...")
#endif // LCD_HEIGHT < 4
#endif // LANGUAGE_GL_H

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Croatian (Hrvatski)
@ -27,8 +28,6 @@
* See also http://marlinfw.org/docs/development/lcd_language.html
*
*/
#ifndef LANGUAGE_HR_H
#define LANGUAGE_HR_H
#define DISPLAY_CHARSET_ISO10646_1 // use the better font on full graphic displays.
#define CHARSIZE 2
@ -250,5 +249,3 @@
#define MSG_FILAMENT_CHANGE_LOAD_1 _UxGT("Loading...")
#define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Nastavljam...")
#endif // LCD_HEIGHT < 4
#endif // LANGUAGE_HR_H

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Italian
@ -27,8 +28,6 @@
* See also http://marlinfw.org/docs/development/lcd_language.html
*
*/
#ifndef LANGUAGE_IT_H
#define LANGUAGE_IT_H
#define DISPLAY_CHARSET_ISO10646_1
@ -423,5 +422,3 @@
#define MSG_FILAMENT_CHANGE_PURGE_1 _UxGT("Spurgo filamento")
#define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Ripresa...")
#endif // LCD_HEIGHT < 4
#endif // LANGUAGE_IT_H

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Japanese (Kana)
@ -29,9 +30,6 @@
*
*/
#ifndef LANGUAGE_KANA_UTF_H
#define LANGUAGE_KANA_UTF_H
#define DISPLAY_CHARSET_ISO10646_KANA
#define CHARSIZE 3
@ -221,5 +219,3 @@
#define MSG_FILAMENT_CHANGE_LOAD_2 _UxGT("シバラクオマチクダサイ") // "filament load"
#define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("プリントヲサイカイシマス") // "Wait for print"
#define MSG_FILAMENT_CHANGE_RESUME_2 _UxGT("シバラクオマチクダサイ") // "to resume"
#endif // LANGUAGE_KANA_UTF_H

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Korean
@ -27,8 +28,6 @@
* See also http://marlinfw.org/docs/development/lcd_language.html
*
*/
#ifndef LANGUAGE_KO_KR_H
#define LANGUAGE_KO_KR_H
#define CHARSIZE 1
@ -412,5 +411,3 @@
#define MSG_FILAMENT_CHANGE_PURGE_1 _UxGT("Purging...")
#define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Resuming...")
#endif // LCD_HEIGHT < 4
#endif // LANGUAGE_KO_KR_H

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Dutch
@ -27,8 +28,6 @@
* See also http://marlinfw.org/docs/development/lcd_language.html
*
*/
#ifndef LANGUAGE_NL_H
#define LANGUAGE_NL_H
#define DISPLAY_CHARSET_ISO10646_1
#define NOT_EXTENDED_ISO10646_1_5X7
@ -281,5 +280,3 @@
#define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Wacht voor")
#define MSG_FILAMENT_CHANGE_RESUME_2 _UxGT("printing...")
#endif // LCD_HEIGHT < 4
#endif // LANGUAGE_NL_H

View file

@ -19,14 +19,12 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Polish for DOGM display - includes accented characters
*/
#ifndef LANGUAGE_PL_DOGM_H
#define LANGUAGE_PL_DOGM_H
#define DISPLAY_CHARSET_ISO10646_PL
#define CHARSIZE 2
@ -253,5 +251,3 @@
#define MSG_FILAMENT_CHANGE_LOAD_1 _UxGT("Ładowanie...")
#define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Wznowienie...")
#endif // LCD_HEIGHT < 4
#endif // LANGUAGE_PL_DOGM_H

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Portuguese (Brazil)
@ -28,8 +29,6 @@
* See also http://marlinfw.org/docs/development/lcd_language.html
*
*/
#ifndef LANGUAGE_PT_BR_UTF_H
#define LANGUAGE_PT_BR_UTF_H
// Put characters here that should be displayed with M117
//_UxGT("áãàçÉéêíóõ")
@ -382,5 +381,3 @@
#define MSG_FILAMENT_CHANGE_EXTRUDE_1 _UxGT("Extrusando...")
#define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Continuando...")
#endif
#endif // LANGUAGE_PT_BR_UTF_H

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Portuguese
@ -28,8 +29,6 @@
* See also http://marlinfw.org/docs/development/lcd_language.html
*
*/
#ifndef LANGUAGE_PT_UTF_H
#define LANGUAGE_PT_UTF_H
#define DISPLAY_CHARSET_ISO10646_1
#define CHARSIZE 2
@ -186,5 +185,3 @@
#define MSG_DELTA_CALIBRATE_CENTER _UxGT("Calibrar Centro")
#define MSG_LCD_ENDSTOPS _UxGT("Fim de curso")
#endif // LANGUAGE_PT_UTF_H

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Russian
@ -27,8 +28,6 @@
* See also http://marlinfw.org/docs/development/lcd_language.html
*
*/
#ifndef LANGUAGE_RU_H
#define LANGUAGE_RU_H
#define DISPLAY_CHARSET_ISO10646_5
#define CHARSIZE 2
@ -399,5 +398,3 @@
#define MSG_FILAMENT_CHANGE_PURGE_1 _UxGT("Выдавливание...")
#define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Возобновление...")
#endif // LCD_HEIGHT < 4
#endif // LANGUAGE_RU_H

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Slovak
@ -31,8 +32,6 @@
* http://www.facebook.com/farmamam
*
*/
#ifndef LANGUAGE_SK_UTF_H
#define LANGUAGE_SK_UTF_H
// Put characters here that should be displayed with M117
//_UxGT("aäAÄaáAÁeéEÉiíIÍlĺLĹ")
@ -437,5 +436,3 @@
#define MSG_FILAMENT_CHANGE_PURGE_1 _UxGT("Vytlačovanie...")
#define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Pokračovanie...")
#endif // LCD_HEIGHT < 4
#endif // LANGUAGE_SK_UTF_H

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* TEST
@ -27,8 +28,6 @@
* See also http://marlinfw.org/docs/development/lcd_language.html
*
*/
#ifndef LANGUAGE_TEST_H
#define LANGUAGE_TEST_H
// Select ONE of the following Mappers.
// They decide what to do with a symbol in the area of [0x80:0xFF]. They take a symbol of this language file and make them point
@ -226,5 +225,3 @@
#define MSG_PID_P STRG_OKTAL_e
#define MSG_PID_I STRG_OKTAL_f
#endif
#endif // LANGUAGE_TEST_H

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Turkish
@ -27,8 +28,6 @@
* See also http://marlinfw.org/docs/development/lcd_language.html
*
*/
#ifndef LANGUAGE_TR_H
#define LANGUAGE_TR_H
#define DISPLAY_CHARSET_ISO10646_TR
#define CHARSIZE 2
@ -266,5 +265,3 @@
#define MSG_FILAMENT_CHANGE_LOAD_1 _UxGT("Yüklüyor...") // Yüklüyor...
#define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Sürdürülüyor...") // Sürdürülüyor...
#endif // LCD_HEIGHT < 4
#endif // LANGUAGE_TR_H

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Ukrainian
@ -27,8 +28,6 @@
* See also http://marlinfw.org/docs/development/lcd_language.html
*
*/
#ifndef LANGUAGE_UK_H
#define LANGUAGE_UK_H
#define DISPLAY_CHARSET_ISO10646_5
#define CHARSIZE 2
@ -240,5 +239,3 @@
#define MSG_FILAMENT_CHANGE_LOAD_1 _UxGT("Ввід...")
#define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Відновлення...")
#endif // LCD_HEIGHT < 4
#endif // LANGUAGE_UK_H

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Simplified Chinese
@ -27,8 +28,6 @@
* See also http://marlinfw.org/docs/development/lcd_language.html
*
*/
#ifndef LANGUAGE_ZH_CN_H
#define LANGUAGE_ZH_CN_H
#define CHARSIZE 3
@ -384,5 +383,3 @@
#define MSG_FILAMENT_CHANGE_PURGE_1 _UxGT("清除中 ...") // "Purging..."
#define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("恢复中 ...") //"Resuming..."
#endif // LCD_HEIGHT < 4
#endif // LANGUAGE_ZH_CN_H

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Traditional Chinese
@ -27,8 +28,6 @@
* See also http://marlinfw.org/docs/development/lcd_language.html
*
*/
#ifndef LANGUAGE_ZH_TW_H
#define LANGUAGE_ZH_TW_H
#define CHARSIZE 3
@ -384,5 +383,3 @@
#define MSG_FILAMENT_CHANGE_PURGE_1 _UxGT("清除中 ...") // "Purging..."
#define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("恢復中 ...") //"Resuming..."
#endif // LCD_HEIGHT < 4
#endif // LANGUAGE_ZH_TW_H

View file

@ -19,9 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef __BUZZER_H__
#define __BUZZER_H__
#pragma once
#include "../inc/MarlinConfig.h"
@ -123,5 +121,3 @@ class Buzzer {
#define BUZZ(d,f) NOOP
#endif
#endif

View file

@ -19,9 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef __CIRCULARQUEUE_H__
#define __CIRCULARQUEUE_H__
#pragma once
#include <stdint.h>
@ -141,5 +139,3 @@ class CircularQueue {
return this->buffer.count;
}
};
#endif

View file

@ -19,9 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef HEX_PRINT_ROUTINES_H
#define HEX_PRINT_ROUTINES_H
#pragma once
#include <stdint.h>
@ -46,5 +44,3 @@ void print_hex_address(const void * const w);
#else
typedef uint16_t ptr_int_t;
#endif
#endif // HEX_PRINT_ROUTINES_H

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Incremental Least Squares Best Fit By Roxy and Ed Williams
@ -32,9 +33,6 @@
*
*/
#ifndef _LEAST_SQUARES_FIT_H_
#define _LEAST_SQUARES_FIT_H_
#include "../inc/MarlinConfig.h"
#include <math.h>
@ -83,5 +81,3 @@ void inline incremental_LSF(struct linear_fit_data *lsf, const float &x, const f
}
int finish_incremental_LSF(struct linear_fit_data *);
#endif // _LEAST_SQUARES_FIT_H_

View file

@ -19,9 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef __NOZZLE_H__
#define __NOZZLE_H__
#pragma once
#include "../inc/MarlinConfig.h"
#include "point_t.h"
@ -90,5 +88,3 @@ class Nozzle {
#endif
};
#endif // __NOZZLE_H__

View file

@ -19,9 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef __PRIVATE_SPI_H__
#define __PRIVATE_SPI_H__
#pragma once
#include "softspi.h"
#include <stdint.h>
@ -53,5 +51,3 @@ class SPIclass<MISO_PIN, MOSI_PIN, SCK_PIN> {
}
};
#endif // __PRIVATE_SPI_H__

View file

@ -19,9 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef STOPWATCH_H
#define STOPWATCH_H
#pragma once
// Print debug messages with M111 S2 (Uses 156 bytes of PROGMEM)
//#define DEBUG_STOPWATCH
@ -116,5 +114,3 @@ class Stopwatch {
#endif
};
#endif // STOPWATCH_H

View file

@ -19,9 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef CONFIGURATION_STORE_H
#define CONFIGURATION_STORE_H
#pragma once
#include "../inc/MarlinConfig.h"
@ -120,5 +118,3 @@ extern MarlinSettings settings;
#undef PORTINIT_SOLO
#undef PORTINIT_AFTER
#endif // CONFIGURATION_STORE_H

View file

@ -19,14 +19,12 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* endstops.h - manages endstops
*/
#ifndef __ENDSTOPS_H__
#define __ENDSTOPS_H__
#include "../inc/MarlinConfig.h"
#include <stdint.h>
@ -173,5 +171,3 @@ class Endstops {
};
extern Endstops endstops;
#endif // __ENDSTOPS_H__

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* planner_bezier.h
@ -27,10 +28,8 @@
*
*/
#ifndef PLANNER_BEZIER_H
#define PLANNER_BEZIER_H
#include "../inc/MarlinConfig.h"
#include <stdint.h>
#include "../core/macros.h"
void cubic_b_spline(
const float position[NUM_AXIS], // current position
@ -39,5 +38,3 @@ void cubic_b_spline(
float fr_mm_s,
uint8_t extruder
);
#endif // PLANNER_BEZIER_H

View file

@ -19,9 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef PRINTCOUNTER_H
#define PRINTCOUNTER_H
#pragma once
#include "../libs/stopwatch.h"
#include "../libs/duration_t.h"
@ -193,5 +191,3 @@ class PrintCounter: public Stopwatch {
#else
extern Stopwatch print_job_timer;
#endif
#endif // PRINTCOUNTER_H

View file

@ -19,14 +19,12 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* probe.h - Move, deploy, enable, etc.
*/
#ifndef PROBE_H
#define PROBE_H
#include "../inc/MarlinConfig.h"
#if HAS_BED_PROBE
@ -73,5 +71,3 @@
set_bltouch_deployed(false);
}
#endif
#endif // PROBE_H

View file

@ -19,14 +19,12 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* module/servo.h
*/
#ifndef _SERVO_H_
#define _SERVO_H_
#include "../inc/MarlinConfig.h"
#include "../HAL/shared/servo.h"
@ -40,5 +38,3 @@ extern void servo_init();
#define DEPLOY_Z_SERVO() MOVE_SERVO(Z_PROBE_SERVO_NR, servo_angles[Z_PROBE_SERVO_NR][0])
#define STOW_Z_SERVO() MOVE_SERVO(Z_PROBE_SERVO_NR, servo_angles[Z_PROBE_SERVO_NR][1])
#endif
#endif // _SERVO_H_

View file

@ -19,9 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef SPEED_LOOKUPTABLE_H
#define SPEED_LOOKUPTABLE_H
#pragma once
#if F_CPU == 16000000
@ -168,5 +166,3 @@
};
#endif
#endif // SPEED_LOOKUPTABLE_H

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* stepper.h - stepper motor driver: executes motion plans of planner.c using the stepper motors
@ -40,9 +41,6 @@
* along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef STEPPER_H
#define STEPPER_H
#include "../inc/MarlinConfig.h"
// Disable multiple steps per ISR
@ -559,5 +557,3 @@ class Stepper {
};
extern Stepper stepper;
#endif // STEPPER_H

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* stepper_indirection.h - stepper motor driver indirection macros
@ -41,9 +42,6 @@
* along with Marlin. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef STEPPER_INDIRECTION_H
#define STEPPER_INDIRECTION_H
#include "../inc/MarlinConfig.h"
// TMC26X drivers have STEP/DIR on normal pins, but ENABLE via SPI
@ -615,5 +613,3 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset
#define NORM_E_DIR(E) E0_DIR_WRITE(!INVERT_E0_DIR)
#define REV_E_DIR(E) E0_DIR_WRITE( INVERT_E0_DIR)
#endif
#endif // STEPPER_INDIRECTION_H

View file

@ -19,14 +19,12 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* temperature.h - temperature controller
*/
#ifndef TEMPERATURE_H
#define TEMPERATURE_H
#include "thermistor/thermistors.h"
#include "../inc/MarlinConfig.h"
@ -660,5 +658,3 @@ class Temperature {
};
extern Temperature thermalManager;
#endif // TEMPERATURE_H

View file

@ -22,17 +22,17 @@
// Pt1000 with 1k0 pullup
const short temptable_1010[][2] PROGMEM = {
PtLine( 0, 1000, 1000)
PtLine( 25, 1000, 1000)
PtLine( 50, 1000, 1000)
PtLine( 75, 1000, 1000)
PtLine(100, 1000, 1000)
PtLine(125, 1000, 1000)
PtLine(150, 1000, 1000)
PtLine(175, 1000, 1000)
PtLine(200, 1000, 1000)
PtLine(225, 1000, 1000)
PtLine(250, 1000, 1000)
PtLine(275, 1000, 1000)
PtLine( 0, 1000, 1000),
PtLine( 25, 1000, 1000),
PtLine( 50, 1000, 1000),
PtLine( 75, 1000, 1000),
PtLine(100, 1000, 1000),
PtLine(125, 1000, 1000),
PtLine(150, 1000, 1000),
PtLine(175, 1000, 1000),
PtLine(200, 1000, 1000),
PtLine(225, 1000, 1000),
PtLine(250, 1000, 1000),
PtLine(275, 1000, 1000),
PtLine(300, 1000, 1000)
};

View file

@ -23,11 +23,11 @@
// Pt1000 with 4k7 pullup
const short temptable_1047[][2] PROGMEM = {
// only a few values are needed as the curve is very flat
PtLine( 0, 1000, 4700)
PtLine( 50, 1000, 4700)
PtLine(100, 1000, 4700)
PtLine(150, 1000, 4700)
PtLine(200, 1000, 4700)
PtLine(250, 1000, 4700)
PtLine( 0, 1000, 4700),
PtLine( 50, 1000, 4700),
PtLine(100, 1000, 4700),
PtLine(150, 1000, 4700),
PtLine(200, 1000, 4700),
PtLine(250, 1000, 4700),
PtLine(300, 1000, 4700)
};

View file

@ -23,11 +23,11 @@
// Pt100 with 1k0 pullup
const short temptable_110[][2] PROGMEM = {
// only a few values are needed as the curve is very flat
PtLine( 0, 100, 1000)
PtLine( 50, 100, 1000)
PtLine(100, 100, 1000)
PtLine(150, 100, 1000)
PtLine(200, 100, 1000)
PtLine(250, 100, 1000)
PtLine( 0, 100, 1000),
PtLine( 50, 100, 1000),
PtLine(100, 100, 1000),
PtLine(150, 100, 1000),
PtLine(200, 100, 1000),
PtLine(250, 100, 1000),
PtLine(300, 100, 1000)
};

View file

@ -23,11 +23,11 @@
// Pt100 with 4k7 pullup
const short temptable_147[][2] PROGMEM = {
// only a few values are needed as the curve is very flat
PtLine( 0, 100, 4700)
PtLine( 50, 100, 4700)
PtLine(100, 100, 4700)
PtLine(150, 100, 4700)
PtLine(200, 100, 4700)
PtLine(250, 100, 4700)
PtLine( 0, 100, 4700),
PtLine( 50, 100, 4700),
PtLine(100, 100, 4700),
PtLine(150, 100, 4700),
PtLine(200, 100, 4700),
PtLine(250, 100, 4700),
PtLine(300, 100, 4700)
};

View file

@ -19,9 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#ifndef THERMISTORS_H_
#define THERMISTORS_H_
#pragma once
#include "../../inc/MarlinConfig.h"
@ -36,9 +34,9 @@
// a=3.9083E-3, b=-5.775E-7
#define PtA 3.9083E-3
#define PtB -5.775E-7
#define PtRt(T,R0) ((R0)*(1.0+(PtA)*(T)+(PtB)*(T)*(T)))
#define PtAdVal(T,R0,Rup) (short)(1024/(Rup/PtRt(T,R0)+1))
#define PtLine(T,R0,Rup) { OV(PtAdVal(T,R0,Rup)), T },
#define PtRt(T,R0) ((R0) * (1.0 + (PtA) * (T) + (PtB) * (T) * (T)))
#define PtAdVal(T,R0,Rup) (short)(1024 / (Rup / PtRt(T, R0) + 1))
#define PtLine(T,R0,Rup) { OV(PtAdVal(T, R0, Rup)), T }
#if ANY_THERMISTOR_IS(1) // beta25 = 4092 K, R25 = 100 kOhm, Pull-up = 4.7 kOhm, "EPCOS"
#include "thermistor_1.h"
@ -276,5 +274,3 @@ static_assert(HEATER_0_TEMPTABLE_LEN < 256 && HEATER_1_TEMPTABLE_LEN < 256 && HE
#define HEATER_CHAMBER_RAW_LO_TEMP 0
#endif
#endif
#endif // THERMISTORS_H_

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* \file
@ -31,8 +32,6 @@
*
* This file is part of the Arduino Sd2Card Library
*/
#ifndef _SD2CARD_H_
#define _SD2CARD_H_
#include "SdFatConfig.h"
#include "SdInfo.h"
@ -202,5 +201,3 @@ class Sd2Card {
bool waitNotBusy(const millis_t timeout_ms);
bool writeData(uint8_t token, const uint8_t* src);
};
#endif // _SD2CARD_H_

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* \file
@ -31,9 +32,6 @@
*
* This file is part of the Arduino Sd2Card Library
*/
#ifndef _SDBASEFILE_H_
#define _SDBASEFILE_H_
#include "SdFatConfig.h"
#include "SdVolume.h"
@ -387,5 +385,3 @@ class SdBaseFile {
bool openCachedEntry(uint8_t cacheIndex, uint8_t oflags);
dir_t* readDirCache();
};
#endif // _SDBASEFILE_H_

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* SdFatConfig.h
@ -28,12 +29,8 @@
* This file is part of the Arduino Sd2Card Library
*/
#ifndef _SDFATCONFIG_H_
#define _SDFATCONFIG_H_
#include "../inc/MarlinConfig.h"
/**
* To use multiple SD cards set USE_MULTIPLE_CARDS nonzero.
*
@ -113,5 +110,3 @@
// Total bytes needed to store a single long filename
#define LONG_FILENAME_LENGTH (FILENAME_LENGTH * MAX_VFAT_ENTRIES + 1)
#endif // _SDFATCONFIG_H_

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* \file
@ -31,8 +32,6 @@
*
* This file is part of the Arduino Sd2Card Library
*/
#ifndef SDFATSTRUCTS_H
#define SDFATSTRUCTS_H
#include <stdint.h>
@ -613,5 +612,3 @@ static inline uint8_t DIR_IS_SUBDIR(const dir_t* dir) {
static inline uint8_t DIR_IS_FILE_OR_SUBDIR(const dir_t* dir) {
return (dir->attributes & DIR_ATT_VOLUME_ID) == 0;
}
#endif // SDFATSTRUCTS_H

View file

@ -32,6 +32,7 @@
#if ENABLED(SDSUPPORT)
#include "SdFatUtil.h"
#include <string.h>
/**
* Amount of free RAM

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Arduino SdFat Library
@ -26,10 +27,6 @@
*
* This file is part of the Arduino Sd2Card Library
*/
#ifndef _SDFATUTIL_H_
#define _SDFATUTIL_H_
#include <string.h>
/**
* \file
@ -41,5 +38,3 @@ namespace SdFatUtil {
}
using namespace SdFatUtil; // NOLINT
#endif // _SDFATUTIL_H_

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* \file
@ -31,8 +32,6 @@
*
* This file is part of the Arduino Sd2Card Library
*/
#ifndef _SDFILE_H_
#define _SDFILE_H_
#include "SdBaseFile.h"
@ -58,5 +57,3 @@ class SdFile : public SdBaseFile/*, public Print*/ {
void write_P(PGM_P str);
void writeln_P(PGM_P str);
};
#endif // _SDFILE_H_

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Arduino Sd2Card Library
@ -26,8 +27,6 @@
*
* This file is part of the Arduino Sd2Card Library
*/
#ifndef _SDINFO_H_
#define _SDINFO_H_
#include <stdint.h>
@ -264,5 +263,3 @@ union csd_t {
csd1_t v1;
csd2_t v2;
};
#endif // _SDINFO_H_

View file

@ -19,6 +19,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* \file
@ -31,8 +32,6 @@
*
* This file is part of the Arduino Sd2Card Library
*/
#ifndef _SDVOLUME_H_
#define _SDVOLUME_H_
#if ENABLED(USB_FLASH_DRIVE_SUPPORT)
#include "usb_flashdrive/Sd2Card_FlashDrive.h"
@ -195,5 +194,3 @@ class SdVolume {
bool readBlock(uint32_t block, uint8_t* dst) { return sdCard_->readBlock(block, dst); }
bool writeBlock(uint32_t block, const uint8_t* dst) { return sdCard_->writeBlock(block, dst); }
};
#endif // _SDVOLUME_H_

View file

@ -19,15 +19,13 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* \file
* \brief Sd2Card class for V2 SD/SDHC cards
*/
#ifndef _SD2CARD_FLASHDRIVE_H_
#define _SD2CARD_FLASHDRIVE_H_
/* Uncomment USB_DEBUG to enable debugging.
* 1 - basic debugging and bounds checking
* 2 - print each block access
@ -99,5 +97,3 @@ class Sd2Card {
uint32_t cardSize();
static bool isInserted();
};
#endif // _SD2CARD_FLASHDRIVE_H_

View file

@ -26,8 +26,7 @@ e-mail : support@circuitsathome.com
#error "Never include UsbCore.h directly; include Usb.h instead"
#endif
#ifndef USBCORE_H
#define USBCORE_H
#pragma once
// Not used anymore? If anyone uses this, please let us know so that this may be
// moved to the proper place, settings.h.
@ -137,68 +136,68 @@ typedef MAX3421e<P10, P9> MAX3421E; // Official Arduinos (UNO, Duemilanove, Mega
class USBDeviceConfig {
public:
virtual uint8_t Init(uint8_t parent __attribute__((unused)), uint8_t port __attribute__((unused)), bool lowspeed __attribute__((unused))) {
return 0;
}
virtual uint8_t Init(uint8_t parent __attribute__((unused)), uint8_t port __attribute__((unused)), bool lowspeed __attribute__((unused))) {
return 0;
}
virtual uint8_t ConfigureDevice(uint8_t parent __attribute__((unused)), uint8_t port __attribute__((unused)), bool lowspeed __attribute__((unused))) {
return 0;
}
virtual uint8_t ConfigureDevice(uint8_t parent __attribute__((unused)), uint8_t port __attribute__((unused)), bool lowspeed __attribute__((unused))) {
return 0;
}
virtual uint8_t Release() {
return 0;
}
virtual uint8_t Release() {
return 0;
}
virtual uint8_t Poll() {
return 0;
}
virtual uint8_t Poll() {
return 0;
}
virtual uint8_t GetAddress() {
return 0;
}
virtual uint8_t GetAddress() {
return 0;
}
virtual void ResetHubPort(uint8_t port __attribute__((unused))) {
return;
} // Note used for hubs only!
virtual void ResetHubPort(uint8_t port __attribute__((unused))) {
return;
} // Note used for hubs only!
virtual bool VIDPIDOK(uint16_t vid __attribute__((unused)), uint16_t pid __attribute__((unused))) {
return false;
}
virtual bool VIDPIDOK(uint16_t vid __attribute__((unused)), uint16_t pid __attribute__((unused))) {
return false;
}
virtual bool DEVCLASSOK(uint8_t klass __attribute__((unused))) {
return false;
}
virtual bool DEVCLASSOK(uint8_t klass __attribute__((unused))) {
return false;
}
virtual bool DEVSUBCLASSOK(uint8_t subklass __attribute__((unused))) {
return true;
}
virtual bool DEVSUBCLASSOK(uint8_t subklass __attribute__((unused))) {
return true;
}
};
/* USB Setup Packet Structure */
typedef struct {
union { // offset description
uint8_t bmRequestType; // 0 Bit-map of request type
union { // offset description
uint8_t bmRequestType; // 0 Bit-map of request type
struct {
uint8_t recipient : 5; // Recipient of the request
uint8_t type : 2; // Type of request
uint8_t direction : 1; // Direction of data X-fer
} __attribute__((packed));
} ReqType_u;
uint8_t bRequest; // 1 Request
struct {
uint8_t recipient : 5; // Recipient of the request
uint8_t type : 2; // Type of request
uint8_t direction : 1; // Direction of data X-fer
} __attribute__((packed));
} ReqType_u;
uint8_t bRequest; // 1 Request
union {
uint16_t wValue; // 2 Depends on bRequest
union {
uint16_t wValue; // 2 Depends on bRequest
struct {
uint8_t wValueLo;
uint8_t wValueHi;
} __attribute__((packed));
} wVal_u;
uint16_t wIndex; // 4 Depends on bRequest
uint16_t wLength; // 6 Depends on bRequest
struct {
uint8_t wValueLo;
uint8_t wValueHi;
} __attribute__((packed));
} wVal_u;
uint16_t wIndex; // 4 Depends on bRequest
uint16_t wLength; // 6 Depends on bRequest
} __attribute__((packed)) SETUP_PKT, *PSETUP_PKT;
@ -207,108 +206,106 @@ typedef struct {
class USBReadParser {
public:
virtual void Parse(const uint16_t len, const uint8_t *pbuf, const uint16_t &offset) = 0;
virtual void Parse(const uint16_t len, const uint8_t *pbuf, const uint16_t &offset) = 0;
};
class USB : public MAX3421E {
AddressPoolImpl<USB_NUMDEVICES> addrPool;
USBDeviceConfig* devConfig[USB_NUMDEVICES];
uint8_t bmHubPre;
AddressPoolImpl<USB_NUMDEVICES> addrPool;
USBDeviceConfig* devConfig[USB_NUMDEVICES];
uint8_t bmHubPre;
public:
USB(void);
USB(void);
void SetHubPreMask() {
bmHubPre |= bmHUBPRE;
};
void SetHubPreMask() {
bmHubPre |= bmHUBPRE;
};
void ResetHubPreMask() {
bmHubPre &= (~bmHUBPRE);
};
void ResetHubPreMask() {
bmHubPre &= (~bmHUBPRE);
};
AddressPool& GetAddressPool() {
return (AddressPool&)addrPool;
};
AddressPool& GetAddressPool() {
return (AddressPool&)addrPool;
};
uint8_t RegisterDeviceClass(USBDeviceConfig *pdev) {
for(uint8_t i = 0; i < USB_NUMDEVICES; i++) {
if(!devConfig[i]) {
devConfig[i] = pdev;
return 0;
}
}
return USB_ERROR_UNABLE_TO_REGISTER_DEVICE_CLASS;
};
uint8_t RegisterDeviceClass(USBDeviceConfig *pdev) {
for(uint8_t i = 0; i < USB_NUMDEVICES; i++) {
if(!devConfig[i]) {
devConfig[i] = pdev;
return 0;
}
}
return USB_ERROR_UNABLE_TO_REGISTER_DEVICE_CLASS;
};
void ForEachUsbDevice(UsbDeviceHandleFunc pfunc) {
addrPool.ForEachUsbDevice(pfunc);
};
uint8_t getUsbTaskState(void);
void setUsbTaskState(uint8_t state);
void ForEachUsbDevice(UsbDeviceHandleFunc pfunc) {
addrPool.ForEachUsbDevice(pfunc);
};
uint8_t getUsbTaskState(void);
void setUsbTaskState(uint8_t state);
EpInfo* getEpInfoEntry(uint8_t addr, uint8_t ep);
uint8_t setEpInfoEntry(uint8_t addr, uint8_t epcount, EpInfo* eprecord_ptr);
EpInfo* getEpInfoEntry(uint8_t addr, uint8_t ep);
uint8_t setEpInfoEntry(uint8_t addr, uint8_t epcount, EpInfo* eprecord_ptr);
/* Control requests */
uint8_t getDevDescr(uint8_t addr, uint8_t ep, uint16_t nbytes, uint8_t* dataptr);
uint8_t getConfDescr(uint8_t addr, uint8_t ep, uint16_t nbytes, uint8_t conf, uint8_t* dataptr);
/* Control requests */
uint8_t getDevDescr(uint8_t addr, uint8_t ep, uint16_t nbytes, uint8_t* dataptr);
uint8_t getConfDescr(uint8_t addr, uint8_t ep, uint16_t nbytes, uint8_t conf, uint8_t* dataptr);
uint8_t getConfDescr(uint8_t addr, uint8_t ep, uint8_t conf, USBReadParser *p);
uint8_t getConfDescr(uint8_t addr, uint8_t ep, uint8_t conf, USBReadParser *p);
uint8_t getStrDescr(uint8_t addr, uint8_t ep, uint16_t nbytes, uint8_t index, uint16_t langid, uint8_t* dataptr);
uint8_t setAddr(uint8_t oldaddr, uint8_t ep, uint8_t newaddr);
uint8_t setConf(uint8_t addr, uint8_t ep, uint8_t conf_value);
/**/
uint8_t ctrlData(uint8_t addr, uint8_t ep, uint16_t nbytes, uint8_t* dataptr, bool direction);
uint8_t ctrlStatus(uint8_t ep, bool direction, uint16_t nak_limit);
uint8_t inTransfer(uint8_t addr, uint8_t ep, uint16_t *nbytesptr, uint8_t* data, uint8_t bInterval = 0);
uint8_t outTransfer(uint8_t addr, uint8_t ep, uint16_t nbytes, uint8_t* data);
uint8_t dispatchPkt(uint8_t token, uint8_t ep, uint16_t nak_limit);
uint8_t getStrDescr(uint8_t addr, uint8_t ep, uint16_t nbytes, uint8_t index, uint16_t langid, uint8_t* dataptr);
uint8_t setAddr(uint8_t oldaddr, uint8_t ep, uint8_t newaddr);
uint8_t setConf(uint8_t addr, uint8_t ep, uint8_t conf_value);
/**/
uint8_t ctrlData(uint8_t addr, uint8_t ep, uint16_t nbytes, uint8_t* dataptr, bool direction);
uint8_t ctrlStatus(uint8_t ep, bool direction, uint16_t nak_limit);
uint8_t inTransfer(uint8_t addr, uint8_t ep, uint16_t *nbytesptr, uint8_t* data, uint8_t bInterval = 0);
uint8_t outTransfer(uint8_t addr, uint8_t ep, uint16_t nbytes, uint8_t* data);
uint8_t dispatchPkt(uint8_t token, uint8_t ep, uint16_t nak_limit);
void Task(void);
void Task(void);
uint8_t DefaultAddressing(uint8_t parent, uint8_t port, bool lowspeed);
uint8_t Configuring(uint8_t parent, uint8_t port, bool lowspeed);
uint8_t ReleaseDevice(uint8_t addr);
uint8_t DefaultAddressing(uint8_t parent, uint8_t port, bool lowspeed);
uint8_t Configuring(uint8_t parent, uint8_t port, bool lowspeed);
uint8_t ReleaseDevice(uint8_t addr);
uint8_t ctrlReq(uint8_t addr, uint8_t ep, uint8_t bmReqType, uint8_t bRequest, uint8_t wValLo, uint8_t wValHi,
uint16_t wInd, uint16_t total, uint16_t nbytes, uint8_t* dataptr, USBReadParser *p);
uint8_t ctrlReq(uint8_t addr, uint8_t ep, uint8_t bmReqType, uint8_t bRequest, uint8_t wValLo, uint8_t wValHi,
uint16_t wInd, uint16_t total, uint16_t nbytes, uint8_t* dataptr, USBReadParser *p);
private:
void init();
uint8_t SetAddress(uint8_t addr, uint8_t ep, EpInfo **ppep, uint16_t *nak_limit);
uint8_t OutTransfer(EpInfo *pep, uint16_t nak_limit, uint16_t nbytes, uint8_t *data);
uint8_t InTransfer(EpInfo *pep, uint16_t nak_limit, uint16_t *nbytesptr, uint8_t *data, uint8_t bInterval = 0);
uint8_t AttemptConfig(uint8_t driver, uint8_t parent, uint8_t port, bool lowspeed);
void init();
uint8_t SetAddress(uint8_t addr, uint8_t ep, EpInfo **ppep, uint16_t *nak_limit);
uint8_t OutTransfer(EpInfo *pep, uint16_t nak_limit, uint16_t nbytes, uint8_t *data);
uint8_t InTransfer(EpInfo *pep, uint16_t nak_limit, uint16_t *nbytesptr, uint8_t *data, uint8_t bInterval = 0);
uint8_t AttemptConfig(uint8_t driver, uint8_t parent, uint8_t port, bool lowspeed);
};
#if 0 //defined(USB_METHODS_INLINE)
//get device descriptor
inline uint8_t USB::getDevDescr(uint8_t addr, uint8_t ep, uint16_t nbytes, uint8_t* dataptr) {
return ( ctrlReq(addr, ep, bmREQ_GET_DESCR, USB_REQUEST_GET_DESCRIPTOR, 0x00, USB_DESCRIPTOR_DEVICE, 0x0000, nbytes, dataptr));
return ( ctrlReq(addr, ep, bmREQ_GET_DESCR, USB_REQUEST_GET_DESCRIPTOR, 0x00, USB_DESCRIPTOR_DEVICE, 0x0000, nbytes, dataptr));
}
//get configuration descriptor
inline uint8_t USB::getConfDescr(uint8_t addr, uint8_t ep, uint16_t nbytes, uint8_t conf, uint8_t* dataptr) {
return ( ctrlReq(addr, ep, bmREQ_GET_DESCR, USB_REQUEST_GET_DESCRIPTOR, conf, USB_DESCRIPTOR_CONFIGURATION, 0x0000, nbytes, dataptr));
return ( ctrlReq(addr, ep, bmREQ_GET_DESCR, USB_REQUEST_GET_DESCRIPTOR, conf, USB_DESCRIPTOR_CONFIGURATION, 0x0000, nbytes, dataptr));
}
//get string descriptor
inline uint8_t USB::getStrDescr(uint8_t addr, uint8_t ep, uint16_t nuint8_ts, uint8_t index, uint16_t langid, uint8_t* dataptr) {
return ( ctrlReq(addr, ep, bmREQ_GET_DESCR, USB_REQUEST_GET_DESCRIPTOR, index, USB_DESCRIPTOR_STRING, langid, nuint8_ts, dataptr));
return ( ctrlReq(addr, ep, bmREQ_GET_DESCR, USB_REQUEST_GET_DESCRIPTOR, index, USB_DESCRIPTOR_STRING, langid, nuint8_ts, dataptr));
}
//set address
inline uint8_t USB::setAddr(uint8_t oldaddr, uint8_t ep, uint8_t newaddr) {
return ( ctrlReq(oldaddr, ep, bmREQ_SET, USB_REQUEST_SET_ADDRESS, newaddr, 0x00, 0x0000, 0x0000, NULL));
return ( ctrlReq(oldaddr, ep, bmREQ_SET, USB_REQUEST_SET_ADDRESS, newaddr, 0x00, 0x0000, 0x0000, NULL));
}
//set configuration
inline uint8_t USB::setConf(uint8_t addr, uint8_t ep, uint8_t conf_value) {
return ( ctrlReq(addr, ep, bmREQ_SET, USB_REQUEST_SET_CONFIGURATION, conf_value, 0x00, 0x0000, 0x0000, NULL));
return ( ctrlReq(addr, ep, bmREQ_SET, USB_REQUEST_SET_CONFIGURATION, conf_value, 0x00, 0x0000, 0x0000, NULL));
}
#endif // defined(USB_METHODS_INLINE)
#endif /* USBCORE_H */

View file

@ -26,8 +26,7 @@ e-mail : support@circuitsathome.com
#error "Never include macros.h directly; include Usb.h instead"
#endif
#ifndef MACROS_H
#define MACROS_H
#pragma once
////////////////////////////////////////////////////////////////////////////////
// HANDY MACROS
@ -85,5 +84,3 @@ e-mail : support@circuitsathome.com
#define USBTRACE1(s,l) (Notify(PSTR(s), l))
#define USBTRACE2(s,r) (Notify(PSTR(s), 0x80), D_PrintHex((r), 0x80), Notify(PSTR("\r\n"), 0x80))
#define USBTRACE3(s,r,l) (Notify(PSTR(s), l), D_PrintHex((r), l), Notify(PSTR("\r\n"), l))
#endif /* MACROS_H */

View file

@ -22,12 +22,11 @@ Web : http://www.circuitsathome.com
e-mail : support@circuitsathome.com
*/
#if !defined(__MASSTORAGE_H__)
#define __MASSTORAGE_H__
#pragma once
// Cruft removal, makes driver smaller, faster.
#ifndef MS_WANT_PARSER
#define MS_WANT_PARSER 0
#define MS_WANT_PARSER 0
#endif
#include "Usb.h"
@ -184,395 +183,394 @@ e-mail : support@circuitsathome.com
#define MASS_MAX_ENDPOINTS 3
struct Capacity {
uint8_t data[8];
//uint32_t dwBlockAddress;
//uint32_t dwBlockLength;
uint8_t data[8];
//uint32_t dwBlockAddress;
//uint32_t dwBlockLength;
} __attribute__((packed));
struct BASICCDB {
uint8_t Opcode;
uint8_t Opcode;
unsigned unused : 5;
unsigned LUN : 3;
unsigned unused : 5;
unsigned LUN : 3;
uint8_t info[12];
uint8_t info[12];
} __attribute__((packed));
typedef BASICCDB BASICCDB_t;
struct CDB6 {
uint8_t Opcode;
uint8_t Opcode;
unsigned LBAMSB : 5;
unsigned LUN : 3;
unsigned LBAMSB : 5;
unsigned LUN : 3;
uint8_t LBAHB;
uint8_t LBALB;
uint8_t AllocationLength;
uint8_t Control;
uint8_t LBAHB;
uint8_t LBALB;
uint8_t AllocationLength;
uint8_t Control;
public:
CDB6(uint8_t _Opcode, uint8_t _LUN, uint32_t LBA, uint8_t _AllocationLength, uint8_t _Control) :
Opcode(_Opcode), LBAMSB(BGRAB2(LBA) & 0x1f), LUN(_LUN), LBAHB(BGRAB1(LBA)), LBALB(BGRAB0(LBA)),
AllocationLength(_AllocationLength), Control(_Control) {
}
CDB6(uint8_t _Opcode, uint8_t _LUN, uint32_t LBA, uint8_t _AllocationLength, uint8_t _Control) :
Opcode(_Opcode), LBAMSB(BGRAB2(LBA) & 0x1f), LUN(_LUN), LBAHB(BGRAB1(LBA)), LBALB(BGRAB0(LBA)),
AllocationLength(_AllocationLength), Control(_Control) {
}
CDB6(uint8_t _Opcode, uint8_t _LUN, uint8_t _AllocationLength, uint8_t _Control) :
Opcode(_Opcode), LBAMSB(0), LUN(_LUN), LBAHB(0), LBALB(0),
AllocationLength(_AllocationLength), Control(_Control) {
}
CDB6(uint8_t _Opcode, uint8_t _LUN, uint8_t _AllocationLength, uint8_t _Control) :
Opcode(_Opcode), LBAMSB(0), LUN(_LUN), LBAHB(0), LBALB(0),
AllocationLength(_AllocationLength), Control(_Control) {
}
} __attribute__((packed));
typedef CDB6 CDB6_t;
struct CDB10 {
uint8_t Opcode;
uint8_t Opcode;
unsigned Service_Action : 5;
unsigned LUN : 3;
unsigned Service_Action : 5;
unsigned LUN : 3;
uint8_t LBA_L_M_MB;
uint8_t LBA_L_M_LB;
uint8_t LBA_L_L_MB;
uint8_t LBA_L_L_LB;
uint8_t LBA_L_M_MB;
uint8_t LBA_L_M_LB;
uint8_t LBA_L_L_MB;
uint8_t LBA_L_L_LB;
uint8_t Misc2;
uint8_t Misc2;
uint8_t ALC_MB;
uint8_t ALC_LB;
uint8_t ALC_MB;
uint8_t ALC_LB;
uint8_t Control;
uint8_t Control;
public:
CDB10(uint8_t _Opcode, uint8_t _LUN) :
Opcode(_Opcode), Service_Action(0), LUN(_LUN),
LBA_L_M_MB(0), LBA_L_M_LB(0), LBA_L_L_MB(0), LBA_L_L_LB(0),
Misc2(0), ALC_MB(0), ALC_LB(0), Control(0) {
}
CDB10(uint8_t _Opcode, uint8_t _LUN) :
Opcode(_Opcode), Service_Action(0), LUN(_LUN),
LBA_L_M_MB(0), LBA_L_M_LB(0), LBA_L_L_MB(0), LBA_L_L_LB(0),
Misc2(0), ALC_MB(0), ALC_LB(0), Control(0) {
}
CDB10(uint8_t _Opcode, uint8_t _LUN, uint16_t xflen, uint32_t _LBA) :
Opcode(_Opcode), Service_Action(0), LUN(_LUN),
LBA_L_M_MB(BGRAB3(_LBA)), LBA_L_M_LB(BGRAB2(_LBA)), LBA_L_L_MB(BGRAB1(_LBA)), LBA_L_L_LB(BGRAB0(_LBA)),
Misc2(0), ALC_MB(BGRAB1(xflen)), ALC_LB(BGRAB0(xflen)), Control(0) {
}
CDB10(uint8_t _Opcode, uint8_t _LUN, uint16_t xflen, uint32_t _LBA) :
Opcode(_Opcode), Service_Action(0), LUN(_LUN),
LBA_L_M_MB(BGRAB3(_LBA)), LBA_L_M_LB(BGRAB2(_LBA)), LBA_L_L_MB(BGRAB1(_LBA)), LBA_L_L_LB(BGRAB0(_LBA)),
Misc2(0), ALC_MB(BGRAB1(xflen)), ALC_LB(BGRAB0(xflen)), Control(0) {
}
} __attribute__((packed));
typedef CDB10 CDB10_t;
struct CDB12 {
uint8_t Opcode;
uint8_t Opcode;
unsigned Service_Action : 5;
unsigned Misc : 3;
unsigned Service_Action : 5;
unsigned Misc : 3;
uint8_t LBA_L_M_LB;
uint8_t LBA_L_L_MB;
uint8_t LBA_L_L_LB;
uint8_t LBA_L_M_LB;
uint8_t LBA_L_L_MB;
uint8_t LBA_L_L_LB;
uint8_t ALC_M_LB;
uint8_t ALC_L_MB;
uint8_t ALC_L_LB;
uint8_t Control;
uint8_t ALC_M_LB;
uint8_t ALC_L_MB;
uint8_t ALC_L_LB;
uint8_t Control;
} __attribute__((packed));
typedef CDB12 CDB12_t;
struct CDB_LBA32_16 {
uint8_t Opcode;
uint8_t Opcode;
unsigned Service_Action : 5;
unsigned Misc : 3;
unsigned Service_Action : 5;
unsigned Misc : 3;
uint8_t LBA_L_M_MB;
uint8_t LBA_L_M_LB;
uint8_t LBA_L_L_MB;
uint8_t LBA_L_L_LB;
uint8_t LBA_L_M_MB;
uint8_t LBA_L_M_LB;
uint8_t LBA_L_L_MB;
uint8_t LBA_L_L_LB;
uint8_t A_M_M_MB;
uint8_t A_M_M_LB;
uint8_t A_M_L_MB;
uint8_t A_M_L_LB;
uint8_t A_M_M_MB;
uint8_t A_M_M_LB;
uint8_t A_M_L_MB;
uint8_t A_M_L_LB;
uint8_t ALC_M_MB;
uint8_t ALC_M_LB;
uint8_t ALC_L_MB;
uint8_t ALC_L_LB;
uint8_t ALC_M_MB;
uint8_t ALC_M_LB;
uint8_t ALC_L_MB;
uint8_t ALC_L_LB;
uint8_t Misc2;
uint8_t Control;
uint8_t Misc2;
uint8_t Control;
} __attribute__((packed));
struct CDB_LBA64_16 {
uint8_t Opcode;
uint8_t Misc;
uint8_t Opcode;
uint8_t Misc;
uint8_t LBA_M_M_MB;
uint8_t LBA_M_M_LB;
uint8_t LBA_M_L_MB;
uint8_t LBA_M_L_LB;
uint8_t LBA_M_M_MB;
uint8_t LBA_M_M_LB;
uint8_t LBA_M_L_MB;
uint8_t LBA_M_L_LB;
uint8_t LBA_L_M_MB;
uint8_t LBA_L_M_LB;
uint8_t LBA_L_L_MB;
uint8_t LBA_L_L_LB;
uint8_t LBA_L_M_MB;
uint8_t LBA_L_M_LB;
uint8_t LBA_L_L_MB;
uint8_t LBA_L_L_LB;
uint8_t ALC_M_MB;
uint8_t ALC_M_LB;
uint8_t ALC_L_MB;
uint8_t ALC_L_LB;
uint8_t ALC_M_MB;
uint8_t ALC_M_LB;
uint8_t ALC_L_MB;
uint8_t ALC_L_LB;
uint8_t Misc2;
uint8_t Control;
uint8_t Misc2;
uint8_t Control;
} __attribute__((packed));
struct InquiryResponse {
uint8_t DeviceType : 5;
uint8_t PeripheralQualifier : 3;
uint8_t DeviceType : 5;
uint8_t PeripheralQualifier : 3;
unsigned Reserved : 7;
unsigned Removable : 1;
unsigned Reserved : 7;
unsigned Removable : 1;
uint8_t Version;
uint8_t Version;
unsigned ResponseDataFormat : 4;
unsigned HISUP : 1;
unsigned NormACA : 1;
unsigned TrmTsk : 1;
unsigned AERC : 1;
unsigned ResponseDataFormat : 4;
unsigned HISUP : 1;
unsigned NormACA : 1;
unsigned TrmTsk : 1;
unsigned AERC : 1;
uint8_t AdditionalLength;
//uint8_t Reserved3[2];
uint8_t AdditionalLength;
//uint8_t Reserved3[2];
unsigned PROTECT : 1;
unsigned Res : 2;
unsigned ThreePC : 1;
unsigned TPGS : 2;
unsigned ACC : 1;
unsigned SCCS : 1;
unsigned PROTECT : 1;
unsigned Res : 2;
unsigned ThreePC : 1;
unsigned TPGS : 2;
unsigned ACC : 1;
unsigned SCCS : 1;
unsigned ADDR16 : 1;
unsigned R1 : 1;
unsigned R2 : 1;
unsigned MCHNGR : 1;
unsigned MULTIP : 1;
unsigned VS : 1;
unsigned ENCSERV : 1;
unsigned BQUE : 1;
unsigned ADDR16 : 1;
unsigned R1 : 1;
unsigned R2 : 1;
unsigned MCHNGR : 1;
unsigned MULTIP : 1;
unsigned VS : 1;
unsigned ENCSERV : 1;
unsigned BQUE : 1;
unsigned SoftReset : 1;
unsigned CmdQue : 1;
unsigned Reserved4 : 1;
unsigned Linked : 1;
unsigned Sync : 1;
unsigned WideBus16Bit : 1;
unsigned WideBus32Bit : 1;
unsigned RelAddr : 1;
unsigned SoftReset : 1;
unsigned CmdQue : 1;
unsigned Reserved4 : 1;
unsigned Linked : 1;
unsigned Sync : 1;
unsigned WideBus16Bit : 1;
unsigned WideBus32Bit : 1;
unsigned RelAddr : 1;
uint8_t VendorID[8];
uint8_t ProductID[16];
uint8_t RevisionID[4];
uint8_t VendorID[8];
uint8_t ProductID[16];
uint8_t RevisionID[4];
} __attribute__((packed));
struct CommandBlockWrapperBase {
uint32_t dCBWSignature;
uint32_t dCBWTag;
uint32_t dCBWDataTransferLength;
uint8_t bmCBWFlags;
uint32_t dCBWSignature;
uint32_t dCBWTag;
uint32_t dCBWDataTransferLength;
uint8_t bmCBWFlags;
public:
CommandBlockWrapperBase() {
}
CommandBlockWrapperBase() {
}
CommandBlockWrapperBase(uint32_t tag, uint32_t xflen, uint8_t flgs) :
dCBWSignature(MASS_CBW_SIGNATURE), dCBWTag(tag), dCBWDataTransferLength(xflen), bmCBWFlags(flgs) {
}
CommandBlockWrapperBase(uint32_t tag, uint32_t xflen, uint8_t flgs) :
dCBWSignature(MASS_CBW_SIGNATURE), dCBWTag(tag), dCBWDataTransferLength(xflen), bmCBWFlags(flgs) {
}
} __attribute__((packed));
struct CommandBlockWrapper : public CommandBlockWrapperBase {
struct {
uint8_t bmCBWLUN : 4;
uint8_t bmReserved1 : 4;
};
struct {
uint8_t bmCBWLUN : 4;
uint8_t bmReserved1 : 4;
};
struct {
uint8_t bmCBWCBLength : 4;
uint8_t bmReserved2 : 4;
};
struct {
uint8_t bmCBWCBLength : 4;
uint8_t bmReserved2 : 4;
};
uint8_t CBWCB[16];
uint8_t CBWCB[16];
public:
// All zeroed.
// All zeroed.
CommandBlockWrapper() :
CommandBlockWrapperBase(0, 0, 0), bmReserved1(0), bmReserved2(0) {
for(int i = 0; i < 16; i++) CBWCB[i] = 0;
}
CommandBlockWrapper() :
CommandBlockWrapperBase(0, 0, 0), bmReserved1(0), bmReserved2(0) {
for(int i = 0; i < 16; i++) CBWCB[i] = 0;
}
// Generic Wrap, CDB zeroed.
// Generic Wrap, CDB zeroed.
CommandBlockWrapper(uint32_t tag, uint32_t xflen, uint8_t flgs, uint8_t lu, uint8_t cmdlen, uint8_t cmd) :
CommandBlockWrapperBase(tag, xflen, flgs),
bmCBWLUN(lu), bmReserved1(0), bmCBWCBLength(cmdlen), bmReserved2(0) {
for(int i = 0; i < 16; i++) CBWCB[i] = 0;
// Type punning can cause optimization problems and bugs.
// Using reinterpret_cast to a dreinterpretifferent object is the proper way to do this.
//(((BASICCDB_t *) CBWCB)->LUN) = cmd;
BASICCDB_t *x = reinterpret_cast<BASICCDB_t *>(CBWCB);
x->LUN = cmd;
}
CommandBlockWrapper(uint32_t tag, uint32_t xflen, uint8_t flgs, uint8_t lu, uint8_t cmdlen, uint8_t cmd) :
CommandBlockWrapperBase(tag, xflen, flgs),
bmCBWLUN(lu), bmReserved1(0), bmCBWCBLength(cmdlen), bmReserved2(0) {
for(int i = 0; i < 16; i++) CBWCB[i] = 0;
// Type punning can cause optimization problems and bugs.
// Using reinterpret_cast to a dreinterpretifferent object is the proper way to do this.
//(((BASICCDB_t *) CBWCB)->LUN) = cmd;
BASICCDB_t *x = reinterpret_cast<BASICCDB_t *>(CBWCB);
x->LUN = cmd;
}
// Wrap for CDB of 6
// Wrap for CDB of 6
CommandBlockWrapper(uint32_t tag, uint32_t xflen, CDB6_t *cdb, uint8_t dir) :
CommandBlockWrapperBase(tag, xflen, dir),
bmCBWLUN(cdb->LUN), bmReserved1(0), bmCBWCBLength(6), bmReserved2(0) {
memcpy(&CBWCB, cdb, 6);
}
// Wrap for CDB of 10
CommandBlockWrapper(uint32_t tag, uint32_t xflen, CDB6_t *cdb, uint8_t dir) :
CommandBlockWrapperBase(tag, xflen, dir),
bmCBWLUN(cdb->LUN), bmReserved1(0), bmCBWCBLength(6), bmReserved2(0) {
memcpy(&CBWCB, cdb, 6);
}
// Wrap for CDB of 10
CommandBlockWrapper(uint32_t tag, uint32_t xflen, CDB10_t *cdb, uint8_t dir) :
CommandBlockWrapperBase(tag, xflen, dir),
bmCBWLUN(cdb->LUN), bmReserved1(0), bmCBWCBLength(10), bmReserved2(0) {
memcpy(&CBWCB, cdb, 10);
}
CommandBlockWrapper(uint32_t tag, uint32_t xflen, CDB10_t *cdb, uint8_t dir) :
CommandBlockWrapperBase(tag, xflen, dir),
bmCBWLUN(cdb->LUN), bmReserved1(0), bmCBWCBLength(10), bmReserved2(0) {
memcpy(&CBWCB, cdb, 10);
}
} __attribute__((packed));
struct CommandStatusWrapper {
uint32_t dCSWSignature;
uint32_t dCSWTag;
uint32_t dCSWDataResidue;
uint8_t bCSWStatus;
uint32_t dCSWSignature;
uint32_t dCSWTag;
uint32_t dCSWDataResidue;
uint8_t bCSWStatus;
} __attribute__((packed));
struct RequestSenseResponce {
uint8_t bResponseCode;
uint8_t bSegmentNumber;
uint8_t bResponseCode;
uint8_t bSegmentNumber;
uint8_t bmSenseKey : 4;
uint8_t bmReserved : 1;
uint8_t bmILI : 1;
uint8_t bmEOM : 1;
uint8_t bmFileMark : 1;
uint8_t bmSenseKey : 4;
uint8_t bmReserved : 1;
uint8_t bmILI : 1;
uint8_t bmEOM : 1;
uint8_t bmFileMark : 1;
uint8_t Information[4];
uint8_t bAdditionalLength;
uint8_t CmdSpecificInformation[4];
uint8_t bAdditionalSenseCode;
uint8_t bAdditionalSenseQualifier;
uint8_t bFieldReplaceableUnitCode;
uint8_t SenseKeySpecific[3];
uint8_t Information[4];
uint8_t bAdditionalLength;
uint8_t CmdSpecificInformation[4];
uint8_t bAdditionalSenseCode;
uint8_t bAdditionalSenseQualifier;
uint8_t bFieldReplaceableUnitCode;
uint8_t SenseKeySpecific[3];
} __attribute__((packed));
class BulkOnly : public USBDeviceConfig, public UsbConfigXtracter {
protected:
static const uint8_t epDataInIndex; // DataIn endpoint index
static const uint8_t epDataOutIndex; // DataOUT endpoint index
static const uint8_t epInterruptInIndex; // InterruptIN endpoint index
static const uint8_t epDataInIndex; // DataIn endpoint index
static const uint8_t epDataOutIndex; // DataOUT endpoint index
static const uint8_t epInterruptInIndex; // InterruptIN endpoint index
USB *pUsb;
uint8_t bAddress;
uint8_t bConfNum; // configuration number
uint8_t bIface; // interface value
uint8_t bNumEP; // total number of EP in the configuration
uint32_t qNextPollTime; // next poll time
bool bPollEnable; // poll enable flag
USB *pUsb;
uint8_t bAddress;
uint8_t bConfNum; // configuration number
uint8_t bIface; // interface value
uint8_t bNumEP; // total number of EP in the configuration
uint32_t qNextPollTime; // next poll time
bool bPollEnable; // poll enable flag
EpInfo epInfo[MASS_MAX_ENDPOINTS];
EpInfo epInfo[MASS_MAX_ENDPOINTS];
uint32_t dCBWTag; // Tag
//uint32_t dCBWDataTransferLength; // Data Transfer Length
uint8_t bLastUsbError; // Last USB error
uint8_t bMaxLUN; // Max LUN
uint8_t bTheLUN; // Active LUN
uint32_t CurrentCapacity[MASS_MAX_SUPPORTED_LUN]; // Total sectors
uint16_t CurrentSectorSize[MASS_MAX_SUPPORTED_LUN]; // Sector size, clipped to 16 bits
bool LUNOk[MASS_MAX_SUPPORTED_LUN]; // use this to check for media changes.
bool WriteOk[MASS_MAX_SUPPORTED_LUN];
void PrintEndpointDescriptor(const USB_ENDPOINT_DESCRIPTOR* ep_ptr);
uint32_t dCBWTag; // Tag
//uint32_t dCBWDataTransferLength; // Data Transfer Length
uint8_t bLastUsbError; // Last USB error
uint8_t bMaxLUN; // Max LUN
uint8_t bTheLUN; // Active LUN
uint32_t CurrentCapacity[MASS_MAX_SUPPORTED_LUN]; // Total sectors
uint16_t CurrentSectorSize[MASS_MAX_SUPPORTED_LUN]; // Sector size, clipped to 16 bits
bool LUNOk[MASS_MAX_SUPPORTED_LUN]; // use this to check for media changes.
bool WriteOk[MASS_MAX_SUPPORTED_LUN];
void PrintEndpointDescriptor(const USB_ENDPOINT_DESCRIPTOR* ep_ptr);
// Additional Initialization Method for Subclasses
// Additional Initialization Method for Subclasses
virtual uint8_t OnInit() {
return 0;
};
virtual uint8_t OnInit() {
return 0;
};
public:
BulkOnly(USB *p);
BulkOnly(USB *p);
uint8_t GetLastUsbError() {
return bLastUsbError;
};
uint8_t GetLastUsbError() {
return bLastUsbError;
};
uint8_t GetbMaxLUN() {
return bMaxLUN; // Max LUN
}
uint8_t GetbMaxLUN() {
return bMaxLUN; // Max LUN
}
uint8_t GetbTheLUN() {
return bTheLUN; // Active LUN
}
uint8_t GetbTheLUN() {
return bTheLUN; // Active LUN
}
bool WriteProtected(uint8_t lun);
uint8_t MediaCTL(uint8_t lun, uint8_t ctl);
uint8_t Read(uint8_t lun, uint32_t addr, uint16_t bsize, uint8_t blocks, uint8_t *buf);
uint8_t Read(uint8_t lun, uint32_t addr, uint16_t bsize, uint8_t blocks, USBReadParser *prs);
uint8_t Write(uint8_t lun, uint32_t addr, uint16_t bsize, uint8_t blocks, const uint8_t *buf);
uint8_t LockMedia(uint8_t lun, uint8_t lock);
bool WriteProtected(uint8_t lun);
uint8_t MediaCTL(uint8_t lun, uint8_t ctl);
uint8_t Read(uint8_t lun, uint32_t addr, uint16_t bsize, uint8_t blocks, uint8_t *buf);
uint8_t Read(uint8_t lun, uint32_t addr, uint16_t bsize, uint8_t blocks, USBReadParser *prs);
uint8_t Write(uint8_t lun, uint32_t addr, uint16_t bsize, uint8_t blocks, const uint8_t *buf);
uint8_t LockMedia(uint8_t lun, uint8_t lock);
bool LUNIsGood(uint8_t lun);
uint32_t GetCapacity(uint8_t lun);
uint16_t GetSectorSize(uint8_t lun);
bool LUNIsGood(uint8_t lun);
uint32_t GetCapacity(uint8_t lun);
uint16_t GetSectorSize(uint8_t lun);
// USBDeviceConfig implementation
uint8_t Init(uint8_t parent, uint8_t port, bool lowspeed);
uint8_t ConfigureDevice(uint8_t parent, uint8_t port, bool lowspeed);
// USBDeviceConfig implementation
uint8_t Init(uint8_t parent, uint8_t port, bool lowspeed);
uint8_t ConfigureDevice(uint8_t parent, uint8_t port, bool lowspeed);
uint8_t Release();
uint8_t Poll();
uint8_t Release();
uint8_t Poll();
virtual uint8_t GetAddress() {
return bAddress;
};
virtual uint8_t GetAddress() {
return bAddress;
};
// UsbConfigXtracter implementation
void EndpointXtract(uint8_t conf, uint8_t iface, uint8_t alt, uint8_t proto, const USB_ENDPOINT_DESCRIPTOR *ep);
// UsbConfigXtracter implementation
void EndpointXtract(uint8_t conf, uint8_t iface, uint8_t alt, uint8_t proto, const USB_ENDPOINT_DESCRIPTOR *ep);
virtual bool DEVCLASSOK(uint8_t klass) {
return (klass == USB_CLASS_MASS_STORAGE);
}
virtual bool DEVCLASSOK(uint8_t klass) {
return (klass == USB_CLASS_MASS_STORAGE);
}
uint8_t SCSITransaction6(CDB6_t *cdb, uint16_t buf_size, void *buf, uint8_t dir);
uint8_t SCSITransaction10(CDB10_t *cdb, uint16_t buf_size, void *buf, uint8_t dir);
uint8_t SCSITransaction6(CDB6_t *cdb, uint16_t buf_size, void *buf, uint8_t dir);
uint8_t SCSITransaction10(CDB10_t *cdb, uint16_t buf_size, void *buf, uint8_t dir);
private:
uint8_t Inquiry(uint8_t lun, uint16_t size, uint8_t *buf);
uint8_t TestUnitReady(uint8_t lun);
uint8_t RequestSense(uint8_t lun, uint16_t size, uint8_t *buf);
uint8_t ModeSense6(uint8_t lun, uint8_t pc, uint8_t page, uint8_t subpage, uint8_t len, uint8_t *buf);
uint8_t GetMaxLUN(uint8_t *max_lun);
uint8_t SetCurLUN(uint8_t lun);
void Reset();
uint8_t ResetRecovery();
uint8_t ReadCapacity10(uint8_t lun, uint8_t *buf);
void ClearAllEP();
void CheckMedia();
bool CheckLUN(uint8_t lun);
uint8_t Page3F(uint8_t lun);
bool IsValidCBW(uint8_t size, uint8_t *pcbw);
bool IsMeaningfulCBW(uint8_t size, uint8_t *pcbw);
uint8_t Inquiry(uint8_t lun, uint16_t size, uint8_t *buf);
uint8_t TestUnitReady(uint8_t lun);
uint8_t RequestSense(uint8_t lun, uint16_t size, uint8_t *buf);
uint8_t ModeSense6(uint8_t lun, uint8_t pc, uint8_t page, uint8_t subpage, uint8_t len, uint8_t *buf);
uint8_t GetMaxLUN(uint8_t *max_lun);
uint8_t SetCurLUN(uint8_t lun);
void Reset();
uint8_t ResetRecovery();
uint8_t ReadCapacity10(uint8_t lun, uint8_t *buf);
void ClearAllEP();
void CheckMedia();
bool CheckLUN(uint8_t lun);
uint8_t Page3F(uint8_t lun);
bool IsValidCBW(uint8_t size, uint8_t *pcbw);
bool IsMeaningfulCBW(uint8_t size, uint8_t *pcbw);
bool IsValidCSW(CommandStatusWrapper *pcsw, CommandBlockWrapperBase *pcbw);
bool IsValidCSW(CommandStatusWrapper *pcsw, CommandBlockWrapperBase *pcbw);
uint8_t ClearEpHalt(uint8_t index);
#if MS_WANT_PARSER
uint8_t Transaction(CommandBlockWrapper *cbw, uint16_t bsize, void *buf, uint8_t flags);
#endif
uint8_t Transaction(CommandBlockWrapper *cbw, uint16_t bsize, void *buf);
uint8_t HandleUsbError(uint8_t error, uint8_t index);
uint8_t HandleSCSIError(uint8_t status);
uint8_t ClearEpHalt(uint8_t index);
#if MS_WANT_PARSER
uint8_t Transaction(CommandBlockWrapper *cbw, uint16_t bsize, void *buf, uint8_t flags);
#endif
uint8_t Transaction(CommandBlockWrapper *cbw, uint16_t bsize, void *buf);
uint8_t HandleUsbError(uint8_t error, uint8_t index);
uint8_t HandleSCSIError(uint8_t status);
};
#endif // __MASSTORAGE_H__

View file

@ -22,8 +22,7 @@ Web : http://www.circuitsathome.com
e-mail : support@circuitsathome.com
*/
#ifndef USB_HOST_SHIELD_SETTINGS_H
#define USB_HOST_SHIELD_SETTINGS_H
#pragma once
#include "../../../inc/MarlinConfig.h"
@ -232,5 +231,3 @@ e-mail : support@circuitsathome.com
#ifdef ARDUINO_ESP8266_WIFIO
#error "This board is currently not supported"
#endif
#endif /* SETTINGS_H */

View file

@ -19,8 +19,7 @@
* location: <http://www.gnu.org/licenses/>. *
****************************************************************************/
#ifndef _USB_HOST_H_
#define _USB_HOST_H_
#pragma once
/* This the following comes from "lib/usbhost.h", but has been rewritten
* to use the SPI functions from Marlin's HAL */
@ -57,5 +56,3 @@ class MAX3421e {
#if defined(__SAM3X8E__) && !defined(ARDUINO_SAM_DUE)
#define ARDUINO_SAM_DUE // Spoof the USB library that this is a DUE
#endif
#endif // _USB_HOST_H_

View file

@ -1,6 +1,5 @@
#ifndef MYGETLINE_H
#define MYGETLINE_H 1
#define MYGETLINE_H
//#include "config.h"