STM32F7 HAL using the official STM32 Arduino Core (#11750)
This commit is contained in:
parent
3e58b3a5d4
commit
348004c34f
126
Marlin/src/HAL/HAL_STM32/HAL.cpp
Normal file
126
Marlin/src/HAL/HAL_STM32/HAL.cpp
Normal file
|
@ -0,0 +1,126 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
*
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
|
||||
* Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
|
||||
* Copyright (c) 2017 Victor Perez
|
||||
*
|
||||
* 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 ARDUINO_ARCH_STM32
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Includes
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
#include "HAL.h"
|
||||
|
||||
#if ENABLED(EEPROM_EMULATED_WITH_SRAM)
|
||||
#if STM32F7xx
|
||||
#include "stm32f7xx_ll_pwr.h"
|
||||
#else
|
||||
#error "EEPROM_EMULATED_WITH_SRAM is currently only supported for STM32F7xx"
|
||||
#endif
|
||||
#endif // EEPROM_EMULATED_WITH_SRAM
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Externals
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Local defines
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Types
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Variables
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Public Variables
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
uint16_t HAL_adc_result;
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Private Variables
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Function prototypes
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Private functions
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Public functions
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// HAL initialization task
|
||||
void HAL_init(void) {
|
||||
|
||||
#if ENABLED(SDSUPPORT)
|
||||
OUT_WRITE(SDSS, HIGH); // Try to set SDSS inactive before any other SPI users start up
|
||||
#endif
|
||||
|
||||
#if ENABLED(EEPROM_EMULATED_WITH_SRAM)
|
||||
// Enable access to backup SRAM
|
||||
__HAL_RCC_PWR_CLK_ENABLE();
|
||||
HAL_PWR_EnableBkUpAccess();
|
||||
__HAL_RCC_BKPSRAM_CLK_ENABLE();
|
||||
|
||||
// Enable backup regulator
|
||||
LL_PWR_EnableBkUpRegulator();
|
||||
// Wait until backup regulator is initialized
|
||||
while (!LL_PWR_IsActiveFlag_BRR());
|
||||
#endif // EEPROM_EMULATED_SRAM
|
||||
}
|
||||
|
||||
void HAL_clear_reset_source(void) { __HAL_RCC_CLEAR_RESET_FLAGS(); }
|
||||
|
||||
uint8_t HAL_get_reset_source (void) {
|
||||
if (__HAL_RCC_GET_FLAG(RCC_FLAG_IWDGRST) != RESET) return RST_WATCHDOG;
|
||||
if (__HAL_RCC_GET_FLAG(RCC_FLAG_SFTRST) != RESET) return RST_SOFTWARE;
|
||||
if (__HAL_RCC_GET_FLAG(RCC_FLAG_PINRST) != RESET) return RST_EXTERNAL;
|
||||
if (__HAL_RCC_GET_FLAG(RCC_FLAG_PORRST) != RESET) return RST_POWER_ON;
|
||||
return 0;
|
||||
}
|
||||
|
||||
void _delay_ms(const int delay_ms) { delay(delay_ms); }
|
||||
|
||||
extern "C" {
|
||||
extern unsigned int _ebss; // end of bss section
|
||||
}
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// ADC
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
void HAL_adc_start_conversion(const uint8_t adc_pin) {
|
||||
HAL_adc_result = analogRead(adc_pin);
|
||||
}
|
||||
|
||||
uint16_t HAL_adc_get_result(void) {
|
||||
return HAL_adc_result;
|
||||
}
|
||||
|
||||
#endif // ARDUINO_ARCH_STM32
|
220
Marlin/src/HAL/HAL_STM32/HAL.h
Normal file
220
Marlin/src/HAL/HAL_STM32/HAL.h
Normal file
|
@ -0,0 +1,220 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
*
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
|
||||
* Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
|
||||
* Copyright (c) 2017 Victor Perez
|
||||
*
|
||||
* 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
|
||||
#undef DEBUG_NONE
|
||||
|
||||
#ifndef vsnprintf_P
|
||||
#define vsnprintf_P vsnprintf
|
||||
#endif
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Includes
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include "Arduino.h"
|
||||
|
||||
#ifdef USBCON
|
||||
#include <USBSerial.h>
|
||||
#endif
|
||||
|
||||
#include "../shared/math_32bit.h"
|
||||
#include "../shared/HAL_SPI.h"
|
||||
#include "fastio_STM32.h"
|
||||
#include "watchdog_STM32.h"
|
||||
|
||||
#include "HAL_timers_STM32.h"
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Defines
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
#if SERIAL_PORT == 0
|
||||
#error "Serial port 0 does not exist"
|
||||
#endif
|
||||
|
||||
#if !WITHIN(SERIAL_PORT, -1, 6)
|
||||
#error "SERIAL_PORT must be from -1 to 6"
|
||||
#endif
|
||||
#if SERIAL_PORT == -1
|
||||
#define MYSERIAL0 SerialUSB
|
||||
#elif SERIAL_PORT == 1
|
||||
#define MYSERIAL0 Serial1
|
||||
#elif SERIAL_PORT == 2
|
||||
#define MYSERIAL0 Serial2
|
||||
#elif SERIAL_PORT == 3
|
||||
#define MYSERIAL0 Serial3
|
||||
#elif SERIAL_PORT == 4
|
||||
#define MYSERIAL0 Serial4
|
||||
#elif SERIAL_PORT == 5
|
||||
#define MYSERIAL0 Serial5
|
||||
#elif SERIAL_PORT == 6
|
||||
#define MYSERIAL0 Serial6
|
||||
#endif
|
||||
|
||||
#ifdef SERIAL_PORT_2
|
||||
#if SERIAL_PORT_2 == 0
|
||||
#error "Serial port 0 does not exist"
|
||||
#endif
|
||||
|
||||
#if !WITHIN(SERIAL_PORT_2, -1, 6)
|
||||
#error "SERIAL_PORT_2 must be from -1 to 6"
|
||||
#elif SERIAL_PORT_2 == SERIAL_PORT
|
||||
#error "SERIAL_PORT_2 must be different than SERIAL_PORT"
|
||||
#endif
|
||||
#define NUM_SERIAL 2
|
||||
#if SERIAL_PORT_2 == -1
|
||||
#define MYSERIAL1 Serial0 // TODO Once CDC is supported
|
||||
#elif SERIAL_PORT_2 == 1
|
||||
#define MYSERIAL1 Serial1
|
||||
#elif SERIAL_PORT_2 == 2
|
||||
#define MYSERIAL1 Serial2
|
||||
#elif SERIAL_PORT_2 == 3
|
||||
#define MYSERIAL1 Serial3
|
||||
#elif SERIAL_PORT_2 == 4
|
||||
#define MYSERIAL1 Serial4
|
||||
#elif SERIAL_PORT_2 == 5
|
||||
#define MYSERIAL1 Serial5
|
||||
#elif SERIAL_PORT_2 == 6
|
||||
#define MYSERIAL1 Serial6
|
||||
#endif
|
||||
#else
|
||||
#define NUM_SERIAL 1
|
||||
#endif
|
||||
|
||||
#define _BV(b) (1 << (b))
|
||||
|
||||
/**
|
||||
* TODO: review this to return 1 for pins that are not analog input
|
||||
*/
|
||||
#ifndef analogInputToDigitalPin
|
||||
#define analogInputToDigitalPin(p) (p)
|
||||
#endif
|
||||
|
||||
#define CRITICAL_SECTION_START uint32_t primask = __get_PRIMASK(); __disable_irq()
|
||||
#define CRITICAL_SECTION_END if (!primask) __enable_irq()
|
||||
#define ISRS_ENABLED() (!__get_PRIMASK())
|
||||
#define ENABLE_ISRS() __enable_irq()
|
||||
#define DISABLE_ISRS() __disable_irq()
|
||||
#define cli() __disable_irq()
|
||||
#define sei() __enable_irq()
|
||||
|
||||
// On AVR this is in math.h?
|
||||
#define square(x) ((x)*(x))
|
||||
|
||||
#ifndef strncpy_P
|
||||
#define strncpy_P(dest, src, num) strncpy((dest), (src), (num))
|
||||
#endif
|
||||
|
||||
// Fix bug in pgm_read_ptr
|
||||
#undef pgm_read_ptr
|
||||
#define pgm_read_ptr(addr) (*(addr))
|
||||
|
||||
#define RST_POWER_ON 1
|
||||
#define RST_EXTERNAL 2
|
||||
#define RST_BROWN_OUT 4
|
||||
#define RST_WATCHDOG 8
|
||||
#define RST_JTAG 16
|
||||
#define RST_SOFTWARE 32
|
||||
#define RST_BACKUP 64
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Types
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
typedef int8_t pin_t;
|
||||
|
||||
#define HAL_SERVO_LIB libServo
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Public Variables
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
/** result of last ADC conversion */
|
||||
extern uint16_t HAL_adc_result;
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Public functions
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// Memory related
|
||||
#define __bss_end __bss_end__
|
||||
|
||||
// Enable hooks into setup for HAL
|
||||
#define HAL_INIT 1
|
||||
void HAL_init(void);
|
||||
|
||||
/** clear reset reason */
|
||||
void HAL_clear_reset_source (void);
|
||||
|
||||
/** reset reason */
|
||||
uint8_t HAL_get_reset_source (void);
|
||||
|
||||
void _delay_ms(const int delay);
|
||||
|
||||
extern "C" char* _sbrk(int incr);
|
||||
|
||||
static int freeMemory() {
|
||||
volatile char top;
|
||||
return &top - reinterpret_cast<char*>(_sbrk(0));
|
||||
}
|
||||
|
||||
// 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);
|
||||
|
||||
|
||||
// EEPROM
|
||||
|
||||
/**
|
||||
* Wire library should work for i2c eeproms.
|
||||
*/
|
||||
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);
|
||||
|
||||
// ADC
|
||||
|
||||
#define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT)
|
||||
|
||||
inline void HAL_adc_init(void) {}
|
||||
|
||||
#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
|
||||
#define HAL_READ_ADC() HAL_adc_result
|
||||
#define HAL_ADC_READY() true
|
||||
|
||||
void HAL_adc_start_conversion(const uint8_t adc_pin);
|
||||
|
||||
uint16_t HAL_adc_get_result(void);
|
||||
|
||||
#define GET_PIN_MAP_PIN(index) index
|
||||
#define GET_PIN_MAP_INDEX(pin) pin
|
||||
#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
|
57
Marlin/src/HAL/HAL_STM32/HAL_Servo_STM32.cpp
Normal file
57
Marlin/src/HAL/HAL_STM32/HAL_Servo_STM32.cpp
Normal file
|
@ -0,0 +1,57 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
* Copyright (C) 2017 Victor Perez
|
||||
*
|
||||
* 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 ARDUINO_ARCH_STM32
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#if HAS_SERVOS
|
||||
|
||||
#include "HAL_Servo_STM32.h"
|
||||
|
||||
uint8_t servoPin[MAX_SERVOS] = { 0 };
|
||||
|
||||
int8_t libServo::attach(const int pin) {
|
||||
if (this->servoIndex >= MAX_SERVOS) return -1;
|
||||
if (pin > 0) servoPin[this->servoIndex] = pin;
|
||||
return Servo::attach(servoPin[this->servoIndex]);
|
||||
}
|
||||
|
||||
int8_t libServo::attach(const int pin, const int min, const int max) {
|
||||
if (pin > 0) servoPin[this->servoIndex] = pin;
|
||||
return Servo::attach(servoPin[this->servoIndex], min, max);
|
||||
}
|
||||
|
||||
void libServo::move(const int value) {
|
||||
constexpr uint16_t servo_delay[] = SERVO_DELAY;
|
||||
static_assert(COUNT(servo_delay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long.");
|
||||
if (this->attach(0) >= 0) {
|
||||
this->write(value);
|
||||
safe_delay(servo_delay[this->servoIndex]);
|
||||
#if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE)
|
||||
this->detach();
|
||||
#endif
|
||||
}
|
||||
}
|
||||
#endif // HAS_SERVOS
|
||||
|
||||
#endif // ARDUINO_ARCH_STM32
|
36
Marlin/src/HAL/HAL_STM32/HAL_Servo_STM32.h
Normal file
36
Marlin/src/HAL/HAL_STM32/HAL_Servo_STM32.h
Normal file
|
@ -0,0 +1,36 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
* Copyright (C) 2017 Victor Perez
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include <Servo.h>
|
||||
|
||||
// Inherit and expand on the official library
|
||||
class libServo : public Servo {
|
||||
public:
|
||||
int8_t attach(const int pin);
|
||||
int8_t attach(const int pin, const int min, const int max);
|
||||
void move(const int value);
|
||||
private:
|
||||
uint16_t min_ticks, max_ticks;
|
||||
uint8_t servoIndex; // index into the channel data for this servo
|
||||
};
|
159
Marlin/src/HAL/HAL_STM32/HAL_spi_STM32.cpp
Normal file
159
Marlin/src/HAL/HAL_STM32/HAL_spi_STM32.cpp
Normal file
|
@ -0,0 +1,159 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
* Copyright (C) 2017 Victor Perez
|
||||
*
|
||||
* 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 ARDUINO_ARCH_STM32
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Includes
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
#include "HAL.h"
|
||||
#include "../shared/HAL_SPI.h"
|
||||
#include "pins_arduino.h"
|
||||
#include "spi_pins.h"
|
||||
#include "../../core/macros.h"
|
||||
|
||||
#include <SPI.h>
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Public Variables
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
static SPISettings spiConfig;
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Public functions
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
#if ENABLED(SOFTWARE_SPI)
|
||||
// --------------------------------------------------------------------------
|
||||
// Software SPI
|
||||
// --------------------------------------------------------------------------
|
||||
#error "Software SPI not supported for STM32F7. Use Hardware SPI."
|
||||
|
||||
#else
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Hardware SPI
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
/**
|
||||
* VGPV SPI speed start and PCLK2/2, by default 108/2 = 54Mhz
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Begin SPI port setup
|
||||
*
|
||||
* @return Nothing
|
||||
*
|
||||
* @details Only configures SS pin since stm32duino creates and initialize the SPI object
|
||||
*/
|
||||
void spiBegin(void) {
|
||||
#if !PIN_EXISTS(SS)
|
||||
#error "SS_PIN not defined!"
|
||||
#endif
|
||||
|
||||
SET_OUTPUT(SS_PIN);
|
||||
WRITE(SS_PIN, HIGH);
|
||||
}
|
||||
|
||||
/** Configure SPI for specified SPI speed */
|
||||
void spiInit(uint8_t spiRate) {
|
||||
// Use datarates Marlin uses
|
||||
uint32_t clock;
|
||||
switch (spiRate) {
|
||||
case SPI_FULL_SPEED: clock = 20000000; break; // 13.9mhz=20000000 6.75mhz=10000000 3.38mhz=5000000 .833mhz=1000000
|
||||
case SPI_HALF_SPEED: clock = 5000000; break;
|
||||
case SPI_QUARTER_SPEED: clock = 2500000; break;
|
||||
case SPI_EIGHTH_SPEED: clock = 1250000; break;
|
||||
case SPI_SPEED_5: clock = 625000; break;
|
||||
case SPI_SPEED_6: clock = 300000; break;
|
||||
default:
|
||||
clock = 4000000; // Default from the SPI library
|
||||
}
|
||||
spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0);
|
||||
SPI.begin();
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Receives a single byte from the SPI port.
|
||||
*
|
||||
* @return Byte received
|
||||
*
|
||||
* @details
|
||||
*/
|
||||
uint8_t spiRec(void) {
|
||||
SPI.beginTransaction(spiConfig);
|
||||
uint8_t returnByte = SPI.transfer(0xFF);
|
||||
SPI.endTransaction();
|
||||
return returnByte;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Receives a number of bytes from the SPI port to a buffer
|
||||
*
|
||||
* @param buf Pointer to starting address of buffer to write to.
|
||||
* @param nbyte Number of bytes to receive.
|
||||
* @return Nothing
|
||||
*
|
||||
* @details Uses DMA
|
||||
*/
|
||||
void spiRead(uint8_t* buf, uint16_t nbyte) {
|
||||
if (nbyte == 0) return;
|
||||
SPI.beginTransaction(spiConfig);
|
||||
for (int i = 0; i < nbyte; i++) {
|
||||
buf[i] = SPI.transfer(0xFF);
|
||||
}
|
||||
SPI.endTransaction();
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Sends a single byte on SPI port
|
||||
*
|
||||
* @param b Byte to send
|
||||
*
|
||||
* @details
|
||||
*/
|
||||
void spiSend(uint8_t b) {
|
||||
SPI.beginTransaction(spiConfig);
|
||||
SPI.transfer(b);
|
||||
SPI.endTransaction();
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Write token and then write from 512 byte buffer to SPI (for SD card)
|
||||
*
|
||||
* @param buf Pointer with buffer start address
|
||||
* @return Nothing
|
||||
*
|
||||
* @details Use DMA
|
||||
*/
|
||||
void spiSendBlock(uint8_t token, const uint8_t* buf) {
|
||||
SPI.beginTransaction(spiConfig);
|
||||
SPI.transfer(token);
|
||||
SPI.transfer((uint8_t*)buf, (uint8_t*)0, 512);
|
||||
SPI.endTransaction();
|
||||
}
|
||||
|
||||
#endif // SOFTWARE_SPI
|
||||
|
||||
#endif // ARDUINO_ARCH_STM32
|
117
Marlin/src/HAL/HAL_STM32/HAL_timers_STM32.cpp
Normal file
117
Marlin/src/HAL/HAL_STM32/HAL_timers_STM32.cpp
Normal file
|
@ -0,0 +1,117 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
*
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
|
||||
* Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#ifdef ARDUINO_ARCH_STM32
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Includes
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
#include "HAL.h"
|
||||
|
||||
#include "HAL_timers_STM32.h"
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Externals
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Local defines
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
#define NUM_HARDWARE_TIMERS 2
|
||||
|
||||
//#define PRESCALER 1
|
||||
// --------------------------------------------------------------------------
|
||||
// Types
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Public Variables
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Private Variables
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
stm32f4_timer_t TimerHandle[NUM_HARDWARE_TIMERS];
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Function prototypes
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Private functions
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Public functions
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
bool timers_initialised[NUM_HARDWARE_TIMERS] = {false};
|
||||
|
||||
void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
|
||||
|
||||
if (!timers_initialised[timer_num]) {
|
||||
constexpr uint32_t step_prescaler = STEPPER_TIMER_PRESCALE - 1,
|
||||
temp_prescaler = TEMP_TIMER_PRESCALE - 1;
|
||||
switch (timer_num) {
|
||||
case STEP_TIMER_NUM:
|
||||
// STEPPER TIMER - use a 32bit timer if possible
|
||||
TimerHandle[timer_num].timer = STEP_TIMER_DEV;
|
||||
TimerHandle[timer_num].irqHandle = Step_Handler;
|
||||
TimerHandleInit(&TimerHandle[timer_num], (((HAL_TIMER_RATE) / step_prescaler) / frequency) - 1, step_prescaler);
|
||||
HAL_NVIC_SetPriority(STEP_TIMER_IRQ_NAME, 6, 0);
|
||||
break;
|
||||
|
||||
case TEMP_TIMER_NUM:
|
||||
// TEMP TIMER - any available 16bit Timer
|
||||
TimerHandle[timer_num].timer = TEMP_TIMER_DEV;
|
||||
TimerHandle[timer_num].irqHandle = Temp_Handler;
|
||||
TimerHandleInit(&TimerHandle[timer_num], (((HAL_TIMER_RATE) / temp_prescaler) / frequency) - 1, temp_prescaler);
|
||||
HAL_NVIC_SetPriority(TEMP_TIMER_IRQ_NAME, 2, 0);
|
||||
break;
|
||||
}
|
||||
timers_initialised[timer_num] = true;
|
||||
}
|
||||
}
|
||||
|
||||
void HAL_timer_enable_interrupt(const uint8_t timer_num) {
|
||||
const IRQn_Type IRQ_Id = IRQn_Type(getTimerIrq(TimerHandle[timer_num].timer));
|
||||
HAL_NVIC_EnableIRQ(IRQ_Id);
|
||||
}
|
||||
|
||||
void HAL_timer_disable_interrupt(const uint8_t timer_num) {
|
||||
const IRQn_Type IRQ_Id = IRQn_Type(getTimerIrq(TimerHandle[timer_num].timer));
|
||||
HAL_NVIC_DisableIRQ(IRQ_Id);
|
||||
|
||||
// We NEED memory barriers to ensure Interrupts are actually disabled!
|
||||
// ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the )
|
||||
__DSB();
|
||||
__ISB();
|
||||
}
|
||||
|
||||
bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
|
||||
const uint32_t IRQ_Id = getTimerIrq(TimerHandle[timer_num].timer);
|
||||
return NVIC->ISER[IRQ_Id >> 5] & _BV32(IRQ_Id & 0x1F);
|
||||
}
|
||||
|
||||
#endif // ARDUINO_ARCH_STM32
|
168
Marlin/src/HAL/HAL_STM32/HAL_timers_STM32.h
Normal file
168
Marlin/src/HAL/HAL_STM32/HAL_timers_STM32.h
Normal file
|
@ -0,0 +1,168 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
*
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
|
||||
* Copyright (c) 2017 Victor Perez
|
||||
*
|
||||
* 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
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Includes
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Defines
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
#define FORCE_INLINE __attribute__((always_inline)) inline
|
||||
|
||||
#define hal_timer_t uint32_t // TODO: One is 16-bit, one 32-bit - does this need to be checked?
|
||||
#define HAL_TIMER_TYPE_MAX 0xFFFF
|
||||
|
||||
#ifdef STM32F0xx
|
||||
|
||||
#define HAL_TIMER_RATE (HAL_RCC_GetSysClockFreq()) // frequency of timer peripherals
|
||||
#define TEMP_TIMER_PRESCALE 666 // prescaler for setting temperature timer, 72Khz
|
||||
#define STEPPER_TIMER_PRESCALE 24 // prescaler for setting stepper timer, 2Mhz
|
||||
|
||||
#define STEP_TIMER 16
|
||||
#define TEMP_TIMER 17
|
||||
|
||||
#elif defined STM32F1xx
|
||||
|
||||
#define HAL_TIMER_RATE (HAL_RCC_GetPCLK2Freq()) // frequency of timer peripherals
|
||||
#define TEMP_TIMER_PRESCALE 1000 // prescaler for setting temperature timer, 72Khz
|
||||
#define STEPPER_TIMER_PRESCALE 36 // prescaler for setting stepper timer, 2Mhz.
|
||||
|
||||
#define STEP_TIMER 4
|
||||
#define TEMP_TIMER 2
|
||||
|
||||
#elif defined STM32F4xx
|
||||
|
||||
#define HAL_TIMER_RATE (HAL_RCC_GetPCLK2Freq()) // frequency of timer peripherals
|
||||
#define TEMP_TIMER_PRESCALE 2333 // prescaler for setting temperature timer, 72Khz
|
||||
#define STEPPER_TIMER_PRESCALE 84 // prescaler for setting stepper timer, 2Mhz
|
||||
|
||||
#define STEP_TIMER 4
|
||||
#define TEMP_TIMER 5
|
||||
|
||||
#elif defined STM32F7xx
|
||||
|
||||
#define HAL_TIMER_RATE (HAL_RCC_GetSysClockFreq()/2) // frequency of timer peripherals
|
||||
#define TEMP_TIMER_PRESCALE 1500 // prescaler for setting temperature timer, 72Khz
|
||||
#define STEPPER_TIMER_PRESCALE 54 // prescaler for setting stepper timer, 2Mhz.
|
||||
|
||||
#define STEP_TIMER 5
|
||||
#define TEMP_TIMER 7
|
||||
|
||||
#if MB(REMRAM_V1)
|
||||
#define STEP_TIMER 2
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
#define STEP_TIMER_NUM 0 // index of timer to use for stepper
|
||||
#define TEMP_TIMER_NUM 1 // index of timer to use for temperature
|
||||
#define PULSE_TIMER_NUM STEP_TIMER_NUM
|
||||
|
||||
#define STEPPER_TIMER_RATE (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) // frequency of stepper timer
|
||||
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs
|
||||
|
||||
#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency
|
||||
|
||||
#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 __TIMER_DEV(X) TIM##X
|
||||
#define _TIMER_DEV(X) __TIMER_DEV(X)
|
||||
#define STEP_TIMER_DEV _TIMER_DEV(STEP_TIMER)
|
||||
#define TEMP_TIMER_DEV _TIMER_DEV(TEMP_TIMER)
|
||||
|
||||
#define __TIMER_CALLBACK(X) TIM##X##_IRQHandler
|
||||
#define _TIMER_CALLBACK(X) __TIMER_CALLBACK(X)
|
||||
|
||||
#define STEP_TIMER_CALLBACK _TIMER_CALLBACK(STEP_TIMER)
|
||||
#define TEMP_TIMER_CALLBACK _TIMER_CALLBACK(TEMP_TIMER)
|
||||
|
||||
#define __TIMER_IRQ_NAME(X) TIM##X##_IRQn
|
||||
#define _TIMER_IRQ_NAME(X) __TIMER_IRQ_NAME(X)
|
||||
|
||||
#define STEP_TIMER_IRQ_NAME _TIMER_IRQ_NAME(STEP_TIMER)
|
||||
#define TEMP_TIMER_IRQ_NAME _TIMER_IRQ_NAME(TEMP_TIMER)
|
||||
|
||||
#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 STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM)
|
||||
#define TEMP_ISR_ENABLED() HAL_timer_interrupt_enabled(TEMP_TIMER_NUM)
|
||||
|
||||
extern void Step_Handler(stimer_t *htim);
|
||||
extern void Temp_Handler(stimer_t *htim);
|
||||
#define HAL_STEP_TIMER_ISR void Step_Handler(stimer_t *htim)
|
||||
#define HAL_TEMP_TIMER_ISR void Temp_Handler(stimer_t *htim)
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Types
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
typedef stimer_t stm32f4_timer_t;
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Public Variables
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
extern stm32f4_timer_t TimerHandle[];
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
// Public functions
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency);
|
||||
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);
|
||||
|
||||
FORCE_INLINE static uint32_t HAL_timer_get_count(const uint8_t timer_num) {
|
||||
return __HAL_TIM_GET_COUNTER(&TimerHandle[timer_num].handle);
|
||||
}
|
||||
|
||||
FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const uint32_t compare) {
|
||||
__HAL_TIM_SET_AUTORELOAD(&TimerHandle[timer_num].handle, compare);
|
||||
if (HAL_timer_get_count(timer_num) >= compare)
|
||||
TimerHandle[timer_num].handle.Instance->EGR |= TIM_EGR_UG; // Generate an immediate update interrupt
|
||||
}
|
||||
|
||||
FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) {
|
||||
return __HAL_TIM_GET_AUTORELOAD(&TimerHandle[timer_num].handle);
|
||||
}
|
||||
|
||||
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);
|
||||
}
|
||||
|
||||
#define HAL_timer_isr_prologue(TIMER_NUM)
|
||||
#define HAL_timer_isr_epilogue(TIMER_NUM)
|
11
Marlin/src/HAL/HAL_STM32/README.md
Normal file
11
Marlin/src/HAL/HAL_STM32/README.md
Normal file
|
@ -0,0 +1,11 @@
|
|||
# Generic STM32 HAL based on the stm32duino core
|
||||
|
||||
This HAL is intended to act as the generic STM32 HAL for all STM32 chips (The whole F, H and L family).
|
||||
|
||||
Currently it supports:
|
||||
* STM32F0xx
|
||||
* STM32F1xx
|
||||
* STM32F4xx
|
||||
* STM32F7xx
|
||||
|
||||
Targeting the official [Arduino STM32 Core](https://github.com/stm32duino/Arduino_Core_STM32).
|
71
Marlin/src/HAL/HAL_STM32/SanityCheck.h
Normal file
71
Marlin/src/HAL/HAL_STM32/SanityCheck.h
Normal file
|
@ -0,0 +1,71 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016, 2017 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
|
||||
|
||||
/**
|
||||
* Test Re-ARM specific 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
|
||||
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
#error "EMERGENCY_PARSER is not yet implemented for STM32. Disable EMERGENCY_PARSER to continue."
|
||||
#endif
|
59
Marlin/src/HAL/HAL_STM32/endstop_interrupts.h
Normal file
59
Marlin/src/HAL/HAL_STM32/endstop_interrupts.h
Normal file
|
@ -0,0 +1,59 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
* Copyright (C) 2017 Victor Perez
|
||||
*
|
||||
* 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 "../../module/endstops.h"
|
||||
|
||||
// One ISR for all EXT-Interrupts
|
||||
void endstop_ISR(void) { endstops.update(); }
|
||||
|
||||
void setup_endstop_interrupts(void) {
|
||||
#if HAS_X_MAX
|
||||
attachInterrupt(X_MAX_PIN, endstop_ISR, CHANGE);
|
||||
#endif
|
||||
#if HAS_X_MIN
|
||||
attachInterrupt(X_MIN_PIN, endstop_ISR, CHANGE);
|
||||
#endif
|
||||
#if HAS_Y_MAX
|
||||
attachInterrupt(Y_MAX_PIN, endstop_ISR, CHANGE);
|
||||
#endif
|
||||
#if HAS_Y_MIN
|
||||
attachInterrupt(Y_MIN_PIN, endstop_ISR, CHANGE);
|
||||
#endif
|
||||
#if HAS_Z_MAX
|
||||
attachInterrupt(Z_MAX_PIN, endstop_ISR, CHANGE);
|
||||
#endif
|
||||
#if HAS_Z_MIN
|
||||
attachInterrupt(Z_MIN_PIN, endstop_ISR, CHANGE);
|
||||
#endif
|
||||
#if HAS_Z2_MAX
|
||||
attachInterrupt(Z2_MAX_PIN, endstop_ISR, CHANGE);
|
||||
#endif
|
||||
#if HAS_Z2_MIN
|
||||
attachInterrupt(Z2_MIN_PIN, endstop_ISR, CHANGE);
|
||||
#endif
|
||||
#if HAS_Z_MIN_PROBE_PIN
|
||||
attachInterrupt(Z_MIN_PROBE_PIN, endstop_ISR, CHANGE);
|
||||
#endif
|
||||
}
|
||||
|
53
Marlin/src/HAL/HAL_STM32/fastio_STM32.h
Normal file
53
Marlin/src/HAL/HAL_STM32/fastio_STM32.h
Normal file
|
@ -0,0 +1,53 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
* Copyright (C) 2017 Victor Perez
|
||||
*
|
||||
* 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 interfaces for STM32F7
|
||||
* These use GPIO functions instead of Direct Port Manipulation, as on AVR.
|
||||
*/
|
||||
|
||||
#define _BV(b) (1 << (b))
|
||||
|
||||
#define USEABLE_HARDWARE_PWM(p) true
|
||||
|
||||
#define READ(IO) digitalRead(IO)
|
||||
#define WRITE(IO,V) digitalWrite(IO,V)
|
||||
#define WRITE_VAR(IO,V) WRITE(IO,V)
|
||||
|
||||
#define _GET_MODE(IO)
|
||||
#define _SET_MODE(IO,M) pinMode(IO, M)
|
||||
#define _SET_OUTPUT(IO) pinMode(IO, OUTPUT) /*!< Output Push Pull Mode & GPIO_NOPULL */
|
||||
|
||||
#define OUT_WRITE(IO,V) do{ _SET_OUTPUT(IO); WRITE(IO,V); }while(0)
|
||||
|
||||
#define SET_INPUT(IO) _SET_MODE(IO, INPUT) /*!< Input Floating Mode */
|
||||
#define SET_INPUT_PULLUP(IO) _SET_MODE(IO, INPUT_PULLUP) /*!< Input with Pull-up activation */
|
||||
#define SET_INPUT_PULLDOWN(IO) _SET_MODE(IO, INPUT_PULLDOWN) /*!< Input with Pull-down activation */
|
||||
#define SET_OUTPUT(IO) OUT_WRITE(IO, LOW)
|
||||
|
||||
#define TOGGLE(IO) OUT_WRITE(IO, !READ(IO))
|
||||
|
||||
#define GET_INPUT(IO)
|
||||
#define GET_OUTPUT(IO)
|
||||
#define GET_TIMER(IO)
|
103
Marlin/src/HAL/HAL_STM32/persistent_store_impl.cpp
Normal file
103
Marlin/src/HAL/HAL_STM32/persistent_store_impl.cpp
Normal file
|
@ -0,0 +1,103 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
*
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
|
||||
* Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
|
||||
* Copyright (c) 2016 Victor Perez victor_pv@hotmail.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 ARDUINO_ARCH_STM32
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#if ENABLED(EEPROM_SETTINGS)
|
||||
|
||||
#include "../shared/persistent_store_api.h"
|
||||
|
||||
#if DISABLED(EEPROM_EMULATED_WITH_SRAM)
|
||||
#include <EEPROM.h>
|
||||
static bool eeprom_data_written = false;
|
||||
#endif
|
||||
|
||||
bool PersistentStore::access_start() {
|
||||
#if DISABLED(EEPROM_EMULATED_WITH_SRAM)
|
||||
eeprom_buffer_fill();
|
||||
#endif
|
||||
return true;
|
||||
}
|
||||
|
||||
bool PersistentStore::access_finish() {
|
||||
#if DISABLED(EEPROM_EMULATED_WITH_SRAM)
|
||||
if (eeprom_data_written) {
|
||||
eeprom_buffer_flush();
|
||||
eeprom_data_written = false;
|
||||
}
|
||||
#endif
|
||||
return true;
|
||||
}
|
||||
|
||||
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
|
||||
while (size--) {
|
||||
uint8_t v = *value;
|
||||
|
||||
// Save to either program flash or Backup SRAM
|
||||
#if DISABLED(EEPROM_EMULATED_WITH_SRAM)
|
||||
eeprom_buffered_write_byte(pos, v);
|
||||
#else
|
||||
*(__IO uint8_t *)(BKPSRAM_BASE + (uint8_t * const)pos) = v;
|
||||
#endif
|
||||
|
||||
crc16(crc, &v, 1);
|
||||
pos++;
|
||||
value++;
|
||||
};
|
||||
#if DISABLED(EEPROM_EMULATED_WITH_SRAM)
|
||||
eeprom_data_written = true;
|
||||
#endif
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing) {
|
||||
do {
|
||||
// Read from either program flash or Backup SRAM
|
||||
const uint8_t c = (
|
||||
#if DISABLED(EEPROM_EMULATED_WITH_SRAM)
|
||||
eeprom_buffered_read_byte(pos)
|
||||
#else
|
||||
(*(__IO uint8_t *)(BKPSRAM_BASE + ((unsigned char*)pos)))
|
||||
#endif
|
||||
);
|
||||
|
||||
if (writing) *value = c;
|
||||
crc16(crc, &c, 1);
|
||||
pos++;
|
||||
value++;
|
||||
} while (--size);
|
||||
return false;
|
||||
}
|
||||
|
||||
size_t PersistentStore::capacity() {
|
||||
#if DISABLED(EEPROM_EMULATED_WITH_SRAM)
|
||||
return E2END + 1;
|
||||
#else
|
||||
return 4096; // 4kB
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif // EEPROM_SETTINGS
|
||||
#endif // ARDUINO_ARCH_STM32
|
1
Marlin/src/HAL/HAL_STM32/pinsDebug.h
Normal file
1
Marlin/src/HAL/HAL_STM32/pinsDebug.h
Normal file
|
@ -0,0 +1 @@
|
|||
#error "Debug pins is not yet supported for STM32!"
|
36
Marlin/src/HAL/HAL_STM32/spi_pins.h
Normal file
36
Marlin/src/HAL/HAL_STM32/spi_pins.h
Normal file
|
@ -0,0 +1,36 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 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/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* Define SPI Pins: SCK, MISO, MOSI, SS
|
||||
*
|
||||
*/
|
||||
#ifndef SCK_PIN
|
||||
#define SCK_PIN 13
|
||||
#endif
|
||||
#ifndef MISO_PIN
|
||||
#define MISO_PIN 12
|
||||
#endif
|
||||
#ifndef MOSI_PIN
|
||||
#define MOSI_PIN 11
|
||||
#endif
|
||||
#ifndef SS_PIN
|
||||
#define SS_PIN 14
|
||||
#endif
|
37
Marlin/src/HAL/HAL_STM32/watchdog_STM32.cpp
Normal file
37
Marlin/src/HAL/HAL_STM32/watchdog_STM32.cpp
Normal file
|
@ -0,0 +1,37 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifdef ARDUINO_ARCH_STM32
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#if ENABLED(USE_WATCHDOG)
|
||||
|
||||
#include "watchdog_STM32.h"
|
||||
#include <IWatchdog.h>
|
||||
|
||||
void watchdog_init() { IWatchdog.begin(4000000); } // 4 sec timeout
|
||||
|
||||
void watchdog_reset() { IWatchdog.reload(); }
|
||||
|
||||
#endif // USE_WATCHDOG
|
||||
#endif // ARDUINO_ARCH_STM32
|
27
Marlin/src/HAL/HAL_STM32/watchdog_STM32.h
Normal file
27
Marlin/src/HAL/HAL_STM32/watchdog_STM32.h
Normal file
|
@ -0,0 +1,27 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
void watchdog_init();
|
||||
void watchdog_reset();
|
|
@ -15,10 +15,12 @@
|
|||
#define HAL_PLATFORM HAL_LPC1768
|
||||
#elif defined(__STM32F1__) || defined(TARGET_STM32F1)
|
||||
#define HAL_PLATFORM HAL_STM32F1
|
||||
#elif defined(STM32F4) || defined(STM32F4xx)
|
||||
#elif defined(STM32GENERIC) && defined(STM32F4)
|
||||
#define HAL_PLATFORM HAL_STM32F4
|
||||
#elif defined(STM32F7)
|
||||
#elif defined(STM32GENERIC) && defined(STM32F7)
|
||||
#define HAL_PLATFORM HAL_STM32F7
|
||||
#elif defined(ARDUINO_ARCH_STM32)
|
||||
#define HAL_PLATFORM HAL_STM32
|
||||
#elif defined(ARDUINO_ARCH_ESP32)
|
||||
#define HAL_PLATFORM HAL_ESP32
|
||||
#else
|
||||
|
|
|
@ -15,6 +15,7 @@
|
|||
#if defined(__arm__) || defined(__thumb__)
|
||||
|
||||
#include "unwmemaccess.h"
|
||||
#include "../../../inc/MarlinConfig.h"
|
||||
|
||||
/* Validate address */
|
||||
|
||||
|
@ -73,7 +74,7 @@
|
|||
#define END_FLASH_ADDR 0x08080000
|
||||
#endif
|
||||
|
||||
#ifdef STM32F7
|
||||
#if MB(THE_BORG)
|
||||
// For STM32F765 in BORG
|
||||
// SRAM (0x20000000 - 0x20080000) (512kb)
|
||||
// FLASH (0x08000000 - 0x08100000) (1024kb)
|
||||
|
@ -84,6 +85,17 @@
|
|||
#define END_FLASH_ADDR 0x08100000
|
||||
#endif
|
||||
|
||||
#if MB(REMRAM_V1)
|
||||
// For STM32F765VI in RemRam v1
|
||||
// SRAM (0x20000000 - 0x20080000) (512kb)
|
||||
// FLASH (0x08000000 - 0x08200000) (2048kb)
|
||||
//
|
||||
#define START_SRAM_ADDR 0x20000000
|
||||
#define END_SRAM_ADDR 0x20080000
|
||||
#define START_FLASH_ADDR 0x08000000
|
||||
#define END_FLASH_ADDR 0x08200000
|
||||
#endif
|
||||
|
||||
#ifdef __MK20DX256__
|
||||
// For MK20DX256 in TEENSY 3.1 or TEENSY 3.2
|
||||
// SRAM (0x1FFF8000 - 0x20008000) (64kb)
|
||||
|
|
|
@ -53,7 +53,7 @@
|
|||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#if HAS_SERVOS && !(IS_32BIT_TEENSY || defined(TARGET_LPC1768) || defined(STM32F1) || defined(STM32F1xx) || defined(STM32F4) || defined(STM32F4xx))
|
||||
#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"
|
||||
|
|
|
@ -74,10 +74,12 @@
|
|||
#include "../HAL_TEENSY35_36/HAL_Servo_Teensy.h"
|
||||
#elif defined(TARGET_LPC1768)
|
||||
#include "../HAL_LPC1768/LPC1768_Servo.h"
|
||||
#elif defined(STM32F1) || defined(STM32F1xx)
|
||||
#elif defined(__STM32F1__) || defined(TARGET_STM32F1)
|
||||
#include "../HAL_STM32F1/HAL_Servo_STM32F1.h"
|
||||
#elif defined(STM32F4) || defined(STM32F4xx)
|
||||
#elif defined(STM32GENERIC) && defined(STM32F4)
|
||||
#include "../HAL_STM32F4/HAL_Servo_STM32F4.h"
|
||||
#elif defined(ARDUINO_ARCH_STM32)
|
||||
#include "../HAL_STM32/HAL_Servo_STM32.h"
|
||||
#else
|
||||
#include <stdint.h>
|
||||
|
||||
|
|
|
@ -236,6 +236,7 @@
|
|||
//
|
||||
|
||||
#define BOARD_THE_BORG 1860 // THE-BORG (Power outputs: Hotend0, Hotend1, Bed, Fan)
|
||||
#define BOARD_REMRAM_V1 1862 // RemRam v1
|
||||
|
||||
//
|
||||
// Espressif ESP32 WiFi
|
||||
|
|
|
@ -72,6 +72,10 @@
|
|||
#define CPU_ST7920_DELAY_1 DELAY_NS(0)
|
||||
#define CPU_ST7920_DELAY_2 DELAY_NS(0)
|
||||
#define CPU_ST7920_DELAY_3 DELAY_NS(189)
|
||||
#elif MB(REMRAM_V1)
|
||||
#define CPU_ST7920_DELAY_1 DELAY_NS(0)
|
||||
#define CPU_ST7920_DELAY_2 DELAY_NS(0)
|
||||
#define CPU_ST7920_DELAY_3 DELAY_NS(0)
|
||||
#elif F_CPU == 16000000
|
||||
#define CPU_ST7920_DELAY_1 DELAY_NS(0)
|
||||
#define CPU_ST7920_DELAY_2 DELAY_NS(0)
|
||||
|
|
|
@ -404,6 +404,8 @@
|
|||
|
||||
#elif MB(THE_BORG)
|
||||
#include "pins_THE_BORG.h" // STM32F7 env:STM32F7
|
||||
#elif MB(REMRAM_V1)
|
||||
#include "pins_REMRAM_V1.h" // STM32F7 env:STM32F7xx
|
||||
|
||||
//
|
||||
// Espressif ESP32
|
||||
|
|
126
Marlin/src/pins/pins_REMRAM_V1.h
Normal file
126
Marlin/src/pins/pins_REMRAM_V1.h
Normal file
|
@ -0,0 +1,126 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef STM32F7xx
|
||||
#error "Oops! Make sure you have an STM32F7 board selected from the 'Tools -> Boards' menu."
|
||||
#endif
|
||||
|
||||
#define DEFAULT_MACHINE_NAME "RemRam"
|
||||
#define BOARD_NAME "RemRam v1"
|
||||
|
||||
#define EEPROM_EMULATED_WITH_SRAM // Emulate the EEPROM using Backup SRAM
|
||||
|
||||
#if E_STEPPERS > 1 || HOTENDS > 1
|
||||
#error "RemRam supports only one hotend / E-stepper."
|
||||
#endif
|
||||
|
||||
//
|
||||
// Limit Switches
|
||||
//
|
||||
#if DISABLED(SENSORLESS_HOMING)
|
||||
#define X_MIN_PIN 58
|
||||
#define X_MAX_PIN 59
|
||||
#define Y_MIN_PIN 60
|
||||
#define Y_MAX_PIN 61
|
||||
#define Z_MIN_PIN 62
|
||||
#define Z_MAX_PIN 63
|
||||
#else
|
||||
#define X_STOP_PIN 36
|
||||
#define Y_STOP_PIN 39
|
||||
#define Z_MIN_PIN 62
|
||||
#define Z_MAX_PIN 42
|
||||
#endif
|
||||
|
||||
//
|
||||
// Z Probe (when not Z_MIN_PIN)
|
||||
//
|
||||
#ifndef Z_MIN_PROBE_PIN
|
||||
#define Z_MIN_PROBE_PIN 26 // EXT_D1
|
||||
#endif
|
||||
|
||||
//
|
||||
// Steppers
|
||||
//
|
||||
#define X_STEP_PIN 22
|
||||
#define X_DIR_PIN 35
|
||||
#define X_ENABLE_PIN 34
|
||||
#define X_CS_PIN 14
|
||||
|
||||
#define Y_STEP_PIN 23
|
||||
#define Y_DIR_PIN 38
|
||||
#define Y_ENABLE_PIN 37
|
||||
#define Y_CS_PIN 15
|
||||
|
||||
#define Z_STEP_PIN 24
|
||||
#define Z_DIR_PIN 41
|
||||
#define Z_ENABLE_PIN 40
|
||||
#define Z_CS_PIN 16
|
||||
|
||||
#define E0_STEP_PIN 25
|
||||
#define E0_DIR_PIN 44
|
||||
#define E0_ENABLE_PIN 43
|
||||
#define E0_CS_PIN 10
|
||||
|
||||
//
|
||||
// Temperature Sensors
|
||||
//
|
||||
#define TEMP_0_PIN 65 // THERM_2
|
||||
#define TEMP_1_PIN 66 // THERM_3
|
||||
#define TEMP_BED_PIN 64 // THERM_1
|
||||
|
||||
//
|
||||
// Heaters / Fans
|
||||
//
|
||||
#define HEATER_0_PIN 33
|
||||
#define HEATER_BED_PIN 31
|
||||
|
||||
#ifndef FAN_PIN
|
||||
#define FAN_PIN 30 // "FAN1"
|
||||
#endif
|
||||
#define FAN1_PIN 32 // "FAN2"
|
||||
|
||||
#define ORIG_E0_AUTO_FAN_PIN 32 // Use this by NOT overriding E0_AUTO_FAN_PIN
|
||||
|
||||
//
|
||||
// Servos
|
||||
//
|
||||
#define SERVO0_PIN 26 // PWM_EXT1
|
||||
#define SERVO1_PIN 27 // PWM_EXT2
|
||||
|
||||
#define SDSS 9
|
||||
#define LED_PIN 21 // STATUS_LED
|
||||
#define KILL_PIN 57
|
||||
|
||||
//
|
||||
// LCD / Controller
|
||||
//
|
||||
#define SD_DETECT_PIN 56 // SD_CARD_DET
|
||||
#define BEEPER_PIN 46 // LCD_BEEPER
|
||||
#define LCD_PINS_RS 49 // LCD_RS
|
||||
#define LCD_PINS_ENABLE 48 // LCD_EN
|
||||
#define LCD_PINS_D4 50 // LCD_D4
|
||||
#define LCD_PINS_D5 51 // LCD_D5
|
||||
#define LCD_PINS_D6 52 // LCD_D6
|
||||
#define LCD_PINS_D7 53 // LCD_D7
|
||||
#define BTN_EN1 54 // BTN_EN1
|
||||
#define BTN_EN2 55 // BTN_EN2
|
||||
#define BTN_ENC 47 // BTN_ENC
|
Loading…
Reference in a new issue