STM32F1 HAL

Adding files for STM32F1 HAL based on libmaple/stm32duino core.
Current persistent_store uses cardreader changes to be sent in separate
commit, but could be changed to use i2c eeprom.
This commit is contained in:
victorpv 2017-09-27 00:30:23 -05:00 committed by Scott Lahteine
parent baf0bd2b24
commit e9acb63290
23 changed files with 3349 additions and 2 deletions

View File

@ -91,6 +91,10 @@ void spiSendBlock(uint8_t token, const uint8_t* buf);
#define CPU_32_BIT
#include "math_32bit.h"
#include "HAL_LPC1768/HAL.h"
#elif defined(__STM32F1__)
#define CPU_32_BIT
#include "math_32bit.h"
#include "HAL_STM32F1/HAL_Stm32f1.h"
#else
#error "Unsupported Platform!"
#endif

View File

@ -0,0 +1,52 @@
/**
* 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 __STM32F1__
#include "../../../src/inc/MarlinConfig.h"
#if HAS_SERVOS
#include "HAL_Servo_Stm32f1.h"
int8_t libServo::attach(const int pin) {
if (this->servoIndex >= MAX_SERVOS) return -1;
return Servo::attach(pin);
}
int8_t libServo::attach(const int pin, const int min, const int max) {
return Servo::attach(pin, min, max);
}
void libServo::move(const int value) {
if (this->attach(0) >= 0) {
this->write(value);
delay(SERVO_DELAY);
#if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE)
this->detach();
#endif
}
}
#endif // HAS_SERVOS
#endif // __STM32F1__

View File

@ -0,0 +1,41 @@
/**
* 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/>.
*
*/
#ifndef HAL_SERVO_STM32F1_H
#define HAL_SERVO_STM32F1_H
#include <../../libraries/Servo/src/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;
uint16_t max_ticks;
uint8_t servoIndex; // index into the channel data for this servo
};
#endif // HAL_SERVO_STM32F1_H

View File

@ -0,0 +1,138 @@
/**
* 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/>.
*
*/
/**
* HAL for stm32duino.com based on Libmaple and compatible (STM32F1)
*/
#ifdef __STM32F1__
// --------------------------------------------------------------------------
// Includes
// --------------------------------------------------------------------------
#include "../HAL.h"
//#include <Wire.h>
// --------------------------------------------------------------------------
// Externals
// --------------------------------------------------------------------------
// --------------------------------------------------------------------------
// Local defines
// --------------------------------------------------------------------------
// --------------------------------------------------------------------------
// Types
// --------------------------------------------------------------------------
// --------------------------------------------------------------------------
// Variables
// --------------------------------------------------------------------------
// --------------------------------------------------------------------------
// Public Variables
// --------------------------------------------------------------------------
uint16_t HAL_adc_result;
// --------------------------------------------------------------------------
// Private Variables
// --------------------------------------------------------------------------
// --------------------------------------------------------------------------
// Function prototypes
// --------------------------------------------------------------------------
// --------------------------------------------------------------------------
// Private functions
// --------------------------------------------------------------------------
// --------------------------------------------------------------------------
// Public functions
// --------------------------------------------------------------------------
/* VGPV Done with defines
// disable interrupts
void cli(void) { noInterrupts(); }
// enable interrupts
void sei(void) { interrupts(); }
*/
void HAL_clear_reset_source(void) { }
/**
* TODO: Check this and change or remove.
* currently returns 1 that's equal to poweron reset.
*/
uint8_t HAL_get_reset_source(void) { return 1; }
void _delay_ms(const int delay_ms) { delay(delay_ms); }
extern "C" {
extern unsigned int _ebss; // end of bss section
}
/**
* TODO: Change this to correct it for libmaple
*/
// return free memory between end of heap (or end bss) and whatever is current
/*
#include "wirish/syscalls.c"
//extern caddr_t _sbrk(int incr);
#ifndef CONFIG_HEAP_END
extern char _lm_heap_end;
#define CONFIG_HEAP_END ((caddr_t)&_lm_heap_end)
#endif
extern "C" {
static int freeMemory() {
char top = 't';
return &top - reinterpret_cast<char*>(sbrk(0));
}
int freeMemory() {
int free_memory;
int heap_end = (int)_sbrk(0);
free_memory = ((int)&free_memory) - ((int)heap_end);
return free_memory;
}
}
*/
// --------------------------------------------------------------------------
// ADC
// --------------------------------------------------------------------------
void HAL_adc_start_conversion(const uint8_t adc_pin) {
HAL_adc_result = (analogRead(adc_pin) >> 2) & 0x3ff; // shift to get 10 bits only.
}
uint16_t HAL_adc_get_result(void) {
return HAL_adc_result;
}
#endif // __STM32F1__

View File

@ -0,0 +1,195 @@
/**
* 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/>.
*
*/
/**
* HAL for stm32duino.com based on Libmaple and compatible (STM32F1)
*/
#ifndef _HAL_STM32F1_H
#define _HAL_STM32F1_H
#undef DEBUG_NONE
#ifndef vsnprintf_P
#define vsnprintf_P vsnprintf
#endif
// --------------------------------------------------------------------------
// Includes
// --------------------------------------------------------------------------
#include <stdint.h>
#include "Arduino.h"
#include "fastio_Stm32f1.h"
#include "watchdog_Stm32f1.h"
#include "HAL_timers_Stm32f1.h"
// --------------------------------------------------------------------------
// Defines
// --------------------------------------------------------------------------
#if SERIAL_PORT == -1
#define MYSERIAL SerialUSB
#elif SERIAL_PORT == 0
#define MYSERIAL Serial
#elif SERIAL_PORT == 1
#define MYSERIAL Serial1
#elif SERIAL_PORT == 2
#define MYSERIAL Serial2
#elif SERIAL_PORT == 3
#define MYSERIAL Serial3
#endif
#define _BV(bit) (1 << (bit))
/**
* TODO: review this to return 1 for pins that are not analog input
*/
#ifndef analogInputToDigitalPin
#define analogInputToDigitalPin(p) (p)
#endif
#define CRITICAL_SECTION_START noInterrupts();
#define CRITICAL_SECTION_END interrupts();
// 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
// --------------------------------------------------------------------------
// --------------------------------------------------------------------------
// Public Variables
// --------------------------------------------------------------------------
/** result of last ADC conversion */
extern uint16_t HAL_adc_result;
// --------------------------------------------------------------------------
// Public functions
// --------------------------------------------------------------------------
// Disable interrupts
#define cli() noInterrupts()
// Enable interrupts
#define sei() interrupts()
// Memory related
#define __bss_end __bss_end__
/** 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" {
int freeMemory(void);
}
*/
extern "C" char* _sbrk(int incr);
/*
static int freeMemory() {
volatile int top;
top = (int)((char*)&top - reinterpret_cast<char*>(_sbrk(0)));
return top;
}
*/
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
/**
* TODO: Write all this eeprom stuff. Can emulate eeprom in flash as last resort.
* 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_ANALOG);
inline void HAL_adc_init(void) {}
#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
#define HAL_READ_ADC HAL_adc_result
void HAL_adc_start_conversion(const uint8_t adc_pin);
uint16_t HAL_adc_get_result(void);
/* Todo: Confirm none of this is needed.
uint16_t HAL_getAdcReading(uint8_t chan);
void HAL_startAdcConversion(uint8_t chan);
uint8_t HAL_pinToAdcChannel(int pin);
uint16_t HAL_getAdcFreerun(uint8_t chan, bool wait_for_conversion = false);
//uint16_t HAL_getAdcSuperSample(uint8_t chan);
void HAL_enable_AdcFreerun(void);
//void HAL_disable_AdcFreerun(uint8_t chan);
*/
#endif // _HAL_STM32F1_H

View File

@ -0,0 +1,169 @@
/**
* 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/>.
*
*/
/**
* Software SPI functions originally from Arduino Sd2Card Library
* Copyright (C) 2009 by William Greiman
*/
/**
* Adapted to the STM32F1 HAL
*/
#ifdef __STM32F1__
// --------------------------------------------------------------------------
// Includes
// --------------------------------------------------------------------------
#include "../HAL.h"
#include "SPI.h"
#include "pins_arduino.h"
#include "spi_pins.h"
#include "../../core/macros.h"
// --------------------------------------------------------------------------
// Public Variables
// --------------------------------------------------------------------------
static SPISettings spiConfig;
// --------------------------------------------------------------------------
// Public functions
// --------------------------------------------------------------------------
#if ENABLED(SOFTWARE_SPI)
// --------------------------------------------------------------------------
// Software SPI
// --------------------------------------------------------------------------
#error "Software SPI not supported for STM32F1. Use hardware SPI."
#else
// --------------------------------------------------------------------------
// Hardware SPI
// --------------------------------------------------------------------------
/**
* VGPV SPI speed start and F_CPU/2, by default 72/2 = 36Mhz
*/
/**
* @brief Begin SPI port setup
*
* @return Nothing
*
* @details Only configures SS pin since libmaple creates and initialize the SPI object
*/
void spiBegin() {
#ifndef SS_PIN
#error "SS_PIN not defined!"
#endif
SET_OUTPUT(SS_PIN);
WRITE(SS_PIN, HIGH);
}
/**
* @brief Initializes SPI port to required speed rate and transfer mode (MSB, SPI MODE 0)
*
* @param spiRate Rate as declared in HAL.h (speed do not match AVR)
* @return Nothing
*
* @details
*/
void spiInit(uint8_t spiRate) {
uint8_t clock;
switch (spiRate) {
case SPI_FULL_SPEED: clock = SPI_CLOCK_DIV2 ; break;
case SPI_HALF_SPEED: clock = SPI_CLOCK_DIV4 ; break;
case SPI_QUARTER_SPEED: clock = SPI_CLOCK_DIV8 ; break;
case SPI_EIGHTH_SPEED: clock = SPI_CLOCK_DIV16; break;
case SPI_SPEED_5: clock = SPI_CLOCK_DIV32; break;
case SPI_SPEED_6: clock = SPI_CLOCK_DIV64; break;
default:
clock = SPI_CLOCK_DIV2; // 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) {
SPI.beginTransaction(spiConfig);
SPI.dmaTransfer(0, const_cast<uint8*>(buf), nbyte);
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.send(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.send(token);
SPI.dmaSend(const_cast<uint8*>(buf), 512);
SPI.endTransaction();
}
#endif // SOFTWARE_SPI
#endif // __STM32F1__

View File

@ -0,0 +1,145 @@
/**
* 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/>.
*
*/
/**
* HAL for stm32duino.com based on Libmaple and compatible (STM32F1)
*/
#ifdef __STM32F1__
// --------------------------------------------------------------------------
// Includes
// --------------------------------------------------------------------------
#include "../HAL.h"
#include "HAL_timers_Stm32f1.h"
// --------------------------------------------------------------------------
// Externals
// --------------------------------------------------------------------------
// --------------------------------------------------------------------------
// Local defines
// --------------------------------------------------------------------------
#define NUM_HARDWARE_TIMERS 4
//#define PRESCALER 1
// --------------------------------------------------------------------------
// Types
// --------------------------------------------------------------------------
// --------------------------------------------------------------------------
// Public Variables
// --------------------------------------------------------------------------
// --------------------------------------------------------------------------
// Private Variables
// --------------------------------------------------------------------------
/* VGPV
const tTimerConfig TimerConfig [NUM_HARDWARE_TIMERS] = {
{ TC0, 0, TC0_IRQn, 0}, // 0 - [servo timer5]
{ TC0, 1, TC1_IRQn, 0}, // 1
{ TC0, 2, TC2_IRQn, 0}, // 2
{ TC1, 0, TC3_IRQn, 2}, // 3 - stepper
{ TC1, 1, TC4_IRQn, 15}, // 4 - temperature
{ TC1, 2, TC5_IRQn, 0}, // 5 - [servo timer3]
{ TC2, 0, TC6_IRQn, 0}, // 6
{ TC2, 1, TC7_IRQn, 0}, // 7
{ TC2, 2, TC8_IRQn, 0}, // 8
};
*/
// --------------------------------------------------------------------------
// Function prototypes
// --------------------------------------------------------------------------
// --------------------------------------------------------------------------
// Private functions
// --------------------------------------------------------------------------
// --------------------------------------------------------------------------
// Public functions
// --------------------------------------------------------------------------
/*
Timer_clock1: Prescaler 2 -> 42MHz
Timer_clock2: Prescaler 8 -> 10.5MHz
Timer_clock3: Prescaler 32 -> 2.625MHz
Timer_clock4: Prescaler 128 -> 656.25kHz
*/
/**
* TODO: Calculate Timer prescale value, so we get the 32bit to adjust
*/
void HAL_timer_start (uint8_t timer_num, uint32_t frequency) {
switch (timer_num) {
case STEP_TIMER_NUM:
StepperTimer.pause();
StepperTimer.setCount(0);
StepperTimer.setPrescaleFactor(STEPPER_TIMER_PRESCALE);
StepperTimer.setOverflow(0xFFFF);
StepperTimer.setCompare (STEP_TIMER_CHAN, (HAL_STEPPER_TIMER_RATE / frequency));
StepperTimer.refresh();
StepperTimer.resume();
break;
case TEMP_TIMER_NUM:
TempTimer.pause();
TempTimer.setCount(0);
TempTimer.setPrescaleFactor(TEMP_TIMER_PRESCALE);
TempTimer.setOverflow(0xFFFF);
TempTimer.setCompare (TEMP_TIMER_CHAN, ((F_CPU / TEMP_TIMER_PRESCALE) / frequency));
TempTimer.refresh();
TempTimer.resume();
break;
}
}
void HAL_timer_enable_interrupt (uint8_t timer_num) {
switch (timer_num) {
case STEP_TIMER_NUM:
StepperTimer.attachInterrupt(STEP_TIMER_CHAN, stepTC_Handler);
break;
case TEMP_TIMER_NUM:
TempTimer.attachInterrupt(STEP_TIMER_CHAN, tempTC_Handler);
break;
default:
break;
}
}
void HAL_timer_disable_interrupt (uint8_t timer_num) {
switch (timer_num) {
case STEP_TIMER_NUM:
StepperTimer.detachInterrupt(STEP_TIMER_CHAN);
break;
case TEMP_TIMER_NUM:
TempTimer.detachInterrupt(STEP_TIMER_CHAN);
break;
default:
break;
}
}
#endif // __STM32F1__

View File

@ -0,0 +1,183 @@
/**
* 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/>.
*
*/
/**
* HAL for stm32duino.com based on Libmaple and compatible (STM32F1)
*/
#ifndef _HAL_TIMERS_STM32F1_H
#define _HAL_TIMERS_STM32F1_H
// --------------------------------------------------------------------------
// Includes
// --------------------------------------------------------------------------
#include <stdint.h>
// --------------------------------------------------------------------------
// Defines
// --------------------------------------------------------------------------
/**
* TODO: Check and confirm what timer we will use for each Temps and stepper driving.
* We should probable drive temps with PWM.
*/
#define FORCE_INLINE __attribute__((always_inline)) inline
#define HAL_TIMER_TYPE uint16_t
#define HAL_TIMER_TYPE_MAX 0xFFFF
#define STEP_TIMER_NUM 5 // index of timer to use for stepper
#define STEP_TIMER_CHAN 1 // Channel of the timer to use for compare and interrupts
#define TEMP_TIMER_NUM 2 // index of timer to use for temperature
#define TEMP_TIMER_CHAN 1 // Channel of the timer to use for compare and interrupts
#define HAL_TIMER_RATE (F_CPU) // frequency of timers peripherals
#define STEPPER_TIMER_PRESCALE 36 // prescaler for setting stepper timer, 2Mhz
#define HAL_STEPPER_TIMER_RATE (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) // frequency of stepper timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE)
#define HAL_TICKS_PER_US ((HAL_STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per us
#define TEMP_TIMER_PRESCALE 1000 // prescaler for setting Temp timer, 72Khz
#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency
#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 ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt (TEMP_TIMER_NUM)
#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt (TEMP_TIMER_NUM)
#define HAL_ENABLE_ISRs() do { if (thermalManager.in_temp_isr)DISABLE_TEMPERATURE_INTERRUPT(); else ENABLE_TEMPERATURE_INTERRUPT(); ENABLE_STEPPER_DRIVER_INTERRUPT(); } while(0)
// TODO change this
#define HAL_TEMP_TIMER_ISR extern "C" void tempTC_Handler(void)
#define HAL_STEP_TIMER_ISR extern "C" void stepTC_Handler(void)
extern "C" void tempTC_Handler(void);
extern "C" void stepTC_Handler(void);
// --------------------------------------------------------------------------
// Types
// --------------------------------------------------------------------------
// --------------------------------------------------------------------------
// Public Variables
// --------------------------------------------------------------------------
static HardwareTimer StepperTimer(STEP_TIMER_NUM);
static HardwareTimer TempTimer(TEMP_TIMER_NUM);
// --------------------------------------------------------------------------
// Public functions
// --------------------------------------------------------------------------
void HAL_timer_start (uint8_t timer_num, uint32_t frequency);
void HAL_timer_enable_interrupt(uint8_t timer_num);
void HAL_timer_disable_interrupt(uint8_t timer_num);
/**
* NOTE: By default libmaple sets ARPE = 1, which means the Auto reload register is preloaded (will only update with an update event)
* Thus we have to pause the timer, update the value, refresh, resume the timer.
* That seems like a big waste of time and may be better to change the timer config to ARPE = 0, so ARR can be updated any time.
* We are using a Channel in each timer in Capture/Compare mode. We could also instead use the Time Update Event Interrupt, but need to disable ARPE
* so we can change the ARR value on the fly (without calling refresh), and not get an interrupt right there because we caused an UEV.
* This mode pretty much makes 2 timers unusable for PWM since they have their counts updated all the time on ISRs.
* The way Marlin manages timer interrupts doesn't make for an efficient usage in STM32F1
* Todo: Look at that possibility later.
*/
static FORCE_INLINE void HAL_timer_set_count (uint8_t timer_num, uint32_t count) {
switch (timer_num) {
case STEP_TIMER_NUM:
StepperTimer.pause();
StepperTimer.setCompare (STEP_TIMER_CHAN, count);
StepperTimer.refresh ();
StepperTimer.resume ();
break;
case TEMP_TIMER_NUM:
TempTimer.pause();
TempTimer.setCompare (TEMP_TIMER_CHAN, count);
TempTimer.refresh ();
TempTimer.resume ();
break;
default:
break;
}
}
static FORCE_INLINE HAL_TIMER_TYPE HAL_timer_get_count (uint8_t timer_num) {
HAL_TIMER_TYPE temp;
switch (timer_num) {
case STEP_TIMER_NUM:
temp = StepperTimer.getCompare(STEP_TIMER_CHAN);
break;
case TEMP_TIMER_NUM:
temp = TempTimer.getCompare(TEMP_TIMER_CHAN);
break;
default:
temp = 0;
break;
}
return temp;
}
static FORCE_INLINE HAL_TIMER_TYPE HAL_timer_get_current_count(uint8_t timer_num) {
HAL_TIMER_TYPE temp;
switch (timer_num) {
case STEP_TIMER_NUM:
temp = StepperTimer.getCount();
break;
case TEMP_TIMER_NUM:
temp = TempTimer.getCount();
break;
default:
temp = 0;
break;
}
return temp;
}
//void HAL_timer_isr_prologue (uint8_t timer_num);
static FORCE_INLINE void HAL_timer_isr_prologue(uint8_t timer_num) {
switch (timer_num) {
case STEP_TIMER_NUM:
StepperTimer.pause();
StepperTimer.setCount(0);
StepperTimer.refresh();
StepperTimer.resume();
break;
case TEMP_TIMER_NUM:
TempTimer.pause();
TempTimer.setCount(0);
TempTimer.refresh();
TempTimer.resume();
break;
default:
break;
}
}
#endif // _HAL_TIMERS_STM32F1_H

View File

@ -0,0 +1,32 @@
# This HAL is for STM32F103 boards used with libmaple/stm32duino Arduino core.
# This HAL is in development and has not been tested with an actual printer.
### The stm32 core needs a modification in the file util.h to avoid conflict with Marlin macros for Debug.
Since only 1 file needs change in the stm32duino core, it's preferable over making changes to Marlin.
After these lines:
<>
#else
#define ASSERT_FAULT(exp) (void)((0))
#endif
<>
Add the following 3 lines:
<>
#undef DEBUG_NONE
#undef DEBUG_FAULT
#undef DEBUG_ALL
<>
### Main developers:
Victorpv
### Most up to date repository for this HAL:
https://github.com/victorpv/Marlin/tree/bugfix-2.0.x
PRs should be first sent to that fork, and once tested merged to Marlin bugfix-2.0.x branch.

View File

@ -0,0 +1,70 @@
/**
* 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/>.
*
*/
/**
* HAL for stm32duino.com based on Libmaple and compatible (STM32F1)
*/
/**
* 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

View File

@ -0,0 +1,91 @@
/**
* 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/>.
*
*/
/**
* Endstop interrupts for Libmaple STM32F1 based targets.
*
* On STM32F, all pins support external interrupt capability.
* Any pin can be used for external interrupts, but there are some restrictions.
* At most 16 different external interrupts can be used at one time.
* Further, you cant just pick any 16 pins to use. This is because every pin on the STM32
* connects to what is called an EXTI line, and only one pin per EXTI line can be used for external interrupts at a time
* Check the Reference Manual of the MCU to confirm which line is used by each pin
*/
/**
* Endstop Interrupts
*
* Without endstop interrupts the endstop pins must be polled continually in
* the stepper-ISR via endstops.update(), most of the time finding no change.
* With this feature endstops.update() is called only when we know that at
* least one endstop has changed state, saving valuable CPU cycles.
*
* This feature only works when all used endstop pins can generate an 'external interrupt'.
*
* Test whether pins issue interrupts on your board by flashing 'pin_interrupt_test.ino'.
* (Located in Marlin/buildroot/share/pin_interrupt_test/pin_interrupt_test.ino)
*/
#ifndef _ENDSTOP_INTERRUPTS_H_
#define _ENDSTOP_INTERRUPTS_H_
void setup_endstop_interrupts(void) {
#if HAS_X_MAX
pinMode(X_MAX_PIN, INPUT);
attachInterrupt(X_MAX_PIN, endstop_ISR, CHANGE); // assign it
#endif
#if HAS_X_MIN
pinMode(X_MIN_PIN, INPUT);
attachInterrupt(X_MIN_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_Y_MAX
pinMode(Y_MAX_PIN, INPUT);
attachInterrupt(Y_MAX_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_Y_MIN
pinMode(Y_MIN_PIN, INPUT);
attachInterrupt(Y_MIN_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_Z_MAX
pinMode(Z_MAX_PIN, INPUT);
attachInterrupt(Z_MAX_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_Z_MIN
pinMode(Z_MIN_PIN, INPUT);
attachInterrupt(Z_MIN_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_Z2_MAX
pinMode(Z2_MAX_PIN, INPUT);
attachInterrupt(Z2_MAX_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_Z2_MIN
pinMode(Z2_MIN_PIN, INPUT);
attachInterrupt(Z2_MIN_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_Z_MIN_PROBE_PIN
pinMode(Z_MIN_PROBE_PIN, INPUT);
attachInterrupt(Z_MIN_PROBE_PIN, endstop_ISR, CHANGE);
#endif
}
#endif //_ENDSTOP_INTERRUPTS_H_

View 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/>.
*
*/
/**
* Fast I/O interfaces for STM32F1
* These use GPIO functions instead of Direct Port Manipulation, as on AVR.
*/
#ifndef _FASTIO_STM32F1_H
#define _FASTIO_STM32F1_H
#include <libmaple/gpio.h>
#define READ(IO) (gpio_read_bit(PIN_MAP[IO].gpio_device, PIN_MAP[IO].gpio_bit) ? HIGH : LOW)
#define WRITE(IO, v) do{ gpio_write_bit(PIN_MAP[IO].gpio_device, PIN_MAP[IO].gpio_bit, v); } while (0)
#define TOGGLE(IO) do{ gpio_toggle_bit(PIN_MAP[IO].gpio_device, PIN_MAP[IO].gpio_bit); } while (0)
#define WRITE_VAR(IO, v) WRITE(io, v)
#define _GET_MODE(IO) (gpio_get_mode(PIN_MAP[IO].gpio_device, PIN_MAP[IO].gpio_bit))
#define _SET_MODE(IO,M) do{ gpio_set_mode(PIN_MAP[IO].gpio_device, PIN_MAP[IO].gpio_bit, M); } while (0)
#define _SET_OUTPUT(IO) _SET_MODE(IO, GPIO_OUTPUT_PP)
#define SET_INPUT(IO) _SET_MODE(IO, GPIO_INPUT_FLOATING)
#define SET_INPUT_PULLUP(IO) _SET_MODE(IO, GPIO_INPUT_PU)
#define SET_OUTPUT(IO) do{ _SET_OUTPUT(IO); WRITE(IO, LOW); }while(0)
#define GET_INPUT(IO) (_GET_MODE(IO) == GPIO_INPUT_FLOATING || _GET_MODE(IO) == GPIO_INPUT_ANALOG || _GET_MODE(IO) == GPIO_INPUT_PU || _GET_MODE(IO) == GPIO_INPUT_PD)
#define GET_OUTPUT(IO) (_GET_MODE(IO) == GPIO_OUTPUT_PP)
#define GET_TIMER(IO) (PIN_MAP[IO].timer_device != NULL)
#define OUT_WRITE(IO, v) { _SET_OUTPUT(IO); WRITE(IO, v); }
#endif /* _FASTIO_STM32F1_H */

View File

@ -0,0 +1,98 @@
/**
* 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/>.
*
*/
/**
* HAL for stm32duino.com based on Libmaple and compatible (STM32F1)
*/
#ifdef __STM32F1__
#include "../../inc/MarlinConfig.h"
#if ENABLED(EEPROM_SETTINGS)
#include "../persistent_store_api.h"
//#include "../../core/types.h"
//#include "../../core/language.h"
//#include "../../core/serial.h"
//#include "../../core/utility.h"
#include "../../sd/cardreader.h"
namespace HAL {
namespace PersistentStore {
#define CONFIG_FILE_NAME "eeprom.dat"
#define HAL_STM32F1_EEPROM_SIZE 4096
char HAL_STM32F1_eeprom_content[HAL_STM32F1_EEPROM_SIZE];
bool access_start() {
if (!card.cardOK) return false;
int16_t bytes_read = 0;
const char eeprom_zero = 0xFF;
card.openFile((char *)CONFIG_FILE_NAME,true);
bytes_read = card.read (HAL_STM32F1_eeprom_content, HAL_STM32F1_EEPROM_SIZE);
if (bytes_read == -1) return false;
for (; bytes_read < HAL_STM32F1_EEPROM_SIZE; bytes_read++) {
HAL_STM32F1_eeprom_content[bytes_read] = eeprom_zero;
}
card.closefile();
return true;
}
bool access_finish(){
if (!card.cardOK) return false;
int16_t bytes_written = 0;
card.openFile((char *)CONFIG_FILE_NAME,true);
bytes_written = card.write (HAL_STM32F1_eeprom_content, HAL_STM32F1_EEPROM_SIZE);
card.closefile();
return (bytes_written == HAL_STM32F1_EEPROM_SIZE);
}
bool write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc) {
for (int i = 0; i < size; i++) {
HAL_STM32F1_eeprom_content [pos + i] = value[i];
}
crc16(crc, value, size);
pos += size;
return true;
}
void read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc) {
for (int i = 0; i < size; i++) {
value[i] = HAL_STM32F1_eeprom_content [pos + i];
}
crc16(crc, value, size);
pos += size;
}
} // PersistentStore::
} // HAL::
#endif // EEPROM_SETTINGS
#endif // __STM32F1__

View File

@ -0,0 +1,37 @@
/**
* 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/>.
*
*/
/**
* HAL for stm32duino.com based on Libmaple and compatible (STM32F1)
*/
#ifndef SPI_PINS_H_
#define SPI_PINS_H_
/**
* Define SPI Pins: SCK, MISO, MOSI, SS
*
* Available chip select pins for HW SPI are 4 10 52 77
*/
#define SCK_PIN PA5
#define MISO_PIN PA6
#define MOSI_PIN PA7
#define SS_PIN PA4
#endif // SPI_PINS_H_

View 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
*
* 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/>.
*
*/
/**
* HAL for stm32duino.com based on Libmaple and compatible (STM32F1)
*/
#ifdef __STM32F1__
#include "../../inc/MarlinConfig.h"
#if ENABLED(USE_WATCHDOG)
#include <libmaple/iwdg.h>
#include "watchdog_Stm32f1.h"
void watchdogSetup(void) {
// do whatever. don't remove this function.
}
/**
* @brief Initialized the independent hardware watchdog.
*
* @return No return
*
* @details The watchdog clock is 40Khz. We need a 4 seconds interval, so use a /256 preescaler and 625 reload value (counts down to 0)
*/
void watchdog_init(void) {
//iwdg_init(IWDG_PRE_256, STM32F1_WD_RELOAD);
}
#endif // USE_WATCHDOG
#endif // __STM32F1__

View File

@ -0,0 +1,44 @@
/**
* 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/>.
*
*/
/**
* HAL for stm32duino.com based on Libmaple and compatible (STM32F1)
*/
#ifndef WATCHDOG_STM32F1_H
#define WATCHDOG_STM32F1_H
#include <libmaple/iwdg.h>
#include "../../../src/inc/MarlinConfig.h"
#define STM32F1_WD_RELOAD 625
// Arduino STM32F1 core now has watchdog support
// Initialize watchdog with a 4 second countdown time
void watchdog_init();
// Reset watchdog. MUST be called at least every 4 seconds after the
// first watchdog_init or STM32F1 will reset.
inline void watchdog_reset() { iwdg_feed(); }
#endif // WATCHDOG_STM32F1_H

View File

@ -30,6 +30,8 @@
#include "HAL_TEENSY35_36/SanityCheck_Teensy_35_36.h"
#elif defined(TARGET_LPC1768)
#include "HAL_LPC1768/SanityCheck_Re_ARM.h"
#elif defined(__STM32F1__)
#include "HAL_STM32F1/SanityCheck_Stm32f1.h"
#else
#error Unsupported Platform!
#endif

View File

@ -34,7 +34,8 @@
#elif defined(TARGET_LPC1768)
#include "HAL_LPC1768/spi_pins.h"
#elif defined(__STM32F1__)
#include "HAL_STM32F1/spi_pins.h"
#else
#error "Unsupported Platform!"
#endif

File diff suppressed because it is too large Load Diff

View File

@ -128,6 +128,7 @@
#define BOARD_RAMPS_14_RE_ARM_EFF 1745 // Re-ARM with RAMPS 1.4 (Power outputs: Hotend, Fan0, Fan1)
#define BOARD_RAMPS_14_RE_ARM_EEF 1746 // Re-ARM with RAMPS 1.4 (Power outputs: Hotend0, Hotend1, Fan)
#define BOARD_RAMPS_14_RE_ARM_SF 1748 // Re-ARM with RAMPS 1.4 (Power outputs: Spindle, Controller Fan)
#define BOARD_STM32F1R 1800 // STM3R Libmaple based stm32f1 controller
#define MB(board) (MOTHERBOARD==BOARD_##board)

View File

@ -298,6 +298,8 @@
#include "pins_RAMPS4DUE.h"
#elif MB(ALLIGATOR)
#include "pins_ALLIGATOR_R2.h"
#elif MB(STM32F1R)
#include "pins_STM32F1R.h"
#else
#error "Unknown MOTHERBOARD value set in Configuration.h"
#endif

View File

@ -76,6 +76,14 @@
#define LARGE_FLASH true
//
// Servos
//
#define SERVO0_PIN 41
#define SERVO1_PIN 42
#define SERVO2_PIN 43
#define SERVO3_PIN 44
//
// Limit Switches
//
@ -102,7 +110,9 @@
#define E0_DIR_PIN 35 // A7
#define E0_ENABLE_PIN 11 // C1
//
// Digital Microstepping
//
#define X_MS1_PIN 25 // B5
#define X_MS2_PIN 26 // B6
#define Y_MS1_PIN 9 // E1

View File

@ -0,0 +1,283 @@
/**
* 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/>.
*
*/
#if !defined(__STM32F1__)
#error "Oops! Make sure you have an STM32F1 board selected from the 'Tools -> Boards' menu."
#endif
/**
* 21017 Victor Perez Marlin for stm32f1 test
*/
#define DEFAULT_MACHINE_NAME "STM32F103RET6"
#define BOARD_NAME "Marlin for STM32"
#define LARGE_FLASH true
// Ignore temp readings during develpment.
#define BOGUS_TEMPERATURE_FAILSAFE_OVERRIDE
//
// Steppers
//
#define X_STEP_PIN PC0
#define X_DIR_PIN PC1
#define X_ENABLE_PIN PA8
#define X_MIN_PIN PB3
#define X_MAX_PIN -1
#define Y_STEP_PIN PC2
#define Y_DIR_PIN PC3
#define Y_ENABLE_PIN PA8
#define Y_MIN_PIN -1
#define Y_MAX_PIN PB4
#define Z_STEP_PIN PC4
#define Z_DIR_PIN PC5
#define Z_ENABLE_PIN PA8
#define Z_MIN_PIN -1
#define Z_MAX_PIN PB5
#define Y2_STEP_PIN -1
#define Y2_DIR_PIN -1
#define Y2_ENABLE_PIN -1
#define Z2_STEP_PIN -1
#define Z2_DIR_PIN -1
#define Z2_ENABLE_PIN -1
#define E0_STEP_PIN PC6
#define E0_DIR_PIN PC7
#define E0_ENABLE_PIN PA8
/**
* TODO: Currently using same Enable pin to all steppers.
*/
#define E1_STEP_PIN PC8
#define E1_DIR_PIN PC9
#define E1_ENABLE_PIN PA8
#define E2_STEP_PIN PC10
#define E2_DIR_PIN PC11
#define E2_ENABLE_PIN PA8
//
// Misc. Functions
//
#define SDPOWER -1
#define SDSS PA4
#define LED_PIN PD2
#define PS_ON_PIN -1
#define KILL_PIN -1
//
// Heaters / Fans
//
#define HEATER_0_PIN PB0 // EXTRUDER 1
#define HEATER_1_PIN PB1
#define HEATER_2_PIN -1
#define HEATER_BED_PIN PA3 // BED
#define HEATER_BED2_PIN -1 // BED2
#define HEATER_BED3_PIN -1 // BED3
#define FAN_PIN -1 // (Sprinter config)
//
// Temperature Sensors
//
#define TEMP_BED_PIN PA0 // ANALOG NUMBERING
#define TEMP_0_PIN PA1 // ANALOG NUMBERING
#define TEMP_1_PIN PA2 // ANALOG NUMBERING
#define TEMP_2_PIN -1 // ANALOG NUMBERING
//
// LCD Pins
//
#if ENABLED(ULTRA_LCD)
#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 PB8
#define LCD_PINS_ENABLE PD2
#define LCD_PINS_D4 PB12
#define LCD_PINS_D5 PB13
#define LCD_PINS_D6 PB14
#define LCD_PINS_D7 PB15
#else
#define LCD_PINS_RS PB8
#define LCD_PINS_ENABLE PD2
#define LCD_PINS_D4 PB12
#define LCD_PINS_D5 PB13
#define LCD_PINS_D6 PB14
#define LCD_PINS_D7 PB15
#if DISABLED(NEWPANEL)
#define BEEPER_PIN 33
// 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
#if ENABLED(NEWPANEL)
#if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER)
#define BEEPER_PIN 37
#define BTN_EN1 31
#define BTN_EN2 33
#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 53
#define SD_DETECT_PIN -1
#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 53
#define SD_DETECT_PIN 49
#elif ENABLED(VIKI2) || ENABLED(miniVIKI)
#define BEEPER_PIN 33
// Pins for DOGM SPI LCD Support
#define DOGLCD_A0 44
#define DOGLCD_CS 45
#define LCD_SCREEN_ROT_180
#define BTN_EN1 22
#define BTN_EN2 7
#define BTN_ENC 39
#define SDSS 53
#define SD_DETECT_PIN -1 // Pin 49 for display sd interface, 72 for easy adapter board
#define KILL_PIN 31
#define STAT_LED_RED_PIN 32
#define STAT_LED_BLUE_PIN 35
#elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER)
#define BTN_EN1 35
#define BTN_EN2 37
#define BTN_ENC 31
#define SD_DETECT_PIN 49
#define LCD_SDSS 53
#define KILL_PIN 41
#define BEEPER_PIN 23
#define DOGLCD_CS 29
#define DOGLCD_A0 27
#define LCD_BACKLIGHT_PIN 33
#elif ENABLED(MINIPANEL)
#define BEEPER_PIN 42
// Pins for DOGM SPI LCD Support
#define DOGLCD_A0 44
#define DOGLCD_CS 66
#define LCD_BACKLIGHT_PIN 65 // backlight LED on A11/D65
#define SDSS 53
#define KILL_PIN 64
// GLCD features
//#define LCD_CONTRAST 190
// Uncomment screen orientation
//#define LCD_SCREEN_ROT_90
//#define LCD_SCREEN_ROT_180
//#define LCD_SCREEN_ROT_270
// The encoder and click button
#define BTN_EN1 40
#define BTN_EN2 63
#define BTN_ENC 59
// not connected to a pin
#define SD_DETECT_PIN 49
#else
// Beeper on AUX-4
#define BEEPER_PIN 33
// buttons are directly attached using AUX-2
#if ENABLED(REPRAPWORLD_KEYPAD)
#define BTN_EN1 64
#define BTN_EN2 59
#define BTN_ENC 63
#define SHIFT_OUT 40
#define SHIFT_CLK 44
#define SHIFT_LD 42
#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
#else
//#define SD_DETECT_PIN -1 // Ramps doesn't use this
#endif
#endif
#endif // NEWPANEL
#endif // ULTRA_LCD
#define U_MIN_PIN -1
#define V_MIN_PIN -1
#define W_MIN_PIN -1