Browse Source

HAL for Linux (#13146)

pull/1/head
Scott Lahteine 5 years ago
committed by GitHub
parent
commit
15aa932aa6
No known key found for this signature in database GPG Key ID: 4AEE18F83AFDEB23
  1. 11
      .travis.yml
  2. 82
      Marlin/src/HAL/HAL_LINUX/HAL.cpp
  3. 109
      Marlin/src/HAL/HAL_LINUX/HAL.h
  4. 73
      Marlin/src/HAL/HAL_LINUX/HAL_timers.cpp
  5. 91
      Marlin/src/HAL/HAL_LINUX/HAL_timers.h
  6. 67
      Marlin/src/HAL/HAL_LINUX/SanityCheck.h
  7. 116
      Marlin/src/HAL/HAL_LINUX/arduino.cpp
  8. 123
      Marlin/src/HAL/HAL_LINUX/fastio.h
  9. 32
      Marlin/src/HAL/HAL_LINUX/hardware/Clock.cpp
  10. 89
      Marlin/src/HAL/HAL_LINUX/hardware/Clock.h
  11. 30
      Marlin/src/HAL/HAL_LINUX/hardware/Gpio.cpp
  12. 141
      Marlin/src/HAL/HAL_LINUX/hardware/Gpio.h
  13. 61
      Marlin/src/HAL/HAL_LINUX/hardware/Heater.cpp
  14. 47
      Marlin/src/HAL/HAL_LINUX/hardware/Heater.h
  15. 50
      Marlin/src/HAL/HAL_LINUX/hardware/IOLoggerCSV.cpp
  16. 40
      Marlin/src/HAL/HAL_LINUX/hardware/IOLoggerCSV.h
  17. 66
      Marlin/src/HAL/HAL_LINUX/hardware/LinearAxis.cpp
  18. 45
      Marlin/src/HAL/HAL_LINUX/hardware/LinearAxis.h
  19. 118
      Marlin/src/HAL/HAL_LINUX/hardware/Timer.cpp
  20. 76
      Marlin/src/HAL/HAL_LINUX/hardware/Timer.h
  21. 125
      Marlin/src/HAL/HAL_LINUX/include/Arduino.h
  22. 70
      Marlin/src/HAL/HAL_LINUX/include/pinmapping.cpp
  23. 59
      Marlin/src/HAL/HAL_LINUX/include/pinmapping.h
  24. 207
      Marlin/src/HAL/HAL_LINUX/include/serial.h
  25. 137
      Marlin/src/HAL/HAL_LINUX/main.cpp
  26. 101
      Marlin/src/HAL/HAL_LINUX/persistent_store_impl.cpp
  27. 63
      Marlin/src/HAL/HAL_LINUX/pinsDebug.h
  28. 80
      Marlin/src/HAL/HAL_LINUX/servo_private.h
  29. 53
      Marlin/src/HAL/HAL_LINUX/spi_pins.h
  30. 46
      Marlin/src/HAL/HAL_LINUX/watchdog.cpp
  31. 34
      Marlin/src/HAL/HAL_LINUX/watchdog.h
  32. 2
      Marlin/src/HAL/platforms.h
  33. 4
      Marlin/src/HAL/shared/Delay.h
  34. 6
      Marlin/src/core/boards.h
  35. 7
      Marlin/src/pins/pins.h
  36. 572
      Marlin/src/pins/pins_RAMPS_LINUX.h
  37. 0
      buildroot/share/tests/DUE-tests
  38. 0
      buildroot/share/tests/LPC1768-tests
  39. 0
      buildroot/share/tests/LPC1769-tests
  40. 0
      buildroot/share/tests/STM32F1-tests
  41. 16
      buildroot/share/tests/linux_native-tests
  42. 0
      buildroot/share/tests/megaatmega2560-tests
  43. 4
      buildroot/share/tests/run_tests
  44. 0
      buildroot/share/tests/teensy35-tests
  45. 14
      platformio.ini

11
.travis.yml

@ -1,5 +1,5 @@
dist: trusty
sudo: false
sudo: require
language: python
python:
@ -22,8 +22,17 @@ env:
- TEST_PLATFORM="LPC1769"
- TEST_PLATFORM="STM32F1"
- TEST_PLATFORM="teensy35"
- TEST_PLATFORM="linux_native"
addons:
apt:
sources:
- ubuntu-toolchain-r-test
packages:
- g++-7
before_install:
- sudo update-alternatives --install /usr/bin/g++ g++ /usr/bin/g++-7 90
#
# Fetch the tag information for the current branch
- git fetch origin --tags

82
Marlin/src/HAL/HAL_LINUX/HAL.cpp

@ -0,0 +1,82 @@
/**
* 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/>.
*
*/
#ifdef __PLAT_LINUX__
#include "../../inc/MarlinConfig.h"
#include "../shared/Delay.h"
HalSerial usb_serial;
// U8glib required functions
extern "C" void u8g_xMicroDelay(uint16_t val) {
DELAY_US(val);
}
extern "C" void u8g_MicroDelay(void) {
u8g_xMicroDelay(1);
}
extern "C" void u8g_10MicroDelay(void) {
u8g_xMicroDelay(10);
}
extern "C" void u8g_Delay(uint16_t val) {
delay(val);
}
//************************//
// return free heap space
int freeMemory() {
return 0;
}
// --------------------------------------------------------------------------
// ADC
// --------------------------------------------------------------------------
void HAL_adc_init(void) {
}
void HAL_adc_enable_channel(int ch) {
}
uint8_t active_ch = 0;
void HAL_adc_start_conversion(const uint8_t ch) {
active_ch = ch;
}
bool HAL_adc_finished(void) {
return true;
}
uint16_t HAL_adc_get_result(void) {
pin_t pin = analogInputToDigitalPin(active_ch);
if (!VALID_PIN(pin)) return 0;
uint16_t data = ((Gpio::get(pin) >> 2) & 0x3FF);
return data; // return 10bit value as Marlin expects
}
void HAL_pwm_init(void) {
}
#endif // __PLAT_LINUX__

109
Marlin/src/HAL/HAL_LINUX/HAL.h

@ -0,0 +1,109 @@
/**
* Marlin 3D Printer Firmware
*
* Copyright (C) 2019 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
#define CPU_32_BIT
// --------------------------------------------------------------------------
// Includes
// --------------------------------------------------------------------------
#define F_CPU 100000000
#define SystemCoreClock F_CPU
#include <iostream>
#include <stdint.h>
#include <stdarg.h>
#undef min
#undef max
#include <algorithm>
void _printf (const char *format, ...);
void _putc(uint8_t c);
uint8_t _getc();
//extern "C" volatile uint32_t _millis;
//arduino: Print.h
#define DEC 10
#define HEX 16
#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/math_32bit.h"
#include "../shared/HAL_SPI.h"
#include "fastio.h"
#include "watchdog.h"
#include "HAL_timers.h"
#include "serial.h"
extern HalSerial usb_serial;
#define MYSERIAL0 usb_serial
#define NUM_SERIAL 1
#define ST7920_DELAY_1 DELAY_NS(600)
#define ST7920_DELAY_2 DELAY_NS(750)
#define ST7920_DELAY_3 DELAY_NS(750)
//
// Interrupts
//
#define CRITICAL_SECTION_START
#define CRITICAL_SECTION_END
#define ISRS_ENABLED()
#define ENABLE_ISRS()
#define DISABLE_ISRS()
//Utility functions
int freeMemory(void);
// SPI: Extended functions which take a channel number (hardware SPI only)
/** Write single byte to specified SPI channel */
void spiSend(uint32_t chan, byte b);
/** Write buffer to specified SPI channel */
void spiSend(uint32_t chan, const uint8_t* buf, size_t n);
/** Read single byte from specified SPI channel */
uint8_t spiRec(uint32_t chan);
// ADC
#define HAL_ANALOG_SELECT(pin) HAL_adc_enable_channel(pin)
#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
#define HAL_READ_ADC() HAL_adc_get_result()
#define HAL_ADC_READY() true
void HAL_adc_init(void);
void HAL_adc_enable_channel(int pin);
void HAL_adc_start_conversion(const uint8_t adc_pin);
uint16_t HAL_adc_get_result(void);
/* ---------------- Delay in cycles */
FORCE_INLINE static void DELAY_CYCLES(uint64_t x) {
Clock::delayCycles(x);
}

73
Marlin/src/HAL/HAL_LINUX/HAL_timers.cpp

@ -0,0 +1,73 @@
/**
* Marlin 3D Printer Firmware
*
* Copyright (C) 2019 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/>.
*
*/
#ifdef __PLAT_LINUX__
#include "hardware/Timer.h"
#include "../../inc/MarlinConfig.h"
#include "HAL_timers.h"
/**
* Use POSIX signals to attempt to emulate Interrupts
* This has many limitations and is not fit for the purpose
*/
HAL_STEP_TIMER_ISR;
HAL_TEMP_TIMER_ISR;
Timer timers[2];
void HAL_timer_init(void) {
timers[0].init(0, STEPPER_TIMER_RATE, TIMER0_IRQHandler);
timers[1].init(1, TEMP_TIMER_RATE, TIMER1_IRQHandler);
}
void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
timers[timer_num].start(frequency);
}
void HAL_timer_enable_interrupt(const uint8_t timer_num) {
timers[timer_num].enable();
}
void HAL_timer_disable_interrupt(const uint8_t timer_num) {
timers[timer_num].disable();
}
bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
return timers[timer_num].enabled();
}
void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) {
timers[timer_num].setCompare(compare);
}
hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) {
return timers[timer_num].getCompare();
}
hal_timer_t HAL_timer_get_count(const uint8_t timer_num) {
return timers[timer_num].getCount();
}
#endif // __PLAT_LINUX__

91
Marlin/src/HAL/HAL_LINUX/HAL_timers.h

@ -0,0 +1,91 @@
/**
* Marlin 3D Printer Firmware
*
* Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.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
/**
* HAL timers for Linux X86_64
*/
// --------------------------------------------------------------------------
// Includes
// --------------------------------------------------------------------------
#include <stdint.h>
// --------------------------------------------------------------------------
// Defines
// --------------------------------------------------------------------------
#define FORCE_INLINE __attribute__((always_inline)) inline
typedef uint32_t hal_timer_t;
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFF
#define HAL_TIMER_RATE ((SystemCoreClock) / 4) // frequency of timers peripherals
#define STEP_TIMER_NUM 0 // Timer Index for Stepper
#define TEMP_TIMER_NUM 1 // Timer Index for Temperature
#define PULSE_TIMER_NUM STEP_TIMER_NUM
#define TEMP_TIMER_RATE 1000000
#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency
#define STEPPER_TIMER_RATE HAL_TIMER_RATE // frequency of stepper timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE)
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs
#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US)
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM)
#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(STEP_TIMER_NUM)
#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM)
#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM)
#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM)
#define HAL_STEP_TIMER_ISR extern "C" void TIMER0_IRQHandler(void)
#define HAL_TEMP_TIMER_ISR extern "C" void TIMER1_IRQHandler(void)
// PWM timer
#define HAL_PWM_TIMER
#define HAL_PWM_TIMER_ISR extern "C" void TIMER3_IRQHandler(void)
#define HAL_PWM_TIMER_IRQn
void HAL_timer_init(void);
void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency);
void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare);
hal_timer_t HAL_timer_get_compare(const uint8_t timer_num);
hal_timer_t HAL_timer_get_count(const uint8_t timer_num);
FORCE_INLINE static void HAL_timer_restrain(const uint8_t timer_num, const uint16_t interval_ticks) {
const hal_timer_t mincmp = HAL_timer_get_count(timer_num) + interval_ticks;
if (HAL_timer_get_compare(timer_num) < mincmp) HAL_timer_set_compare(timer_num, mincmp);
}
void HAL_timer_enable_interrupt(const uint8_t timer_num);
void HAL_timer_disable_interrupt(const uint8_t timer_num);
bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
#define HAL_timer_isr_prologue(TIMER_NUM)
#define HAL_timer_isr_epilogue(TIMER_NUM)

67
Marlin/src/HAL/HAL_LINUX/SanityCheck.h

@ -0,0 +1,67 @@
/**
* 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/>.
*
*/
/**
* Test X86_64 configuration values for errors at compile-time.
*/
#if ENABLED(SPINDLE_LASER_ENABLE)
#if !PIN_EXISTS(SPINDLE_LASER_ENABLE)
#error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENABLE_PIN."
#elif SPINDLE_DIR_CHANGE && !PIN_EXISTS(SPINDLE_DIR)
#error "SPINDLE_DIR_PIN not defined."
#elif ENABLED(SPINDLE_LASER_PWM) && PIN_EXISTS(SPINDLE_LASER_PWM)
#if !PWM_PIN(SPINDLE_LASER_PWM_PIN)
#error "SPINDLE_LASER_PWM_PIN not assigned to a PWM pin."
#elif !(SPINDLE_LASER_PWM_PIN == 4 || SPINDLE_LASER_PWM_PIN == 6 || SPINDLE_LASER_PWM_PIN == 11)
#error "SPINDLE_LASER_PWM_PIN must use SERVO0, SERVO1 or SERVO3 connector"
#elif SPINDLE_LASER_POWERUP_DELAY < 1
#error "SPINDLE_LASER_POWERUP_DELAY must be greater than 0."
#elif SPINDLE_LASER_POWERDOWN_DELAY < 1
#error "SPINDLE_LASER_POWERDOWN_DELAY must be greater than 0."
#elif !defined(SPINDLE_LASER_PWM_INVERT)
#error "SPINDLE_LASER_PWM_INVERT missing."
#elif !defined(SPEED_POWER_SLOPE) || !defined(SPEED_POWER_INTERCEPT) || !defined(SPEED_POWER_MIN) || !defined(SPEED_POWER_MAX)
#error "SPINDLE_LASER_PWM equation constant(s) missing."
#elif PIN_EXISTS(CASE_LIGHT) && SPINDLE_LASER_PWM_PIN == CASE_LIGHT_PIN
#error "SPINDLE_LASER_PWM_PIN is used by CASE_LIGHT_PIN."
#elif PIN_EXISTS(E0_AUTO_FAN) && SPINDLE_LASER_PWM_PIN == E0_AUTO_FAN_PIN
#error "SPINDLE_LASER_PWM_PIN is used by E0_AUTO_FAN_PIN."
#elif PIN_EXISTS(E1_AUTO_FAN) && SPINDLE_LASER_PWM_PIN == E1_AUTO_FAN_PIN
#error "SPINDLE_LASER_PWM_PIN is used by E1_AUTO_FAN_PIN."
#elif PIN_EXISTS(E2_AUTO_FAN) && SPINDLE_LASER_PWM_PIN == E2_AUTO_FAN_PIN
#error "SPINDLE_LASER_PWM_PIN is used by E2_AUTO_FAN_PIN."
#elif PIN_EXISTS(E3_AUTO_FAN) && SPINDLE_LASER_PWM_PIN == E3_AUTO_FAN_PIN
#error "SPINDLE_LASER_PWM_PIN is used by E3_AUTO_FAN_PIN."
#elif PIN_EXISTS(E4_AUTO_FAN) && SPINDLE_LASER_PWM_PIN == E4_AUTO_FAN_PIN
#error "SPINDLE_LASER_PWM_PIN is used by E4_AUTO_FAN_PIN."
#elif PIN_EXISTS(FAN) && SPINDLE_LASER_PWM_PIN == FAN_PIN
#error "SPINDLE_LASER_PWM_PIN is used FAN_PIN."
#elif PIN_EXISTS(FAN1) && SPINDLE_LASER_PWM_PIN == FAN1_PIN
#error "SPINDLE_LASER_PWM_PIN is used FAN1_PIN."
#elif PIN_EXISTS(FAN2) && SPINDLE_LASER_PWM_PIN == FAN2_PIN
#error "SPINDLE_LASER_PWM_PIN is used FAN2_PIN."
#elif PIN_EXISTS(CONTROLLERFAN) && SPINDLE_LASER_PWM_PIN == CONTROLLERFAN_PIN
#error "SPINDLE_LASER_PWM_PIN is used by CONTROLLERFAN_PIN."
#endif
#endif
#endif // SPINDLE_LASER_ENABLE

116
Marlin/src/HAL/HAL_LINUX/arduino.cpp

@ -0,0 +1,116 @@
/**
* 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/>.
*
*/
#ifdef __PLAT_LINUX__
#include <iostream>
#include "../../inc/MarlinConfig.h"
#include "hardware/Clock.h"
#include "../shared/Delay.h"
// Interrupts
void cli(void) { } // Disable
void sei(void) { } // Enable
// Time functions
void _delay_ms(const int delay_ms) {
delay(delay_ms);
}
uint32_t millis() {
return (uint32_t)Clock::millis();
}
// This is required for some Arduino libraries we are using
void delayMicroseconds(uint32_t us) {
Clock::delayMicros(us);
}
extern "C" void delay(const int msec) {
Clock::delayMillis(msec);
}
// IO functions
// As defined by Arduino INPUT(0x0), OUTPUT(0x1), INPUT_PULLUP(0x2)
void pinMode(const pin_t pin, const uint8_t mode) {
if (!VALID_PIN(pin)) return;
Gpio::setMode(pin, mode);
}
void digitalWrite(pin_t pin, uint8_t pin_status) {
if (!VALID_PIN(pin)) return;
Gpio::set(pin, pin_status);
}
bool digitalRead(pin_t pin) {
if (!VALID_PIN(pin)) return false;
return Gpio::get(pin);
}
void analogWrite(pin_t pin, int pwm_value) { // 1 - 254: pwm_value, 0: LOW, 255: HIGH
if (!VALID_PIN(pin)) return;
Gpio::set(pin, pwm_value);
}
uint16_t analogRead(pin_t adc_pin) {
if (!VALID_PIN(DIGITAL_PIN_TO_ANALOG_PIN(adc_pin))) return 0;
return Gpio::get(DIGITAL_PIN_TO_ANALOG_PIN(adc_pin));
}
// **************************
// Persistent Config Storage
// **************************
void eeprom_write_byte(unsigned char *pos, unsigned char value) {
}
unsigned char eeprom_read_byte(uint8_t * pos) { return '\0'; }
void eeprom_read_block(void *__dst, const void *__src, size_t __n) { }
void eeprom_update_block(const void *__src, void *__dst, size_t __n) { }
char *dtostrf (double __val, signed char __width, unsigned char __prec, char *__s) {
char format_string[20];
snprintf(format_string, 20, "%%%d.%df", __width, __prec);
sprintf(__s, format_string, __val);
return __s;
}
int32_t random(int32_t max) {
return rand() % max;
}
int32_t random(int32_t min, int32_t max) {
return min + rand() % (max - min);
}
void randomSeed(uint32_t value) {
srand(value);
}
int map(uint16_t x, uint16_t in_min, uint16_t in_max, uint16_t out_min, uint16_t out_max) {
return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
}
#endif // __PLAT_LINUX__

123
Marlin/src/HAL/HAL_LINUX/fastio.h

@ -0,0 +1,123 @@
/**
* 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
/**
* Fast I/O Routines for X86_64
*/
#include <Arduino.h>
#include <pinmapping.h>
#define USEABLE_HARDWARE_PWM(pin) false
#define SET_DIR_INPUT(IO) Gpio::setDir(IO, 1)
#define SET_DIR_OUTPUT(IO) Gpio::setDir(IO, 0)
#define SET_MODE(IO, mode) Gpio::setMode(IO, mode)
#define WRITE_PIN_SET(IO) Gpio::set(IO)
#define WRITE_PIN_CLR(IO) Gpio::clear(IO)
#define READ_PIN(IO) Gpio::get(IO)
#define WRITE_PIN(IO,V) Gpio::set(IO, V)
/**
* Magic I/O routines
*
* Now you can simply SET_OUTPUT(STEP); WRITE(STEP, HIGH); WRITE(STEP, LOW);
*
* Why double up on these macros? see http://gcc.gnu.org/onlinedocs/cpp/Stringification.html
*/
/// Read a pin
#define _READ(IO) READ_PIN(IO)
/// Write to a pin
#define _WRITE_VAR(IO,V) digitalWrite(IO,V)
#define _WRITE(IO,V) WRITE_PIN(IO,V)
/// toggle a pin
#define _TOGGLE(IO) _WRITE(IO, !READ(IO))
/// set pin as input
#define _SET_INPUT(IO) SET_DIR_INPUT(IO)
/// set pin as output
#define _SET_OUTPUT(IO) SET_DIR_OUTPUT(IO)
/// set pin as input with pullup mode
#define _PULLUP(IO,V) pinMode(IO, (V) ? INPUT_PULLUP : INPUT)
/// set pin as input with pulldown mode
#define _PULLDOWN(IO,V) pinMode(IO, (V) ? INPUT_PULLDOWN : INPUT)
// hg42: all pins can be input or output (I hope)
// hg42: undefined pins create compile error (IO, is no pin)
// hg42: currently not used, but was used by pinsDebug
/// check if pin is an input
#define _GET_INPUT(IO) (LPC1768_PIN_PIN(IO) >= 0)
/// check if pin is an output
#define _GET_OUTPUT(IO) (LPC1768_PIN_PIN(IO) >= 0)
// hg42: GET_TIMER is used only to check if it's a PWM pin
// hg42: we cannot use USEABLE_HARDWARE_PWM because it uses a function that cannot be used statically
// hg42: instead use PWM bit from the #define
/// check if pin is a timer
#define _GET_TIMER(IO) TRUE // could be LPC1768_PIN_PWM(IO), but there
// hg42: could be this:
// #define _GET_TIMER(IO) LPC1768_PIN_PWM(IO)
// but this is an incomplete check (12 pins are PWMable, but only 6 can be used at the same time)
/// Read a pin wrapper
#define READ(IO) _READ(IO)
/// Write to a pin wrapper
#define WRITE_VAR(IO,V) _WRITE_VAR(IO,V)
#define WRITE(IO,V) _WRITE(IO,V)
/// toggle a pin wrapper
#define TOGGLE(IO) _TOGGLE(IO)
/// set pin as input wrapper
#define SET_INPUT(IO) _SET_INPUT(IO)
/// set pin as input with pullup wrapper
#define SET_INPUT_PULLUP(IO) do{ _SET_INPUT(IO); _PULLUP(IO, HIGH); }while(0)
/// set pin as input with pulldown wrapper
#define SET_INPUT_PULLDOWN(IO) do{ _SET_INPUT(IO); _PULLDOWN(IO, HIGH); }while(0)
/// set pin as output wrapper - reads the pin and sets the output to that value
#define SET_OUTPUT(IO) do{ _WRITE(IO, _READ(IO)); _SET_OUTPUT(IO); }while(0)
/// check if pin is an input wrapper
#define GET_INPUT(IO) _GET_INPUT(IO)
/// check if pin is an output wrapper
#define GET_OUTPUT(IO) _GET_OUTPUT(IO)
/// check if pin is a timer (wrapper)
#define GET_TIMER(IO) _GET_TIMER(IO)
// Shorthand
#define OUT_WRITE(IO,V) do{ SET_OUTPUT(IO); WRITE(IO,V); }while(0)

32
Marlin/src/HAL/HAL_LINUX/hardware/Clock.cpp

@ -0,0 +1,32 @@
/**
* 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/>.
*
*/
#ifdef __PLAT_LINUX__
#include "../../../inc/MarlinConfig.h"
#include "Clock.h"
std::chrono::nanoseconds Clock::startup = std::chrono::high_resolution_clock::now().time_since_epoch();
uint32_t Clock::frequency = F_CPU;
double Clock::time_multiplier = 1.0;
#endif // __PLAT_LINUX__

89
Marlin/src/HAL/HAL_LINUX/hardware/Clock.h

@ -0,0 +1,89 @@
/**
* 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 <chrono>
#include <thread>
class Clock {
public:
static uint64_t ticks(uint32_t frequency = Clock::frequency) {
return (Clock::nanos() - Clock::startup.count()) / (1000000000ULL / frequency);
}
static uint64_t nanosToTicks(uint64_t ns, uint32_t frequency = Clock::frequency) {
return ns / (1000000000ULL / frequency);
}
// Time acceleration compensated
static uint64_t ticksToNanos(uint64_t tick, uint32_t frequency = Clock::frequency) {
return (tick * (1000000000ULL / frequency)) / Clock::time_multiplier;
}
static void setFrequency(uint32_t freq) {
Clock::frequency = freq;
}
// Time Acceleration compensated
static uint64_t nanos() {
auto now = std::chrono::high_resolution_clock::now().time_since_epoch();
return (now.count() - Clock::startup.count()) * Clock::time_multiplier;
}
static uint64_t micros() {
return Clock::nanos() / 1000;
}
static uint64_t millis() {
return Clock::micros() / 1000;
}
static double seconds() {
return Clock::nanos() / 1000000000.0;
}
static void delayCycles(uint64_t cycles) {
std::this_thread::sleep_for(std::chrono::nanoseconds( (1000000000L / frequency) * cycles) / Clock::time_multiplier );
}
static void delayMicros(uint64_t micros) {
std::this_thread::sleep_for(std::chrono::microseconds( micros ) / Clock::time_multiplier);
}
static void delayMillis(uint64_t millis) {
std::this_thread::sleep_for(std::chrono::milliseconds( millis ) / Clock::time_multiplier);
}
static void delaySeconds(double secs) {
std::this_thread::sleep_for(std::chrono::duration<double, std::milli>(secs * 1000) / Clock::time_multiplier);
}
// Will reduce timer resolution increasing likelihood of overflows
static void setTimeMultiplier(double tm) {
Clock::time_multiplier = tm;
}
private:
static std::chrono::nanoseconds startup;
static uint32_t frequency;
static double time_multiplier;
};

30
Marlin/src/HAL/HAL_LINUX/hardware/Gpio.cpp

@ -0,0 +1,30 @@
/**
* 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/>.
*
*/
#ifdef __PLAT_LINUX__
#include "Gpio.h"
pin_data Gpio::pin_map[Gpio::pin_count+1] = {};
IOLogger* Gpio::logger = nullptr;
#endif // __PLAT_LINUX__

141
Marlin/src/HAL/HAL_LINUX/hardware/Gpio.h

@ -0,0 +1,141 @@
/**
* 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 "Clock.h"
#include "../../../inc/MarlinConfigPre.h"
#include <stdint.h>
typedef int16_t pin_type;
struct GpioEvent {
enum Type {
NOP,
FALL,
RISE,
SET_VALUE,
SETM,
SETD
};
uint64_t timestamp;
pin_type pin_id;
GpioEvent::Type event;
GpioEvent(uint64_t timestamp, pin_type pin_id, GpioEvent::Type event){
this->timestamp = timestamp;
this->pin_id = pin_id;
this->event = event;
}
};
class IOLogger {
public:
virtual ~IOLogger(){};
virtual void log(GpioEvent ev) = 0;
};
class Peripheral {
public:
virtual ~Peripheral(){};
virtual void interrupt(GpioEvent ev) = 0;
virtual void update() = 0;
};
struct pin_data {
uint8_t dir;
uint8_t mode;
uint16_t value;
Peripheral* cb;
};
class Gpio {
public:
static const pin_type pin_count = 255;
static pin_data pin_map[pin_count+1];
static bool valid_pin(pin_type pin) {
return pin >= 0 && pin <= pin_count;
}
static void set(pin_type pin) {
set(pin, 1);
}
static void set(pin_type pin, uint16_t value) {
if (!valid_pin(pin)) return;
GpioEvent::Type evt_type = value > 1 ? GpioEvent::SET_VALUE : value > pin_map[pin].value ? GpioEvent::RISE : value < pin_map[pin].value ? GpioEvent::FALL : GpioEvent::NOP;
pin_map[pin].value = value;
GpioEvent evt(Clock::nanos(), pin, evt_type);
if (pin_map[pin].cb != nullptr) {
pin_map[pin].cb->interrupt(evt);
}
if (Gpio::logger != nullptr) Gpio::logger->log(evt);
}
static uint16_t get(pin_type pin) {
if (!valid_pin(pin)) return 0;
return pin_map[pin].value;
}
static void clear(pin_type pin) {
set(pin, 0);
}
static void setMode(pin_type pin, uint8_t value) {
if (!valid_pin(pin)) return;
pin_map[pin].mode = value;
GpioEvent evt(Clock::nanos(), pin, GpioEvent::Type::SETM);
if (pin_map[pin].cb != nullptr) pin_map[pin].cb->interrupt(evt);
if (Gpio::logger != nullptr) Gpio::logger->log(evt);
}
static uint8_t getMode(pin_type pin) {
if (!valid_pin(pin)) return 0;
return pin_map[pin].mode;
}
static void setDir(pin_type pin, uint8_t value) {
if (!valid_pin(pin)) return;
pin_map[pin].dir = value;
GpioEvent evt(Clock::nanos(), pin, GpioEvent::Type::SETD);
if (pin_map[pin].cb != nullptr) pin_map[pin].cb->interrupt(evt);
if (Gpio::logger != nullptr) Gpio::logger->log(evt);
}
static uint8_t getDir(pin_type pin) {
if (!valid_pin(pin)) return 0;
return pin_map[pin].dir;
}
static void attachPeripheral(pin_type pin, Peripheral* per) {
if (!valid_pin(pin)) return;
pin_map[pin].cb = per;
}
static void attachLogger(IOLogger* logger) {
Gpio::logger = logger;
}
private:
static IOLogger* logger;
};

61
Marlin/src/HAL/HAL_LINUX/hardware/Heater.cpp

@ -0,0 +1,61 @@
/**
* 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/>.
*
*/
#ifdef __PLAT_LINUX__
#include "Clock.h"
#include <stdio.h>
#include "../../../inc/MarlinConfig.h"
#include "Heater.h"
Heater::Heater(pin_t heater, pin_t adc) {
heater_state = 0;
room_temp_raw = 150;
last = Clock::micros();
heater_pin = heater;
adc_pin = adc;
heat = 0.0;
}
Heater::~Heater() {
}
void Heater::update() {
// crude pwm read and cruder heat simulation
auto now = Clock::micros();
double delta = (now - last);
if (delta > 1000 ) {
heater_state = pwmcap.update(0xFFFF * Gpio::pin_map[heater_pin].value);
last = now;
heat += (heater_state - heat) * (delta / 1000000000.0);
if (heat < room_temp_raw) heat = room_temp_raw;
Gpio::pin_map[analogInputToDigitalPin(adc_pin)].value = 0xFFFF - (uint16_t)heat;
}
}
void Heater::interrupt(GpioEvent ev) {
// ununsed
}
#endif // __PLAT_LINUX__

47
Marlin/src/HAL/HAL_LINUX/hardware/Heater.h

@ -0,0 +1,47 @@
/**
* 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 "Gpio.h"
struct LowpassFilter {
uint64_t data_delay = 0;
uint16_t update(uint16_t value) {
data_delay = data_delay - (data_delay >> 6) + value;
return (uint16_t)(data_delay >> 6);
}
};
class Heater: public Peripheral {
public:
Heater(pin_t heater, pin_t adc);
virtual ~Heater();
void interrupt(GpioEvent ev);
void update();
pin_t heater_pin, adc_pin;
uint16_t room_temp_raw;
uint16_t heater_state;
LowpassFilter pwmcap;
double heat;
uint64_t last;
};

50
Marlin/src/HAL/HAL_LINUX/hardware/IOLoggerCSV.cpp

@ -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/>.
*
*/
#ifdef __PLAT_LINUX__
#include "IOLoggerCSV.h"
IOLoggerCSV::IOLoggerCSV(std::string filename) {
file.open(filename);
}
IOLoggerCSV::~IOLoggerCSV() {
file.close();
}
void IOLoggerCSV::log(GpioEvent ev) {
std::lock_guard<std::mutex> lock(vector_lock);
events.push_back(ev); //minimal impact to signal handler
}
void IOLoggerCSV::flush() {
{ std::lock_guard<std::mutex> lock(vector_lock);
while (!events.empty()) {
file << events.front().timestamp << ", "<< events.front().pin_id << ", " << events.front().event << std::endl;
events.pop_front();
}
}
file.flush();
}
#endif // __PLAT_LINUX__

40
Marlin/src/HAL/HAL_LINUX/hardware/IOLoggerCSV.h

@ -0,0 +1,40 @@
/**
* 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 <mutex>
#include <list>
#include <fstream>
#include "Gpio.h"
class IOLoggerCSV: public IOLogger {
public:
IOLoggerCSV(std::string filename);
virtual ~IOLoggerCSV();
void flush();
void log(GpioEvent ev);
private:
std::ofstream file;
std::list<GpioEvent> events;
std::mutex vector_lock;
};

66
Marlin/src/HAL/HAL_LINUX/hardware/LinearAxis.cpp

@ -0,0 +1,66 @@
/**
* 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/>.
*
*/
#ifdef __PLAT_LINUX__
#include <random>
#include <stdio.h>
#include "Clock.h"
#include "LinearAxis.h"
LinearAxis::LinearAxis(pin_type enable, pin_type dir, pin_type step, pin_type end_min, pin_type end_max) {
enable_pin = enable;
dir_pin = dir;
step_pin = step;
min_pin = end_min;
max_pin = end_max;
min_position = 50;
max_position = (200*80) + min_position;
position = rand() % ((max_position - 40) - min_position) + (min_position + 20);
last_update = Clock::nanos();
Gpio::attachPeripheral(step_pin, this);
}
LinearAxis::~LinearAxis() {
}
void LinearAxis::update() {
}
void LinearAxis::interrupt(GpioEvent ev) {
if (ev.pin_id == step_pin && !Gpio::pin_map[enable_pin].value){
if (ev.event == GpioEvent::RISE) {
last_update = ev.timestamp;
position += -1 + 2 * Gpio::pin_map[dir_pin].value;
Gpio::pin_map[min_pin].value = (position < min_position);
//Gpio::pin_map[max_pin].value = (position > max_position);
//if(position < min_position) printf("axis(%d) endstop : pos: %d, mm: %f, min: %d\n", step_pin, position, position / 80.0, Gpio::pin_map[min_pin].value);
}
}
}
#endif // __PLAT_LINUX__

45
Marlin/src/HAL/HAL_LINUX/hardware/LinearAxis.h

@ -0,0 +1,45 @@
/**
* 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 <chrono>
#include "Gpio.h"
class LinearAxis: public Peripheral {
public:
LinearAxis(pin_type enable, pin_type dir, pin_type step, pin_type end_min, pin_type end_max);
virtual ~LinearAxis();
void update();
void interrupt(GpioEvent ev);
pin_type enable_pin;
pin_type dir_pin;
pin_type step_pin;
pin_type min_pin;
pin_type max_pin;
int32_t position;
int32_t min_position;
int32_t max_position;
uint64_t last_update;
};

118
Marlin/src/HAL/HAL_LINUX/hardware/Timer.cpp

@ -0,0 +1,118 @@
/**
* 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/>.
*
*/
#ifdef __PLAT_LINUX__
#include "Timer.h"
#include <stdio.h>
Timer::Timer() {
active = false;
compare = 0;
frequency = 0;
overruns = 0;
timerid = 0;
cbfn = nullptr;
period = 0;
start_time = 0;
avg_error = 0;
}
Timer::~Timer() {
timer_delete(timerid);
}
void Timer::init(uint32_t sig_id, uint32_t sim_freq, callback_fn* fn) {
struct sigaction sa;
struct sigevent sev;
frequency = sim_freq;
cbfn = fn;
sa.sa_flags = SA_SIGINFO;
sa.sa_sigaction = Timer::handler;
sigemptyset(&sa.sa_mask);
if (sigaction(SIGRTMIN, &sa, NULL) == -1) {
return; // todo: handle error
}
sigemptyset(&mask);
sigaddset(&mask, SIGRTMIN);
disable();
sev.sigev_notify = SIGEV_SIGNAL;
sev.sigev_signo = SIGRTMIN;
sev.sigev_value.sival_ptr = (void*)this;
if (timer_create(CLOCK_REALTIME, &sev, &timerid) == -1) {
return; // todo: handle error
}
}
void Timer::start(uint32_t frequency) {
setCompare(this->frequency / frequency);
//printf("timer(%ld) started\n", getID());
}
void Timer::enable() {
if (sigprocmask(SIG_UNBLOCK, &mask, NULL) == -1) {
return; // todo: handle error
}
active = true;
//printf("timer(%ld) enabled\n", getID());
}
void Timer::disable() {
if (sigprocmask(SIG_SETMASK, &mask, NULL) == -1) {
return; // todo: handle error
}
active = false;
}
void Timer::setCompare(uint32_t compare) {
uint32_t nsec_offset = 0;
if (active) {
nsec_offset = Clock::nanos() - this->start_time; // calculate how long the timer would have been running for
nsec_offset = nsec_offset < 1000 ? nsec_offset : 0; // constrain, this shouldn't be needed but apparently Marlin enables interrupts on the stepper timer before initialising it, todo: investigate ?bug?
}
this->compare = compare;
uint64_t ns = Clock::ticksToNanos(compare, frequency) - nsec_offset;
struct itimerspec its;
its.it_value.tv_sec = ns / 1000000000;
its.it_value.tv_nsec = ns % 1000000000;
its.it_interval.tv_sec = its.it_value.tv_sec;
its.it_interval.tv_nsec = its.it_value.tv_nsec;
if (timer_settime(timerid, 0, &its, NULL) == -1) {
printf("timer(%ld) failed, compare: %d(%ld)\n", getID(), compare, its.it_value.tv_nsec);
return; // todo: handle error
}
//printf("timer(%ld) started, compare: %d(%d)\n", getID(), compare, its.it_value.tv_nsec);
this->period = its.it_value.tv_nsec;
this->start_time = Clock::nanos();
}
uint32_t Timer::getCount() {
return Clock::nanosToTicks(Clock::nanos() - this->start_time, frequency);
}
#endif // __PLAT_LINUX__

76
Marlin/src/HAL/HAL_LINUX/hardware/Timer.h

@ -0,0 +1,76 @@
/**
* 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 <stdint.h>
#include <stdlib.h>
#include <unistd.h>
#include <signal.h>
#include <time.h>
#include <stdio.h>
#include "Clock.h"
class Timer {
public:
Timer();
virtual ~Timer();
typedef void (callback_fn)();
void init(uint32_t sig_id, uint32_t sim_freq, callback_fn* fn);
void start(uint32_t frequency);
void enable();
bool enabled() {return active;}
void disable();
void setCompare(uint32_t compare);
uint32_t getCount();
uint32_t getCompare() {return compare;}
uint32_t getOverruns() {return overruns;}
uint32_t getAvgError() {return avg_error;}
intptr_t getID() {
return (*(intptr_t*)timerid);
}
static void handler(int sig, siginfo_t *si, void *uc){
Timer* _this = (Timer*)si->si_value.sival_ptr;
_this->avg_error += (Clock::nanos() - _this->start_time) - _this->period; //high_resolution_clock is also limited in precision, but best we have
_this->avg_error /= 2; //very crude precision analysis (actually within +-500ns usually)
_this->start_time = Clock::nanos(); // wrap
_this->cbfn();
_this->overruns += timer_getoverrun(_this->timerid); // even at 50Khz this doesn't stay zero, again demonstrating the limitations
// using a realtime linux kernel would help somewhat
}
private:
bool active;
uint32_t compare;
uint32_t frequency;
uint32_t overruns;
timer_t timerid;
sigset_t mask;
callback_fn* cbfn;
uint64_t period;
uint64_t avg_error;
uint64_t start_time;
};

125
Marlin/src/HAL/HAL_LINUX/include/Arduino.h

@ -0,0 +1,125 @@
/**
* 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 <stddef.h>
#include <stdint.h>
#include <math.h>
#include <cstring>
#include <pinmapping.h>
#define HIGH 0x01
#define LOW 0x00
#define INPUT 0x00
#define OUTPUT 0x01
#define INPUT_PULLUP 0x02
#define INPUT_PULLDOWN 0x03
#define LSBFIRST 0
#define MSBFIRST 1
#define CHANGE 0x02
#define FALLING 0x03
#define RISING 0x04
#define E2END 0xFFF // EEPROM end address
typedef uint8_t byte;
#define PROGMEM
#define PSTR(v) (v)
#define PGM_P const char *
// Used for libraries, preprocessor, and constants
#define min(a,b) ((a)<(b)?(a):(b))
#define max(a,b) ((a)>(b)?(a):(b))
#define abs(x) ((x)>0?(x):-(x))
#ifndef isnan
#define isnan std::isnan
#endif
#ifndef isinf
#define isinf std::isinf
#endif
#define sq(v) ((v) * (v))
#define square(v) sq(v)
#define constrain(value, arg_min, arg_max) ((value) < (arg_min) ? (arg_min) :((value) > (arg_max) ? (arg_max) : (value)))
//Interrupts
void cli(void); // Disable
void sei(void); // Enable
void attachInterrupt(uint32_t pin, void (*callback)(void), uint32_t mode);
void detachInterrupt(uint32_t pin);
extern "C" void GpioEnableInt(uint32_t port, uint32_t pin, uint32_t mode);
extern "C" void GpioDisableInt(uint32_t port, uint32_t pin);
// Program Memory
#define pgm_read_ptr(addr) (*((void**)(addr)))
#define pgm_read_byte_near(addr) (*((uint8_t*)(addr)))
#define pgm_read_float_near(addr) (*((float*)(addr)))
#define pgm_read_word_near(addr) (*((uint16_t*)(addr)))
#define pgm_read_dword_near(addr) (*((uint32_t*)(addr)))
#define pgm_read_byte(addr) pgm_read_byte_near(addr)
#define pgm_read_float(addr) pgm_read_float_near(addr)
#define pgm_read_word(addr) pgm_read_word_near(addr)
#define pgm_read_dword(addr) pgm_read_dword_near(addr)
using std::memcpy;
#define memcpy_P memcpy
#define sprintf_P sprintf
#define strstr_P strstr
#define strncpy_P strncpy
#define vsnprintf_P vsnprintf
#define strcpy_P strcpy
#define snprintf_P snprintf
#define strlen_P strlen
// Time functions
extern "C" {
void delay(const int milis);
}
void _delay_ms(const int delay);
void delayMicroseconds(unsigned long);
uint32_t millis();
//IO functions
void pinMode(const pin_t, const uint8_t);
void digitalWrite(pin_t, uint8_t);
bool digitalRead(pin_t);
void analogWrite(pin_t, int);
uint16_t analogRead(pin_t);
// EEPROM
void eeprom_write_byte(unsigned char *pos, unsigned char value);
unsigned char eeprom_read_byte(unsigned char *pos);
void eeprom_read_block (void *__dst, const void *__src, size_t __n);
void eeprom_update_block (const void *__src, void *__dst, size_t __n);
int32_t random(int32_t);
int32_t random(int32_t, int32_t);
void randomSeed(uint32_t);
char *dtostrf (double __val, signed char __width, unsigned char __prec, char *__s);
int map(uint16_t x, uint16_t in_min, uint16_t in_max, uint16_t out_min, uint16_t out_max);

70
Marlin/src/HAL/HAL_LINUX/include/pinmapping.cpp

@ -0,0 +1,70 @@
/**
* 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/>.
*
*/
#ifdef __PLAT_LINUX__
#include <pinmapping.h>
#include "../../../gcode/parser.h"
uint8_t analog_offset = NUM_DIGITAL_PINS - NUM_ANALOG_INPUTS;
// Get the digital pin for an analog index
pin_t analogInputToDigitalPin(const int8_t p) {
return (WITHIN(p, 0, NUM_ANALOG_INPUTS) ? analog_offset + p : P_NC);
}
// Return the index of a pin number
int16_t GET_PIN_MAP_INDEX(const pin_t pin) {
return pin;
}
// Test whether the pin is valid
bool VALID_PIN(const pin_t p) {
return WITHIN(p, 0, NUM_DIGITAL_PINS);
}
// Get the analog index for a digital pin
int8_t DIGITAL_PIN_TO_ANALOG_PIN(const pin_t p) {
return (WITHIN(p, analog_offset, NUM_DIGITAL_PINS) ? p - analog_offset : P_NC);
}
// Test whether the pin is PWM
bool PWM_PIN(const pin_t p) {
return false;
}
// Test whether the pin is interruptable
bool INTERRUPT_PIN(const pin_t p) {
return false;
}
// Get the pin number at the given index
pin_t GET_PIN_MAP_PIN(const int16_t ind) {
return ind;
}
int16_t PARSED_PIN_INDEX(const char code, const int16_t dval) {
return parser.intval(code, dval);
}
#endif // __PLAT_LINUX__

59
Marlin/src/HAL/HAL_LINUX/include/pinmapping.h

@ -0,0 +1,59 @@
/**
* 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 "../../../inc/MarlinConfigPre.h"
#include <stdint.h>
#include "../hardware/Gpio.h"
typedef pin_type pin_t;
#define P_NC -1
constexpr uint16_t NUM_DIGITAL_PINS = Gpio::pin_count;
constexpr uint8_t NUM_ANALOG_INPUTS = 16;
#define HAL_SENSITIVE_PINS
// Get the digital pin for an analog index
pin_t analogInputToDigitalPin(const int8_t p);
// Return the index of a pin number
int16_t GET_PIN_MAP_INDEX(const pin_t pin);
// Test whether the pin is valid
bool VALID_PIN(const pin_t p);
// Get the analog index for a digital pin
int8_t DIGITAL_PIN_TO_ANALOG_PIN(const pin_t p);
// Test whether the pin is PWM
bool PWM_PIN(const pin_t p);
// Test whether the pin is interruptable
bool INTERRUPT_PIN(const pin_t p);
// Get the pin number at the given index
pin_t GET_PIN_MAP_PIN(const int16_t ind);
// Parse a G-code word into a pin index
int16_t PARSED_PIN_INDEX(const char code, const int16_t dval);

207
Marlin/src/HAL/HAL_LINUX/include/serial.h

@ -0,0 +1,207 @@
/**
* 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 "../../../inc/MarlinConfigPre.h"
#if ENABLED(EMERGENCY_PARSER)
#include "../../../feature/emergency_parser.h"
#endif
#include <stdarg.h>
#include <stdio.h>
/**
* Generic RingBuffer
* T type of the buffer array
* S size of the buffer (must be power of 2)
*
*/
template <typename T, uint32_t S> class RingBuffer {
public:
RingBuffer() { index_read = index_write = 0; }
uint32_t available() volatile { return index_write - index_read; }
uint32_t free() volatile { return buffer_size - available(); }
bool empty() volatile { return index_read == index_write; }
bool full() volatile { return available() == buffer_size; }
void clear() volatile { index_read = index_write = 0; }
bool peek(T *value) volatile {
if (value == 0 || available() == 0)
return false;
*value = buffer[mask(index_read)];
return true;
}
int read() volatile {
if (empty()) return -1;
return buffer[mask(index_read++)];
}
bool write(T value) volatile {
if (full()) return false;
buffer[mask(index_write++)] = value;
return true;
}
private:
uint32_t mask(uint32_t val) volatile {
return buffer_mask & val;
}
static const uint32_t buffer_size = S;
static const uint32_t buffer_mask = buffer_size - 1;
volatile T buffer[buffer_size];
volatile uint32_t index_write;
volatile uint32_t index_read;
};
class HalSerial {
public:
#if ENABLED(EMERGENCY_PARSER)
EmergencyParser::State emergency_state;
#endif
HalSerial() { host_connected = true; }
void begin(int32_t baud) {
}
int peek() {
uint8_t value;
return receive_buffer.peek(&value) ? value : -1;
}
int read() { return receive_buffer.read(); }
size_t write(char c) {
if (!host_connected) return 0;
while (!transmit_buffer.free());
return transmit_buffer.write(c);
}
operator bool() { return host_connected; }
uint16_t available() {
return (uint16_t)receive_buffer.available();
}
void flush() { receive_buffer.clear(); }
uint8_t availableForWrite(void){
return transmit_buffer.free() > 255 ? 255 : (uint8_t)transmit_buffer.free();
}
void flushTX(void){
if (host_connected)
while (transmit_buffer.available()) { /* nada */ }
}
void printf(const char *format, ...) {
static char buffer[256];
va_list vArgs;
va_start(vArgs, format);
int length = vsnprintf((char *) buffer, 256, (char const *) format, vArgs);
va_end(vArgs);
if (length > 0 && length < 256) {
if (host_connected) {
for (int i = 0; i < length;) {
if (transmit_buffer.write(buffer[i])) {
++i;
}
}
}
}
}
#define DEC 10
#define HEX 16
#define OCT 8
#define BIN 2
void print_bin(uint32_t value, uint8_t num_digits) {
uint32_t mask = 1 << (num_digits -1);
for (uint8_t i = 0; i < num_digits; i++) {
if (!(i % 4) && i) write(' ');
if (!(i % 16) && i) write(' ');
if (value & mask) write('1');
else write('0');
value <<= 1;
}
}
void print(const char value[]) { printf("%s" , value); }
void print(char value, int nbase = 0) {
if (nbase == BIN) print_bin(value, 8);
else if (nbase == OCT) printf("%3o", value);
else if (nbase == HEX) printf("%2X", value);
else if (nbase == DEC ) printf("%d", value);
else printf("%c" , value);
}
void print(unsigned char value, int nbase = 0) {
if (nbase == BIN) print_bin(value, 8);
else if (nbase == OCT) printf("%3o", value);
else if (nbase == HEX) printf("%2X", value);
else printf("%u" , value);
}
void print(int value, int nbase = 0) {
if (nbase == BIN) print_bin(value, 16);
else if (nbase == OCT) printf("%6o", value);
else if (nbase == HEX) printf("%4X", value);
else printf("%d", value);
}
void print(unsigned int value, int nbase = 0) {
if (nbase == BIN) print_bin(value, 16);
else if (nbase == OCT) printf("%6o", value);
else if (nbase == HEX) printf("%4X", value);
else printf("%u" , value);
}
void print(long value, int nbase = 0) {
if (nbase == BIN) print_bin(value, 32);
else if (nbase == OCT) printf("%11o", value);
else if (nbase == HEX) printf("%8X", value);
else printf("%ld" , value);
}
void print(unsigned long value, int nbase = 0) {
if (nbase == BIN) print_bin(value, 32);
else if (nbase == OCT) printf("%11o", value);
else if (nbase == HEX) printf("%8X", value);
else printf("%lu" , value);
}
void print(float value, int round = 6) { printf("%f" , value); }
void print(double value, int round = 6) { printf("%f" , value); }
void println(const char value[]) { printf("%s\n" , value); }
void println(char value, int nbase = 0) { print(value, nbase); println(); }
void println(unsigned char value, int nbase = 0) { print(value, nbase); println(); }
void println(int value, int nbase = 0) { print(value, nbase); println(); }
void println(unsigned int value, int nbase = 0) { print(value, nbase); println(); }
void println(long value, int nbase = 0) { print(value, nbase); println(); }
void println(unsigned long value, int nbase = 0) { print(value, nbase); println(); }
void println(float value, int round = 6) { printf("%f\n" , value); }
void println(double value, int round = 6) { printf("%f\n" , value); }
void println(void) { print('\n'); }
volatile RingBuffer<uint8_t, 128> receive_buffer;
volatile RingBuffer<uint8_t, 128> transmit_buffer;
volatile bool host_connected;
};

137
Marlin/src/HAL/HAL_LINUX/main.cpp

@ -0,0 +1,137 @@
/**
* Marlin 3D Printer Firmware
*
* Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* 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/>.
*
*/
#ifdef __PLAT_LINUX__
extern void setup();
extern void loop();
#include <thread>
#include <iostream>
#include <fstream>
#include "../../inc/MarlinConfig.h"
#include <stdio.h>
#include <stdarg.h>
#include "../shared/Delay.h"
#include "hardware/IOLoggerCSV.h"
#include "hardware/Heater.h"
#include "hardware/LinearAxis.h"
// simple stdout / stdin implementation for fake serial port
void write_serial_thread() {
for (;;) {
for (std::size_t i = usb_serial.transmit_buffer.available(); i > 0; i--) {
fputc(usb_serial.transmit_buffer.read(), stdout);
}
std::this_thread::yield();
}
}
void read_serial_thread() {
char buffer[255] = {};
for (;;) {
std::size_t len = MIN(usb_serial.receive_buffer.free(), 254U);
if (fgets(buffer, len, stdin))
for (std::size_t i = 0; i < strlen(buffer); i++)
usb_serial.receive_buffer.write(buffer[i]);
std::this_thread::yield();
}
}
void simulation_loop() {
Heater hotend(HEATER_0_PIN, TEMP_0_PIN);
Heater bed(HEATER_BED_PIN, TEMP_BED_PIN);
LinearAxis x_axis(X_ENABLE_PIN, X_DIR_PIN, X_STEP_PIN, X_MIN_PIN, X_MAX_PIN);
LinearAxis y_axis(Y_ENABLE_PIN, Y_DIR_PIN, Y_STEP_PIN, Y_MIN_PIN, Y_MAX_PIN);
LinearAxis z_axis(Z_ENABLE_PIN, Z_DIR_PIN, Z_STEP_PIN, Z_MIN_PIN, Z_MAX_PIN);
LinearAxis extruder0(E0_ENABLE_PIN, E0_DIR_PIN, E0_STEP_PIN, P_NC, P_NC);
//#define GPIO_LOGGING // Full GPIO and Positional Logging
#ifdef GPIO_LOGGING
IOLoggerCSV logger("all_gpio_log.csv");
Gpio::attachLogger(&logger);
std::ofstream position_log;
position_log.open("axis_position_log.csv");
int32_t x,y,z;
#endif
for (;;) {
hotend.update();
bed.update();
x_axis.update();
y_axis.update();
z_axis.update();
extruder0.update();
#ifdef GPIO_LOGGING
if (x_axis.position != x || y_axis.position != y || z_axis.position != z) {
uint64_t update = MAX3(x_axis.last_update, y_axis.last_update, z_axis.last_update);
position_log << update << ", " << x_axis.position << ", " << y_axis.position << ", " << z_axis.position << std::endl;
position_log.flush();
x = x_axis.position;
y = y_axis.position;
z = z_axis.position;
}
// flush the logger
logger.flush();
#endif
std::this_thread::yield();
}
}
int main(void) {
std::thread write_serial (write_serial_thread);
std::thread read_serial (read_serial_thread);
#if NUM_SERIAL > 0
MYSERIAL0.begin(BAUDRATE);
SERIAL_PRINTF("x86_64 Initialised\n");
SERIAL_FLUSHTX();
#endif
Clock::setFrequency(F_CPU);
Clock::setTimeMultiplier(1.0); // some testing at 10x
HAL_timer_init();
std::thread simulation (simulation_loop);
DELAY_US(10000);
setup();
for (;;) {
loop();
std::this_thread::yield();
}
simulation.join();
write_serial.join();
read_serial.join();
}
#endif // __PLAT_LINUX__

101
Marlin/src/HAL/HAL_LINUX/persistent_store_impl.cpp

@ -0,0 +1,101 @@
/**
* 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/>.
*
*/
#ifdef __PLAT_LINUX__
#include "../../inc/MarlinConfig.h"
#if ENABLED(EEPROM_SETTINGS)
#include "../shared/persistent_store_api.h"
#include <stdio.h>
uint8_t buffer[E2END];
char filename[] = "eeprom.dat";
bool PersistentStore::access_start() {
const char eeprom_erase_value = 0xFF;
FILE * eeprom_file = fopen(filename, "rb");
if (eeprom_file == NULL) return false;
fseek(eeprom_file, 0L, SEEK_END);
std::size_t file_size = ftell(eeprom_file);
if (file_size < E2END) {
memset(buffer + file_size, eeprom_erase_value, E2END - file_size);
}
else {
fseek(eeprom_file, 0L, SEEK_SET);
fread(buffer, sizeof(uint8_t), sizeof(buffer), eeprom_file);
}
fclose(eeprom_file);
return true;
}
bool PersistentStore::access_finish() {
FILE * eeprom_file = fopen(filename, "wb");
if (eeprom_file == NULL) return false;
fwrite(buffer, sizeof(uint8_t), sizeof(buffer), eeprom_file);
fclose(eeprom_file);
return true;
}
bool PersistentStore::write_data(int &pos, const uint8_t *value, const size_t size, uint16_t *crc) {
std::size_t bytes_written = 0;
for (std::size_t i = 0; i < size; i++) {
buffer[pos+i] = value[i];
bytes_written ++;
}
crc16(crc, value, size);
pos = pos + size;
return (bytes_written != size); // return true for any error
}
bool PersistentStore::read_data(int &pos, uint8_t* value, const size_t size, uint16_t *crc, const bool writing/*=true*/) {
std::size_t bytes_read = 0;
if (writing) {
for (std::size_t i = 0; i < size; i++) {
value[i] = buffer[pos+i];
bytes_read ++;
}
crc16(crc, value, size);
}
else {
uint8_t temp[size];
for (std::size_t i = 0; i < size; i++) {
temp[i] = buffer[pos+i];
bytes_read ++;
}
crc16(crc, temp, size);
}
pos = pos + size;
return bytes_read != size; // return true for any error
}
size_t PersistentStore::capacity() { return 4096; } // 4KiB of Emulated EEPROM
#endif // EEPROM_SETTINGS
#endif // __PLAT_LINUX__

63
Marlin/src/HAL/HAL_LINUX/pinsDebug.h

@ -0,0 +1,63 @@
/**
* 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/>.
*
*/
/**
* Support routines for X86_64
*/
/**
* Translation of routines & variables used by pinsDebug.h
*/
#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS
#define pwm_details(pin) pin = pin // do nothing // print PWM details
#define pwm_status(pin) false //Print a pin's PWM status. Return true if it's currently a PWM pin.
#define IS_ANALOG(P) (DIGITAL_PIN_TO_ANALOG_PIN(P) >= 0 ? 1 : 0)
#define digitalRead_mod(p) digitalRead(p)
#define PRINT_PORT(p)
#define GET_ARRAY_PIN(p) pin_array[p].pin
#define NAME_FORMAT(p) PSTR("%-##p##s")
#define PRINT_ARRAY_NAME(x) do {sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer);} while (0)
#define PRINT_PIN(p) do {sprintf_P(buffer, PSTR("%3d "), p); SERIAL_ECHO(buffer);} while (0)
#define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin
// active ADC function/mode/code values for PINSEL registers
constexpr int8_t ADC_pin_mode(pin_t pin) {
return (-1);
}
int8_t get_pin_mode(pin_t pin) {
if (!VALID_PIN(pin)) return -1;
return 0;
}
bool GET_PINMODE(pin_t pin) {
int8_t pin_mode = get_pin_mode(pin);
if (pin_mode == -1 || pin_mode == ADC_pin_mode(pin)) // found an invalid pin or active analog pin
return false;
return (Gpio::getMode(pin) != 0); //input/output state
}
bool GET_ARRAY_IS_DIGITAL(pin_t pin) {
return (!IS_ANALOG(pin) || get_pin_mode(pin) != ADC_pin_mode(pin));
}

80
Marlin/src/HAL/HAL_LINUX/servo_private.h

@ -0,0 +1,80 @@
/**
* 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
/**
* servo.h - Interrupt driven Servo library for Arduino using 16 bit timers- Version 2
* Copyright (c) 2009 Michael Margolis. All right reserved.
*
* This library is free software; you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public
* License as published by the Free Software Foundation; either
* version 2.1 of the License, or (at your option) any later version.
*
* This library 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
* Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public
* License along with this library; if not, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
/**
* Based on "servo.h - Interrupt driven Servo library for Arduino using 16 bit timers -
* Version 2 Copyright (c) 2009 Michael Margolis. All right reserved.
*
* The only modification was to update/delete macros to match the LPC176x.
*
*/
#include <stdint.h>
// Macros
//values in microseconds
#define MIN_PULSE_WIDTH 544 // the shortest pulse sent to a servo
#define MAX_PULSE_WIDTH 2400 // the longest pulse sent to a servo
#define DEFAULT_PULSE_WIDTH 1500 // default pulse width when servo is attached
#define REFRESH_INTERVAL 20000 // minimum time to refresh servos in microseconds
#define MAX_SERVOS 4
#define INVALID_SERVO 255 // flag indicating an invalid servo index
// Types
typedef struct {
uint8_t nbr : 8 ; // a pin number from 0 to 254 (255 signals invalid pin)
uint8_t isActive : 1 ; // true if this channel is enabled, pin not pulsed if false
} ServoPin_t;
typedef struct {
ServoPin_t Pin;
unsigned int pulse_width; // pulse width in microseconds
} ServoInfo_t;
// Global variables
extern uint8_t ServoCount;
extern ServoInfo_t servo_info[MAX_SERVOS];

53
Marlin/src/HAL/HAL_LINUX/spi_pins.h

@ -0,0 +1,53 @@
/**
* 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 "src/core/macros.h"
#if ENABLED(SDSUPPORT) && ENABLED(DOGLCD) && (LCD_PINS_D4 == SCK_PIN || LCD_PINS_ENABLE == MOSI_PIN || DOGLCD_SCK == SCK_PIN || DOGLCD_MOSI == MOSI_PIN)
#define LPC_SOFTWARE_SPI // If the SD card and LCD adapter share the same SPI pins, then software SPI is currently
// needed due to the speed and mode requred for communicating with each device being different.
// This requirement can be removed if the SPI access to these devices is updated to use
// spiBeginTransaction.
#endif
/** onboard SD card */
//#define SCK_PIN P0_07
//#define MISO_PIN P0_08
//#define MOSI_PIN P0_09
//#define SS_PIN P0_06
/** external */
#ifndef SCK_PIN
#define SCK_PIN 50
#endif
#ifndef MISO_PIN
#define MISO_PIN 51
#endif
#ifndef MOSI_PIN
#define MOSI_PIN 52
#endif
#ifndef SS_PIN
#define SS_PIN 53
#endif
#ifndef SDSS
#define SDSS SS_PIN
#endif

46
Marlin/src/HAL/HAL_LINUX/watchdog.cpp

@ -0,0 +1,46 @@
/**
* 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/>.
*
*/
#ifdef __PLAT_LINUX__
#include "../../inc/MarlinConfig.h"
#if ENABLED(USE_WATCHDOG)
#include "watchdog.h"
void watchdog_init(void) {}
void HAL_clear_reset_source(void) {}
uint8_t HAL_get_reset_source(void) {
return RST_POWER_ON;
}
void watchdog_reset() {}
#else
void HAL_clear_reset_source(void) {}
uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; }
#endif // USE_WATCHDOG
#endif // __PLAT_LINUX__

34
Marlin/src/HAL/HAL_LINUX/watchdog.h

@ -0,0 +1,34 @@
/**
* 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
#define RST_POWER_ON 1
#define RST_EXTERNAL 2
#define RST_BROWN_OUT 4
#define RST_WATCHDOG 8
#define WDT_TIMEOUT 4000000 // 4 second timeout
void watchdog_init(void);
void watchdog_reset(void);
void HAL_clear_reset_source(void);
uint8_t HAL_get_reset_source(void);

2
Marlin/src/HAL/platforms.h

@ -41,6 +41,8 @@
#define HAL_PLATFORM HAL_STM32
#elif defined(ARDUINO_ARCH_ESP32)
#define HAL_PLATFORM HAL_ESP32
#elif defined(__PLAT_LINUX__)
#define HAL_PLATFORM HAL_LINUX
#else
#error "Unsupported Platform!"
#endif

4
Marlin/src/HAL/shared/Delay.h

@ -158,6 +158,10 @@
}
}
#elif defined(__PLAT_LINUX__)
// specified inside platform
#else
#error "Unsupported MCU architecture"

6
Marlin/src/core/boards.h

@ -259,4 +259,10 @@
//
#define BOARD_ESP32 1900
//
// Simulations
//
#define BOARD_LINUX_RAMPS 2000
#define MB(board) (defined(BOARD_##board) && MOTHERBOARD==BOARD_##board)

7
Marlin/src/pins/pins.h

@ -448,6 +448,13 @@
#elif MB(ESP32)
#include "pins_ESP32.h"
//
// Linux Native Debug board
//
#elif MB(LINUX_RAMPS)
#include "pins_RAMPS_LINUX.h" // Linux env:linux_native
#else
#error "Unknown MOTHERBOARD value set in Configuration.h"
#endif

572
Marlin/src/pins/pins_RAMPS_LINUX.h

@ -0,0 +1,572 @@
/**
* 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/>.
*
*/
/**
* Arduino Mega with RAMPS v1.4 (or v1.3) pin assignments
*
* Applies to the following boards:
*
* RAMPS_14_EFB (Hotend, Fan, Bed)
* RAMPS_14_EEB (Hotend0, Hotend1, Bed)
* RAMPS_14_EFF (Hotend, Fan0, Fan1)
* RAMPS_14_EEF (Hotend0, Hotend1, Fan)
* RAMPS_14_SF (Spindle, Controller Fan)
*
* RAMPS_13_EFB (Hotend, Fan, Bed)
* RAMPS_13_EEB (Hotend0, Hotend1, Bed)
* RAMPS_13_EFF (Hotend, Fan0, Fan1)
* RAMPS_13_EEF (Hotend0, Hotend1, Fan)
* RAMPS_13_SF (Spindle, Controller Fan)
*
* Other pins_MYBOARD.h files may override these defaults
*
* Differences between
* RAMPS_13 | RAMPS_14
* 7 | 11
*/
#ifndef BOARD_NAME
#define BOARD_NAME "RAMPS 1.4"
#endif
#define IS_RAMPS_EFB
//
// Servos
//
#ifdef IS_RAMPS_13
#define SERVO0_PIN 7 // RAMPS_13 // Will conflict with BTN_EN2 on LCD_I2C_VIKI
#else
#define SERVO0_PIN 11
#endif
#define SERVO1_PIN 6
#define SERVO2_PIN 5
#ifndef SERVO3_PIN
#define SERVO3_PIN 4
#endif
//
// Limit Switches
//
#define X_MIN_PIN 3
#ifndef X_MAX_PIN
#define X_MAX_PIN 2
#endif
#define Y_MIN_PIN 14
#define Y_MAX_PIN 15
#define Z_MIN_PIN 18
#define Z_MAX_PIN 19
//
// Z Probe (when not Z_MIN_PIN)
//
#ifndef Z_MIN_PROBE_PIN
#define Z_MIN_PROBE_PIN 32
#endif
//
// Steppers
//
#define X_STEP_PIN 54
#define X_DIR_PIN 55
#define X_ENABLE_PIN 38
#ifndef X_CS_PIN
#define X_CS_PIN 53
#endif
#define Y_STEP_PIN 60
#define Y_DIR_PIN 61
#define Y_ENABLE_PIN 56
#ifndef Y_CS_PIN
#define Y_CS_PIN 49
#endif
#define Z_STEP_PIN 46
#define Z_DIR_PIN 48
#define Z_ENABLE_PIN 62
#ifndef Z_CS_PIN
#define Z_CS_PIN 40
#endif
#define E0_STEP_PIN 26
#define E0_DIR_PIN 28
#define E0_ENABLE_PIN 24
#ifndef E0_CS_PIN
#define E0_CS_PIN 42
#endif
#define E1_STEP_PIN 36
#define E1_DIR_PIN 34
#define E1_ENABLE_PIN 30
#ifndef E1_CS_PIN
#define E1_CS_PIN 44
#endif
//
// Temperature Sensors
//
#define TEMP_0_PIN 0 // Analog Input
#define TEMP_1_PIN 1 // Analog Input
#define TEMP_BED_PIN 2 // Analog Input
// SPI for Max6675 or Max31855 Thermocouple
#if DISABLED(SDSUPPORT)
#define MAX6675_SS_PIN 66 // Do not use pin 53 if there is even the remote possibility of using Display/SD card
#else
#define MAX6675_SS_PIN 66 // Do not use pin 49 as this is tied to the switch inside the SD card socket to detect if there is an SD card present
#endif
//
// Augmentation for auto-assigning RAMPS plugs
//
#if DISABLED(IS_RAMPS_EEB) && DISABLED(IS_RAMPS_EEF) && DISABLED(IS_RAMPS_EFB) && DISABLED(IS_RAMPS_EFF) && DISABLED(IS_RAMPS_SF) && !PIN_EXISTS(MOSFET_D)
#if HOTENDS > 1
#if TEMP_SENSOR_BED
#define IS_RAMPS_EEB
#else
#define IS_RAMPS_EEF
#endif
#elif TEMP_SENSOR_BED
#define IS_RAMPS_EFB
#else
#define IS_RAMPS_EFF
#endif
#endif
//
// Heaters / Fans
//
#ifndef MOSFET_D_PIN
#define MOSFET_D_PIN -1
#endif
#ifndef RAMPS_D8_PIN
#define RAMPS_D8_PIN 8
#endif
#ifndef RAMPS_D9_PIN
#define RAMPS_D9_PIN 9
#endif
#ifndef RAMPS_D10_PIN
#define RAMPS_D10_PIN 10
#endif
#define HEATER_0_PIN RAMPS_D10_PIN
#if ENABLED(IS_RAMPS_EFB) // Hotend, Fan, Bed
#define FAN_PIN RAMPS_D9_PIN
#define HEATER_BED_PIN RAMPS_D8_PIN
#elif ENABLED(IS_RAMPS_EEF) // Hotend, Hotend, Fan
#define HEATER_1_PIN RAMPS_D9_PIN
#define FAN_PIN RAMPS_D8_PIN
#elif ENABLED(IS_RAMPS_EEB) // Hotend, Hotend, Bed
#define HEATER_1_PIN RAMPS_D9_PIN
#define HEATER_BED_PIN RAMPS_D8_PIN
#elif ENABLED(IS_RAMPS_EFF) // Hotend, Fan, Fan
#define FAN_PIN RAMPS_D9_PIN
#define FAN1_PIN RAMPS_D8_PIN
#elif ENABLED(IS_RAMPS_SF) // Spindle, Fan
#define FAN_PIN RAMPS_D8_PIN
#else // Non-specific are "EFB" (i.e., "EFBF" or "EFBE")
#define FAN_PIN RAMPS_D9_PIN
#define HEATER_BED_PIN RAMPS_D8_PIN
#if HOTENDS == 1
#define FAN1_PIN MOSFET_D_PIN
#else
#define HEATER_1_PIN MOSFET_D_PIN
#endif
#endif
#ifndef FAN_PIN
#define FAN_PIN 4 // IO pin. Buffer needed
#endif
//
// Misc. Functions
//
#define SDSS 53
#define LED_PIN 13
#ifndef FILWIDTH_PIN
#define FILWIDTH_PIN 5 // Analog Input on AUX2
#endif
// define digital pin 4 for the filament runout sensor. Use the RAMPS 1.4 digital input 4 on the servos connector
#ifndef FIL_RUNOUT_PIN
#define FIL_RUNOUT_PIN 4
#endif
#ifndef PS_ON_PIN
#define PS_ON_PIN 12
#endif
#if ENABLED(CASE_LIGHT_ENABLE) && !defined(CASE_LIGHT_PIN) && !defined(SPINDLE_LASER_ENABLE_PIN)
#if NUM_SERVOS <= 1 // try to use servo connector first
#define CASE_LIGHT_PIN 6 // MUST BE HARDWARE PWM
#elif !(ENABLED(ULTRA_LCD) && ENABLED(NEWPANEL) \
&& (ENABLED(PANEL_ONE) || ENABLED(VIKI2) || ENABLED(miniVIKI) || ENABLED(MINIPANEL) || ENABLED(REPRAPWORLD_KEYPAD))) // try to use AUX 2
#define CASE_LIGHT_PIN 44 // MUST BE HARDWARE PWM
#endif
#endif
//
// M3/M4/M5 - Spindle/Laser Control
//
#if ENABLED(SPINDLE_LASER_ENABLE) && !PIN_EXISTS(SPINDLE_LASER_ENABLE)
#if !defined(NUM_SERVOS) || NUM_SERVOS == 0 // try to use servo connector first
#define SPINDLE_LASER_ENABLE_PIN 4 // Pin should have a pullup/pulldown!
#define SPINDLE_LASER_PWM_PIN 6 // MUST BE HARDWARE PWM
#define SPINDLE_DIR_PIN 5
#elif !(ENABLED(ULTRA_LCD) && ENABLED(NEWPANEL) \
&& (ENABLED(PANEL_ONE) || ENABLED(VIKI2) || ENABLED(miniVIKI) || ENABLED(MINIPANEL) || ENABLED(REPRAPWORLD_KEYPAD))) // try to use AUX 2
#define SPINDLE_LASER_ENABLE_PIN 40 // Pin should have a pullup/pulldown!
#define SPINDLE_LASER_PWM_PIN 44 // MUST BE HARDWARE PWM
#define SPINDLE_DIR_PIN 65
#endif
#endif
//
// Průša i3 MK2 Multiplexer Support
//
#ifndef E_MUX0_PIN
#define E_MUX0_PIN 40 // Z_CS_PIN
#endif
#ifndef E_MUX1_PIN
#define E_MUX1_PIN 42 // E0_CS_PIN
#endif
#ifndef E_MUX2_PIN
#define E_MUX2_PIN 44 // E1_CS_PIN
#endif
/**
* Default pins for TMC software SPI
*/
#if ENABLED(TMC_USE_SW_SPI)
#ifndef TMC_SW_MOSI
#define TMC_SW_MOSI 66
#endif
#ifndef TMC_SW_MISO
#define TMC_SW_MISO 44
#endif
#ifndef TMC_SW_SCK
#define TMC_SW_SCK 64
#endif
#endif
#if ENABLED(HAVE_TMC2208)
/**
* TMC2208 stepper drivers
*
* Hardware serial communication ports.
* If undefined software serial is used according to the pins below
*/
//#define X_HARDWARE_SERIAL Serial1
//#define X2_HARDWARE_SERIAL Serial1
//#define Y_HARDWARE_SERIAL Serial1
//#define Y2_HARDWARE_SERIAL Serial1
//#define Z_HARDWARE_SERIAL Serial1
//#define Z2_HARDWARE_SERIAL Serial1
//#define E0_HARDWARE_SERIAL Serial1
//#define E1_HARDWARE_SERIAL Serial1
//#define E2_HARDWARE_SERIAL Serial1
//#define E3_HARDWARE_SERIAL Serial1
//#define E4_HARDWARE_SERIAL Serial1
/**
* Software serial
*/
#define X_SERIAL_TX_PIN 40
#define X_SERIAL_RX_PIN 63
#define X2_SERIAL_TX_PIN -1
#define X2_SERIAL_RX_PIN -1
#define Y_SERIAL_TX_PIN 59
#define Y_SERIAL_RX_PIN 64
#define Y2_SERIAL_TX_PIN -1
#define Y2_SERIAL_RX_PIN -1
#define Z_SERIAL_TX_PIN 42
#define Z_SERIAL_RX_PIN 65
#define Z2_SERIAL_TX_PIN -1
#define Z2_SERIAL_RX_PIN -1
#define E0_SERIAL_TX_PIN 44
#define E0_SERIAL_RX_PIN 66
#define E1_SERIAL_TX_PIN -1
#define E1_SERIAL_RX_PIN -1
#define E2_SERIAL_TX_PIN -1
#define E2_SERIAL_RX_PIN -1
#define E3_SERIAL_TX_PIN -1
#define E3_SERIAL_RX_PIN -1
#define E4_SERIAL_TX_PIN -1
#define E4_SERIAL_RX_PIN -1
#endif
//////////////////////////
// LCDs and Controllers //
//////////////////////////
#if ENABLED(ULTRA_LCD)
//
// LCD Display output pins
//
#if ENABLED(REPRAPWORLD_GRAPHICAL_LCD)
#define LCD_PINS_RS 49 // CS chip select /SS chip slave select
#define LCD_PINS_ENABLE 51 // SID (MOSI)
#define LCD_PINS_D4 52 // SCK (CLK) clock
#elif ENABLED(NEWPANEL) && ENABLED(PANEL_ONE)
#define LCD_PINS_RS 40
#define LCD_PINS_ENABLE 42
#define LCD_PINS_D4 65
#define LCD_PINS_D5 66
#define LCD_PINS_D6 44
#define LCD_PINS_D7 64
#else
#if ENABLED(CR10_STOCKDISPLAY)
#define LCD_PINS_RS 27
#define LCD_PINS_ENABLE 29
#define LCD_PINS_D4 25
#if DISABLED(NEWPANEL)
#define BEEPER_PIN 37
#endif
#elif ENABLED(ZONESTAR_LCD)
#define LCD_PINS_RS 64
#define LCD_PINS_ENABLE 44
#define LCD_PINS_D4 63
#define LCD_PINS_D5 40
#define LCD_PINS_D6 42
#define LCD_PINS_D7 65
#else
#if ENABLED(MKS_12864OLED) || ENABLED(MKS_12864OLED_SSD1306)
#define LCD_PINS_DC 25 // Set as output on init
#define LCD_PINS_RS 27 // Pull low for 1s to init
// DOGM SPI LCD Support
#define DOGLCD_CS 16
#define DOGLCD_MOSI 17
#define DOGLCD_SCK 23
#define DOGLCD_A0 LCD_PINS_DC
#else
#define LCD_PINS_RS 16
#define LCD_PINS_ENABLE 17
#define LCD_PINS_D4 23
#define LCD_PINS_D5 25
#define LCD_PINS_D6 27
#endif
#define LCD_PINS_D7 29
#if DISABLED(NEWPANEL)
#define BEEPER_PIN 33
#endif
#endif
#if DISABLED(NEWPANEL)
// Buttons are attached to a shift register
// Not wired yet
//#define SHIFT_CLK 38
//#define SHIFT_LD 42
//#define SHIFT_OUT 40
//#define SHIFT_EN 17
#endif
#endif
//
// LCD Display input pins
//
#if ENABLED(NEWPANEL)
#if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER)
#define BEEPER_PIN 37
#if ENABLED(CR10_STOCKDISPLAY)
#define BTN_EN1 17
#define BTN_EN2 23
#else
#define BTN_EN1 31
#define BTN_EN2 33
#endif
#define BTN_ENC 35
#define SD_DETECT_PIN 49
#define KILL_PIN 41
#if ENABLED(BQ_LCD_SMART_CONTROLLER)
#define LCD_BACKLIGHT_PIN 39
#endif
#elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD)
#define BTN_EN1 64
#define BTN_EN2 59
#define BTN_ENC 63
#define SD_DETECT_PIN 42
#elif ENABLED(LCD_I2C_PANELOLU2)
#define BTN_EN1 47
#define BTN_EN2 43
#define BTN_ENC 32
#define LCD_SDSS SDSS
#define KILL_PIN 41
#elif ENABLED(LCD_I2C_VIKI)
#define BTN_EN1 22 // http://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains 40/42.
#define BTN_EN2 7 // 22/7 are unused on RAMPS_14. 22 is unused and 7 the SERVO0_PIN on RAMPS_13.
#define BTN_ENC -1
#define LCD_SDSS SDSS
#define SD_DETECT_PIN 49
#elif ENABLED(VIKI2) || ENABLED(miniVIKI)
#define DOGLCD_CS 45
#define DOGLCD_A0 44
#define LCD_SCREEN_ROT_180
#define BEEPER_PIN 33
#define STAT_LED_RED_PIN 32
#define STAT_LED_BLUE_PIN 35
#define BTN_EN1 22
#define BTN_EN2 7
#define BTN_ENC 39
#define SD_DETECT_PIN -1 // Pin 49 for display sd interface, 72 for easy adapter board
#define KILL_PIN 31
#elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER)
#define DOGLCD_CS 29
#define DOGLCD_A0 27
#define BEEPER_PIN 23
#define LCD_BACKLIGHT_PIN 33
#define BTN_EN1 35
#define BTN_EN2 37
#define BTN_ENC 31
#define LCD_SDSS SDSS
#define SD_DETECT_PIN 49
#define KILL_PIN 41
#elif ENABLED(MKS_MINI_12864) // Added in Marlin 1.1.6
#define DOGLCD_A0 27
#define DOGLCD_CS 25
// GLCD features
//#define LCD_CONTRAST 190
// Uncomment screen orientation
//#define LCD_SCREEN_ROT_90
//#define LCD_SCREEN_ROT_180
//#define LCD_SCREEN_ROT_270
#define BEEPER_PIN 37
// not connected to a pin
#define LCD_BACKLIGHT_PIN 65 // backlight LED on A11/D65
#define BTN_EN1 31
#define BTN_EN2 33
#define BTN_ENC 35
#define SD_DETECT_PIN 49
#define KILL_PIN 64
#elif ENABLED(MINIPANEL)
#define BEEPER_PIN 42
// not connected to a pin
#define LCD_BACKLIGHT_PIN 65 // backlight LED on A11/D65
#define DOGLCD_A0 44
#define DOGLCD_CS 66
// GLCD features
//#define LCD_CONTRAST 190
// Uncomment screen orientation
//#define LCD_SCREEN_ROT_90
//#define LCD_SCREEN_ROT_180
//#define LCD_SCREEN_ROT_270
#define BTN_EN1 40
#define BTN_EN2 63
#define BTN_ENC 59
#define SD_DETECT_PIN 49
#define KILL_PIN 64
#elif ENABLED(ZONESTAR_LCD)
#define ADC_KEYPAD_PIN 12
#elif ENABLED(AZSMZ_12864)
// Pins only defined for RAMPS_SMART currently
#else
// Beeper on AUX-4
#define BEEPER_PIN 33
// Buttons are directly attached using AUX-2
#if ENABLED(REPRAPWORLD_KEYPAD)
#define SHIFT_OUT 40
#define SHIFT_CLK 44
#define SHIFT_LD 42
#define BTN_EN1 64
#define BTN_EN2 59
#define BTN_ENC 63
#elif ENABLED(PANEL_ONE)
#define BTN_EN1 59 // AUX2 PIN 3
#define BTN_EN2 63 // AUX2 PIN 4
#define BTN_ENC 49 // AUX3 PIN 7
#else
#define BTN_EN1 37
#define BTN_EN2 35
#define BTN_ENC 31
#endif
#if ENABLED(G3D_PANEL)
#define SD_DETECT_PIN 49
#define KILL_PIN 41
#endif
#endif
#endif // NEWPANEL
#endif // ULTRA_LCD

0
buildroot/share/tests/DUE_tests → buildroot/share/tests/DUE-tests

0
buildroot/share/tests/LPC1768_tests → buildroot/share/tests/LPC1768-tests

0
buildroot/share/tests/LPC1769_tests → buildroot/share/tests/LPC1769-tests

0
buildroot/share/tests/STM32F1_tests → buildroot/share/tests/STM32F1-tests

16
buildroot/share/tests/linux_native-tests

@ -0,0 +1,16 @@
#!/usr/bin/env bash
#
# Build tests for Linux x86_64
#
# exit on first failure
set -e
restore_configs
opt_set MOTHERBOARD BOARD_LINUX_RAMPS
opt_set TEMP_SENSOR_BED 1
opt_enable PIDTEMPBED EEPROM_SETTINGS
exec_test $1 $2 "Linux with EEPROM"
# cleanup
restore_configs

0
buildroot/share/tests/megaatmega2560_tests → buildroot/share/tests/megaatmega2560-tests

4
buildroot/share/tests/run_tests

@ -33,7 +33,7 @@ if [[ $2 = "ALL" ]]; then
declare -a tests=(${dir_list[@]/*run_tests/})
for f in "${tests[@]}"; do
env_backup
testenv=$(basename $f | cut -d"_" -f1)
testenv=$(basename $f | cut -d"-" -f1)
printf "Running \033[0;32m$f\033[0m Tests\n"
exec_test $1 "$testenv --target clean" "Setup Build Environment"
$f $1 $testenv
@ -42,7 +42,7 @@ if [[ $2 = "ALL" ]]; then
else
env_backup
exec_test $1 "$2 --target clean" "Setup Build Environment"
$2_tests $1 $2
$2-tests $1 $2
env_restore
fi
printf "\033[0;32mAll tests completed successfully\033[0m\n"

0
buildroot/share/tests/teensy35_tests → buildroot/share/tests/teensy35-tests

14
platformio.ini

@ -381,3 +381,17 @@ board_build.f_cpu = 16000000L
lib_deps = ${common.lib_deps}
src_filter = ${common.default_src_filter} +<src/HAL/HAL_AVR>
monitor_speed = 250000
#
# Native
# No supported Arduino libraries, base Marlin only
#
[env:linux_native]
platform = native
build_flags = -D__PLAT_LINUX__ -std=gnu++17 -ggdb -g -lrt -lpthread
src_build_flags = -Wall -IMarlin/src/HAL/HAL_LINUX/include
build_unflags = -Wall
lib_ldf_mode = off
lib_deps =
extra_scripts =
src_filter = ${common.default_src_filter} +<src/HAL/HAL_LINUX>

Loading…
Cancel
Save