Use Arduino.h include wrapper (#13877)

This commit is contained in:
Scott Lahteine 2019-05-02 00:45:50 -05:00 committed by GitHub
parent 51d1e0f1dd
commit e7682eea42
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
32 changed files with 155 additions and 118 deletions

View File

@ -24,14 +24,7 @@
#include <stdint.h>
#include <Arduino.h>
#include <util/delay.h>
#include <avr/eeprom.h>
#include <avr/pgmspace.h>
#include <avr/interrupt.h>
#include <avr/io.h>
#include "../shared/Marduino.h"
#include "../shared/HAL_SPI.h"
#include "fastio_AVR.h"
#include "watchdog_AVR.h"
@ -43,6 +36,12 @@
#include "MarlinSerial.h"
#endif
#include <util/delay.h>
#include <avr/eeprom.h>
#include <avr/pgmspace.h>
#include <avr/interrupt.h>
#include <avr/io.h>
// --------------------------------------------------------------------------
// Defines
// --------------------------------------------------------------------------

View File

@ -30,7 +30,7 @@
#ifdef FASTIO_EXT_START
#include <Arduino.h>
#include "../shared/Marduino.h"
#define _IS_EXT(P) WITHIN(P, FASTIO_EXT_START, FASTIO_EXT_END)

View File

@ -58,8 +58,8 @@
#if HAS_SERVOS
#include <avr/interrupt.h>
#include <Arduino.h>
#include "../shared/Marduino.h"
#include "../shared/servo.h"
#include "../shared/servo_private.h"

View File

@ -36,7 +36,7 @@
#if ENABLED(EEPROM_SETTINGS) && DISABLED(I2C_EEPROM, SPI_EEPROM)
#include <Arduino.h>
#include "../shared/Marduino.h"
#define EEPROMSize 4096
#define PagesPerGroup 128

View File

@ -29,16 +29,15 @@
#define CPU_32_BIT
#include <stdint.h>
#include <Arduino.h>
#include "../shared/Marduino.h"
#include "../shared/math_32bit.h"
#include "../shared/HAL_SPI.h"
#include "fastio_Due.h"
#include "watchdog_Due.h"
#include "HAL_timers_Due.h"
#include <stdint.h>
// Serial ports
#if !WITHIN(SERIAL_PORT, -1, 3)
#error "SERIAL_PORT must be from -1 to 3"

View File

@ -44,7 +44,7 @@
#if HAS_SERVOS
#include <Arduino.h>
#include "../shared/Marduino.h"
#include "../shared/servo.h"
#include "../shared/servo_private.h"

View File

@ -28,7 +28,7 @@
* Translation of routines & variables used by pinsDebug.h
*/
#include <Arduino.h>
#include "../shared/Marduino.h"
/**
* Due/Marlin quirks

View File

@ -66,20 +66,20 @@
#include "../../Marlin.h"
#define SPI_FULL_SPEED 0
#define SPI_HALF_SPEED 1
#define SPI_QUARTER_SPEED 2
#define SPI_EIGHTH_SPEED 3
#define SPI_FULL_SPEED 0
#define SPI_HALF_SPEED 1
#define SPI_QUARTER_SPEED 2
#define SPI_EIGHTH_SPEED 3
#define SPI_SIXTEENTH_SPEED 4
#define SPI_SPEED_5 5
#define SPI_SPEED_6 6
#define SPI_SPEED_5 5
#define SPI_SPEED_6 6
void spiBegin();
void spiInit(uint8_t spiRate);
void spiSend(uint8_t b);
void spiSend(const uint8_t* buf, size_t n);
#include <Arduino.h>
#include "../shared/Marduino.h"
#include "fastio_Due.h"
void u8g_SetPIOutput_DUE_hw_spi(u8g_t *u8g, uint8_t pin_index) {

View File

@ -59,10 +59,11 @@
#if HAS_GRAPHICAL_LCD
#include <U8glib.h>
#include <Arduino.h>
#include "../shared/Marduino.h"
#include "../shared/Delay.h"
#include <U8glib.h>
void u8g_SetPIOutput_DUE(u8g_t *u8g, uint8_t pin_index) {
PIO_Configure(g_APinDescription[u8g->pin_list[pin_index]].pPort, PIO_OUTPUT_1,
g_APinDescription[u8g->pin_list[pin_index]].ulPin, g_APinDescription[u8g->pin_list[pin_index]].ulPinConfiguration); // OUTPUT

View File

@ -30,19 +30,7 @@
#include <stdint.h>
// these are going to be re-defined in Arduino.h
#undef DISABLED
#undef M_PI
#undef _BV
#include <Arduino.h>
// revert back to the correct (old) definition
#undef DISABLED
#define DISABLED(V...) DO(DIS,&&,V)
// re-define in case Arduino.h has been skipped due to earlier inclusion (i.e. in Marlin\src\HAL\HAL_ESP32\i2s.cpp)
#define _BV(b) (1UL << (b))
#include "../shared/Marduino.h"
#include "../shared/math_32bit.h"
#include "../shared/HAL_SPI.h"

View File

@ -21,13 +21,9 @@
*/
#ifdef ARDUINO_ARCH_ESP32
// replace that with the proper imports, then cleanup workarounds in Marlin\src\HAL\HAL_ESP32\HAL.h
#include <Arduino.h>
// revert back to the correct definition
#undef DISABLED
#define DISABLED(V...) DO(DIS,&&,V)
#include "i2s.h"
#include "../shared/Marduino.h"
#include "../../core/macros.h"
#include "driver/periph_ctrl.h"
#include "rom/lldesc.h"

View File

@ -21,6 +21,8 @@
*/
#pragma once
#include <stdint.h>
// current value of the outputs provided over i2s
extern uint32_t i2s_port_data;

View File

@ -47,16 +47,15 @@ uint8_t _getc();
//arduino: Print.h
#define DEC 10
#define HEX 16
#define OCT 8
#define BIN 2
#define OCT 8
#define BIN 2
//arduino: binary.h (weird defines)
#define B01 1
#define B10 2
#include "hardware/Clock.h"
#include <Arduino.h>
#include "../shared/Marduino.h"
#include "../shared/math_32bit.h"
#include "../shared/HAL_SPI.h"
#include "fastio.h"

View File

@ -25,7 +25,7 @@
* Fast I/O Routines for X86_64
*/
#include <Arduino.h>
#include "../shared/Marduino.h"
#include <pinmapping.h>
#define SET_DIR_INPUT(IO) Gpio::setDir(IO, 1)

View File

@ -37,18 +37,18 @@ void HAL_init();
extern "C" volatile millis_t _millis;
#include <Arduino.h>
#include <pinmapping.h>
#include <CDCSerial.h>
#include "../shared/Marduino.h"
#include "../shared/math_32bit.h"
#include "../shared/HAL_SPI.h"
#include "fastio.h"
#include <adc.h>
#include "watchdog.h"
#include "HAL_timers.h"
#include "MarlinSerial.h"
#include <adc.h>
#include <pinmapping.h>
#include <CDCSerial.h>
//
// Default graphical display delays
//

View File

@ -33,7 +33,7 @@
* For TARGET LPC1768
*/
#include <Arduino.h>
#include "../shared/Marduino.h"
#define PWM_PIN(P) true // all pins are PWM capable
#define USEABLE_HARDWARE_PWM(P) PWM_PIN(P)

View File

@ -59,17 +59,17 @@
#if HAS_GRAPHICAL_LCD
#include <U8glib.h>
#include "SoftwareSPI.h"
#undef SPI_SPEED
#define SPI_SPEED 2 // About 2 MHz
#include <Arduino.h>
#include <algorithm>
#include <LPC17xx.h>
#include <gpio.h>
#include <Arduino.h>
#include <U8glib.h>
uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, const pin_t sck_pin, const pin_t miso_pin, const pin_t mosi_pin ) {

View File

@ -28,20 +28,20 @@
// Includes
// --------------------------------------------------------------------------
#include <stdint.h>
#include "Arduino.h"
#ifdef USBCON
#include <USBSerial.h>
#endif
#include "../../inc/MarlinConfigPre.h"
#include "../shared/Marduino.h"
#include "../shared/math_32bit.h"
#include "../shared/HAL_SPI.h"
#include "fastio_STM32.h"
#include "watchdog_STM32.h"
#include "../../inc/MarlinConfigPre.h"
#include <stdint.h>
#ifdef USBCON
#include <USBSerial.h>
#endif
// --------------------------------------------------------------------------
// Defines
// --------------------------------------------------------------------------

View File

@ -36,14 +36,7 @@
// Includes
// --------------------------------------------------------------------------
#include <stdint.h>
#include <util/atomic.h>
#include <Arduino.h>
// --------------------------------------------------------------------------
// Includes
// --------------------------------------------------------------------------
#include "../shared/Marduino.h"
#include "../shared/math_32bit.h"
#include "../shared/HAL_SPI.h"
@ -51,6 +44,10 @@
#include "watchdog_STM32F1.h"
#include "HAL_timers_STM32F1.h"
#include <stdint.h>
#include <util/atomic.h>
#include "../../inc/MarlinConfigPre.h"
// --------------------------------------------------------------------------

View File

@ -25,7 +25,8 @@
// Includes
// --------------------------------------------------------------------------
#include "Arduino.h"
#include "../shared/Marduino.h"
#include "libmaple/sdio.h"
#include "libmaple/dma.h"

View File

@ -32,21 +32,21 @@
// Includes
// --------------------------------------------------------------------------
#include <stdint.h>
#include "Arduino.h"
#ifdef USBCON
#include <USBSerial.h>
#endif
#include "../shared/Marduino.h"
#include "../shared/math_32bit.h"
#include "../shared/HAL_SPI.h"
#include "fastio_STM32F4.h"
#include "watchdog_STM32F4.h"
#include "HAL_timers_STM32F4.h"
#include "../../inc/MarlinConfigPre.h"
#include <stdint.h>
#ifdef USBCON
#include <USBSerial.h>
#endif
// --------------------------------------------------------------------------
// Defines
// --------------------------------------------------------------------------

View File

@ -34,8 +34,7 @@
#include <stdint.h>
#include "Arduino.h"
#include "../shared/Marduino.h"
#include "../shared/math_32bit.h"
#include "../shared/HAL_SPI.h"
@ -44,6 +43,7 @@
#include "HAL_timers_STM32F7.h"
#include "../../inc/MarlinConfigPre.h"
// --------------------------------------------------------------------------
// Defines

View File

@ -28,14 +28,7 @@
#define CPU_32_BIT
// _BV is re-defined in Arduino.h
#undef _BV
#include <Arduino.h>
// Redefine sq macro defined by teensy3/wiring.h
#undef sq
#define sq(x) ((x)*(x))
#include "../shared/Marduino.h"
#include "../math_32bit.h"
#include "../HAL_SPI.h"

View File

@ -31,15 +31,7 @@
// Includes
// --------------------------------------------------------------------------
// _BV is re-defined in Arduino.h
#undef _BV
#include <Arduino.h>
// Redefine sq macro defined by teensy3/wiring.h
#undef sq
#define sq(x) ((x)*(x))
#include "../shared/Marduino.h"
#include "../shared/math_32bit.h"
#include "../shared/HAL_SPI.h"

View File

@ -33,4 +33,4 @@
void ST7920_set_cmd();
void ST7920_set_dat();
void ST7920_write_byte(const uint8_t data);
#endif
#endif

View File

@ -0,0 +1,50 @@
/**
* Marlin 3D Printer Firmware
* Copyright (C) 2019 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
/**
* HAL/shared/Marduino.h
*/
#undef DISABLED // Redefined by ESP32
#undef M_PI // Redefined by all
#undef _BV // Redefined by some
#undef sq // Redefined by teensy3/wiring.h
#include <Arduino.h> // NOTE: If included earlier then this line is a NOOP
#undef DISABLED
#define DISABLED(V...) DO(DIS,&&,V)
#undef _BV
#define _BV(b) (1UL << (b))
#undef sq
#define sq(x) ((x)*(x))
#ifndef SBI
#define SBI(A,B) (A |= (1 << (B)))
#endif
#ifndef CBI
#define CBI(A,B) (A &= ~(1 << (B)))
#endif

View File

@ -55,7 +55,6 @@
#if HAS_SERVOS && !(IS_32BIT_TEENSY || defined(TARGET_LPC1768) || defined(STM32F1) || defined(STM32F1xx) || defined(STM32F4) || defined(STM32F4xx) || defined(STM32F7xx))
//#include <Arduino.h>
#include "servo.h"
#include "servo_private.h"

View File

@ -8,9 +8,10 @@
*/
#pragma once
#include <stdlib.h>
#include <Arduino.h>
#include "../HAL/shared/Marduino.h"
#include "../core/macros.h"
#include <stdlib.h>
#include <stddef.h> // wchar_t
#include <stdint.h> // uint32_t

View File

@ -746,6 +746,7 @@ void MarlinUI::update() {
refresh();
init_lcd(); // May revive the LCD if static electricity killed it
ms = millis();
next_lcd_update_ms = ms + LCD_UPDATE_INTERVAL; // delay LCD update until after SD activity completes
}

View File

@ -21,7 +21,7 @@
*/
#pragma once
#include <Arduino.h>
#include "../HAL/shared/Marduino.h"
struct duration_t {
/**

View File

@ -1,17 +1,36 @@
// https://github.com/niteris/ArduinoSoftSpi
/**
* Marlin 3D Printer Firmware
* Copyright (C) 2019 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 <Arduino.h>
//
// Based on https://github.com/niteris/ArduinoSoftSpi
//
#include "../HAL/shared/Marduino.h"
#ifndef FORCE_INLINE
#define FORCE_INLINE inline __attribute__((always_inline))
#endif
#ifndef _BV
#define _BV(B) (1 << (B))
#define SBI(A,B) (A |= (1 << (B)))
#define CBI(A,B) (A &= ~(1 << (B)))
#endif
#define nop __asm__ volatile ("nop") // NOP for timing
#ifdef __arm__

View File

@ -271,7 +271,7 @@
// Check if all pins are defined in mega/pins_arduino.h
#include <Arduino.h>
//#include <Arduino.h>
static_assert(NUM_DIGITAL_PINS > MAX_PIN, "add missing pins to [arduino dir]/hardware/arduino/avr/variants/mega/pins_arduino.h based on fastio.h"
"to digital_pin_to_port_PGM, digital_pin_to_bit_mask_PGM, digital_pin_to_timer_PGM, NUM_DIGITAL_PINS, see below");