HAL updates

This commit is contained in:
Scott Lahteine 2017-09-06 06:28:32 -05:00
parent 65996e4235
commit 54326fb06a
52 changed files with 327 additions and 378 deletions

View file

@ -3,7 +3,7 @@
#include <stdio.h> #include <stdio.h>
#include <string.h> #include <string.h>
#include <inttypes.h> #include <inttypes.h>
#include "../../../../src/HAL/HAL_LPC1768/arduino.h" #include <HAL_LPC1768/arduino.h>
// When the display powers up, it is configured as follows: // When the display powers up, it is configured as follows:
// //

View file

@ -23,7 +23,7 @@
*/ */
#include <stdlib.h> #include <stdlib.h>
#include "../../../../src/HAL/HAL_LPC1768/arduino.h" #include <HAL_LPC1768/arduino.h>
#include "Stream.h" #include "Stream.h"

View file

@ -92,7 +92,7 @@ void spiSendBlock(uint8_t token, const uint8_t* buf);
#include "math_32bit.h" #include "math_32bit.h"
#include "HAL_LPC1768/HAL.h" #include "HAL_LPC1768/HAL.h"
#else #else
#error Unsupported Platform! #error "Unsupported Platform!"
#endif #endif
#endif /* HAL_H_ */ #endif // _HAL_H

View file

@ -34,7 +34,7 @@
// -------------------------------------------------------------------------- // --------------------------------------------------------------------------
#include "../HAL.h" #include "../HAL.h"
#include "../../../macros.h" #include "../../core/macros.h"
// -------------------------------------------------------------------------- // --------------------------------------------------------------------------
// Externals // Externals
@ -75,7 +75,7 @@
// -------------------------------------------------------------------------- // --------------------------------------------------------------------------
#if ENABLED(SDSUPPORT) #if ENABLED(SDSUPPORT)
#include "../../../SdFatUtil.h" #include "../../sd/SdFatUtil.h"
int freeMemory() { return SdFatUtil::FreeRam(); } int freeMemory() { return SdFatUtil::FreeRam(); }
#else #else

View file

@ -56,7 +56,7 @@ bool endstop_monitor_flag = false;
#define REPORT_NAME_DIGITAL(NAME, COUNTER) _ADD_PIN(#NAME, COUNTER) #define REPORT_NAME_DIGITAL(NAME, COUNTER) _ADD_PIN(#NAME, COUNTER)
#define REPORT_NAME_ANALOG(NAME, COUNTER) _ADD_PIN(#NAME, COUNTER) #define REPORT_NAME_ANALOG(NAME, COUNTER) _ADD_PIN(#NAME, COUNTER)
#include "../../../pinsDebug_list.h" #include "../../pins/pinsDebug_list.h"
#line 51 #line 51
// manually add pins that have names that are macros which don't play well with these macros // manually add pins that have names that are macros which don't play well with these macros
@ -107,7 +107,7 @@ const PinInfo pin_array[] PROGMEM = {
#endif #endif
#endif #endif
#include "../../../pinsDebug_list.h" #include "../../pins/pinsDebug_list.h"
#line 102 #line 102
}; };
@ -483,7 +483,7 @@ inline void report_pin_state_extended(int8_t pin, bool ignore, bool extended = f
SERIAL_CHAR('.'); SERIAL_CHAR('.');
SERIAL_ECHO_SP(26 + strlen(start_string)); // add padding if not the first instance found SERIAL_ECHO_SP(26 + strlen(start_string)); // add padding if not the first instance found
} }
name_mem_pointer = (char*)pgm_read_word(&pin_array[x].name); name_mem_pointer = (char*)pgm_read_ptr(&pin_array[x].name);
for (uint8_t y = 0; y < 28; y++) { // always print pin name for (uint8_t y = 0; y < 28; y++) { // always print pin name
temp_char = pgm_read_byte(name_mem_pointer + y); temp_char = pgm_read_byte(name_mem_pointer + y);
if (temp_char != 0) if (temp_char != 0)

View file

@ -37,7 +37,7 @@
// Includes // Includes
// -------------------------------------------------------------------------- // --------------------------------------------------------------------------
#include "../../../MarlinConfig.h" #include "../../inc/MarlinConfig.h"
// -------------------------------------------------------------------------- // --------------------------------------------------------------------------
// Public Variables // Public Variables

View file

@ -31,7 +31,7 @@
#ifdef ARDUINO_ARCH_AVR #ifdef ARDUINO_ARCH_AVR
#include "MarlinSerial.h" #include "MarlinSerial.h"
#include "../../../Marlin.h" #include "../../Marlin.h"
// Disable HardwareSerial.cpp to support chips without a UART (Attiny, etc.) // Disable HardwareSerial.cpp to support chips without a UART (Attiny, etc.)
@ -47,8 +47,7 @@
#if ENABLED(EMERGENCY_PARSER) #if ENABLED(EMERGENCY_PARSER)
#include "../../../stepper.h" #include "../../module/stepper.h"
#include "../../../language.h"
// Currently looking for: M108, M112, M410 // Currently looking for: M108, M112, M410
// If you alter the parser please don't forget to update the capabilities in Conditionals_post.h // If you alter the parser please don't forget to update the capabilities in Conditionals_post.h

View file

@ -32,7 +32,7 @@
#ifndef MARLINSERIAL_H #ifndef MARLINSERIAL_H
#define MARLINSERIAL_H #define MARLINSERIAL_H
#include "../../../MarlinConfig.h" #include "../../inc/MarlinConfig.h"
#include <WString.h> #include <WString.h>

View file

@ -38,7 +38,8 @@
#ifndef _ENDSTOP_INTERRUPTS_H_ #ifndef _ENDSTOP_INTERRUPTS_H_
#define _ENDSTOP_INTERRUPTS_H_ #define _ENDSTOP_INTERRUPTS_H_
#include "../../../macros.h" #include "../../core/macros.h"
#include <stdint.h>
/** /**
* Patch for pins_arduino.h (...\Arduino\hardware\arduino\avr\variants\mega\pins_arduino.h) * Patch for pins_arduino.h (...\Arduino\hardware\arduino\avr\variants\mega\pins_arduino.h)

View file

@ -30,7 +30,7 @@
#define _FASTIO_ARDUINO_H #define _FASTIO_ARDUINO_H
#include <avr/io.h> #include <avr/io.h>
#include "../../../macros.h" #include "../../core/macros.h"
#define AVR_AT90USB1286_FAMILY (defined(__AVR_AT90USB1287__) || defined(__AVR_AT90USB1286__) || defined(__AVR_AT90USB1286P__) || defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB646P__) || defined(__AVR_AT90USB647__)) #define AVR_AT90USB1286_FAMILY (defined(__AVR_AT90USB1287__) || defined(__AVR_AT90USB1286__) || defined(__AVR_AT90USB1286P__) || defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB646P__) || defined(__AVR_AT90USB647__))
#define AVR_ATmega1284_FAMILY (defined(__AVR_ATmega644__) || defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644PA__) || defined(__AVR_ATmega1284P__)) #define AVR_ATmega1284_FAMILY (defined(__AVR_ATmega644__) || defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644PA__) || defined(__AVR_ATmega1284P__))
@ -168,6 +168,7 @@ typedef enum {
} ClockSource2; } ClockSource2;
// Get interrupt bits in an orderly way // Get interrupt bits in an orderly way
// Ex: cs = GET_CS(0); coma1 = GET_COM(A,1);
#define GET_WGM(T) (((TCCR##T##A >> WGM##T##0) & 0x3) | ((TCCR##T##B >> WGM##T##2 << 2) & 0xC)) #define GET_WGM(T) (((TCCR##T##A >> WGM##T##0) & 0x3) | ((TCCR##T##B >> WGM##T##2 << 2) & 0xC))
#define GET_CS(T) ((TCCR##T##B >> CS##T##0) & 0x7) #define GET_CS(T) ((TCCR##T##B >> CS##T##0) & 0x7)
#define GET_COM(T,Q) ((TCCR##T##Q >> COM##T##Q##0) & 0x3) #define GET_COM(T,Q) ((TCCR##T##Q >> COM##T##Q##0) & 0x3)
@ -182,6 +183,7 @@ typedef enum {
#define GET_FOCC(T) GET_FOC(T,C) #define GET_FOCC(T) GET_FOC(T,C)
// Set Wave Generation Mode bits // Set Wave Generation Mode bits
// Ex: SET_WGM(5,CTC_ICRn);
#define _SET_WGM(T,V) do{ \ #define _SET_WGM(T,V) do{ \
TCCR##T##A = (TCCR##T##A & ~(0x3 << WGM##T##0)) | (( int(V) & 0x3) << WGM##T##0); \ TCCR##T##A = (TCCR##T##A & ~(0x3 << WGM##T##0)) | (( int(V) & 0x3) << WGM##T##0); \
TCCR##T##B = (TCCR##T##B & ~(0x3 << WGM##T##2)) | (((int(V) >> 2) & 0x3) << WGM##T##2); \ TCCR##T##B = (TCCR##T##B & ~(0x3 << WGM##T##2)) | (((int(V) >> 2) & 0x3) << WGM##T##2); \
@ -189,6 +191,7 @@ typedef enum {
#define SET_WGM(T,V) _SET_WGM(T,WGM_##V) #define SET_WGM(T,V) _SET_WGM(T,WGM_##V)
// Set Clock Select bits // Set Clock Select bits
// Ex: SET_CS3(PRESCALER_64);
#define _SET_CS(T,V) (TCCR##T##B = (TCCR##T##B & ~(0x7 << CS##T##0)) | ((int(V) & 0x7) << CS##T##0)) #define _SET_CS(T,V) (TCCR##T##B = (TCCR##T##B & ~(0x7 << CS##T##0)) | ((int(V) & 0x7) << CS##T##0))
#define _SET_CS0(V) _SET_CS(0,V) #define _SET_CS0(V) _SET_CS(0,V)
#define _SET_CS1(V) _SET_CS(1,V) #define _SET_CS1(V) _SET_CS(1,V)
@ -213,6 +216,7 @@ typedef enum {
#define SET_CS(T,V) SET_CS##T(V) #define SET_CS(T,V) SET_CS##T(V)
// Set Compare Mode bits // Set Compare Mode bits
// Ex: SET_COMS(4,CLEAR_SET,CLEAR_SET,CLEAR_SET);
#define _SET_COM(T,Q,V) (TCCR##T##Q = (TCCR##T##Q & ~(0x3 << COM##T##Q##0)) | (int(V) << COM##T##Q##0)) #define _SET_COM(T,Q,V) (TCCR##T##Q = (TCCR##T##Q & ~(0x3 << COM##T##Q##0)) | (int(V) << COM##T##Q##0))
#define SET_COM(T,Q,V) _SET_COM(T,Q,COM_##V) #define SET_COM(T,Q,V) _SET_COM(T,Q,COM_##V)
#define SET_COMA(T,V) SET_COM(T,A,V) #define SET_COMA(T,V) SET_COM(T,A,V)
@ -221,12 +225,15 @@ typedef enum {
#define SET_COMS(T,V1,V2,V3) do{ SET_COMA(T,V1); SET_COMB(T,V2); SET_COMC(T,V3); }while(0) #define SET_COMS(T,V1,V2,V3) do{ SET_COMA(T,V1); SET_COMB(T,V2); SET_COMC(T,V3); }while(0)
// Set Noise Canceler bit // Set Noise Canceler bit
// Ex: SET_ICNC(2,1)
#define SET_ICNC(T,V) (TCCR##T##B = (V) ? TCCR##T##B | _BV(ICNC##T) : TCCR##T##B & ~_BV(ICNC##T)) #define SET_ICNC(T,V) (TCCR##T##B = (V) ? TCCR##T##B | _BV(ICNC##T) : TCCR##T##B & ~_BV(ICNC##T))
// Set Input Capture Edge Select bit // Set Input Capture Edge Select bit
// Ex: SET_ICES(5,0)
#define SET_ICES(T,V) (TCCR##T##B = (V) ? TCCR##T##B | _BV(ICES##T) : TCCR##T##B & ~_BV(ICES##T)) #define SET_ICES(T,V) (TCCR##T##B = (V) ? TCCR##T##B | _BV(ICES##T) : TCCR##T##B & ~_BV(ICES##T))
// Set Force Output Compare bit // Set Force Output Compare bit
// Ex: SET_FOC(3,A,1)
#define SET_FOC(T,Q,V) (TCCR##T##C = (V) ? TCCR##T##C | _BV(FOC##T##Q) : TCCR##T##C & ~_BV(FOC##T##Q)) #define SET_FOC(T,Q,V) (TCCR##T##C = (V) ? TCCR##T##C | _BV(FOC##T##Q) : TCCR##T##C & ~_BV(FOC##T##Q))
#define SET_FOCA(T,V) SET_FOC(T,A,V) #define SET_FOCA(T,V) SET_FOC(T,A,V)
#define SET_FOCB(T,V) SET_FOC(T,B,V) #define SET_FOCB(T,V) SET_FOC(T,B,V)

View file

@ -2,10 +2,7 @@
#include "../persistent_store_api.h" #include "../persistent_store_api.h"
#include "../../../types.h" #include "../../inc/MarlinConfig.h"
#include "../../../language.h"
#include "../../../serial.h"
#include "../../../utility.h"
#if ENABLED(EEPROM_SETTINGS) #if ENABLED(EEPROM_SETTINGS)

View file

@ -54,13 +54,13 @@
#define GET_ARRAY_PIN(p) pgm_read_byte(&pin_array[p].pin) #define GET_ARRAY_PIN(p) pgm_read_byte(&pin_array[p].pin)
#endif #endif
#define VALID_PIN(pin)) (pin >= 0 && pin < NUM_DIGITAL_PINS ? 1 : 0) #define VALID_PIN(pin) (pin >= 0 && pin < NUM_DIGITAL_PINS ? 1 : 0)
#define DIGITAL_PIN_TO_ANALOG_PIN(p) int(p - analogInputToDigitalPin(0)) #define DIGITAL_PIN_TO_ANALOG_PIN(p) int(p - analogInputToDigitalPin(0))
#define IS_ANALOG(P) ((P) >= analogInputToDigitalPin(0) && ((P) <= analogInputToDigitalPin(15) || (P) <= analogInputToDigitalPin(7))) #define IS_ANALOG(P) ((P) >= analogInputToDigitalPin(0) && ((P) <= analogInputToDigitalPin(15) || (P) <= analogInputToDigitalPin(7)))
#define GET_ARRAY_PIN(p) pgm_read_byte(&pin_array[p].pin) #define GET_ARRAY_PIN(p) pgm_read_byte(&pin_array[p].pin)
void PRINT_ARRAY_NAME(uint8_t x) { void PRINT_ARRAY_NAME(uint8_t x) {
char *name_mem_pointer = (char*)pgm_read_word(&pin_array[x].name); char *name_mem_pointer = (char*)pgm_read_ptr(&pin_array[x].name);
for (uint8_t y = 0; y < MAX_NAME_LENGTH; y++) { for (uint8_t y = 0; y < MAX_NAME_LENGTH; y++) {
char temp_char = pgm_read_byte(name_mem_pointer + y); char temp_char = pgm_read_byte(name_mem_pointer + y);
if (temp_char != 0) if (temp_char != 0)
@ -362,7 +362,8 @@ static void pwm_details(uint8_t pin) {
} }
#endif #endif
#ifndef PRINT_PORT(p) #ifndef PRINT_PORT
void print_port(int8_t pin) { // print port number void print_port(int8_t pin) { // print port number
#ifdef digitalPinToPort_DEBUG #ifdef digitalPinToPort_DEBUG
uint8_t x; uint8_t x;
@ -394,4 +395,7 @@ static void pwm_details(uint8_t pin) {
} }
#define PRINT_PORT(p) print_port(p) #define PRINT_PORT(p) print_port(p)
#endif #endif
#define GET_PIN_INFO(pin) do{}while(0)

View file

@ -53,7 +53,7 @@
#ifdef ARDUINO_ARCH_AVR #ifdef ARDUINO_ARCH_AVR
#include "../../../MarlinConfig.h" #include "../../inc/MarlinConfig.h"
#if HAS_SERVOS #if HAS_SERVOS

View file

@ -22,13 +22,13 @@
#ifdef ARDUINO_ARCH_AVR #ifdef ARDUINO_ARCH_AVR
#include "../../../MarlinConfig.h" #include "../../inc/MarlinConfig.h"
#if ENABLED(USE_WATCHDOG) #if ENABLED(USE_WATCHDOG)
#include "watchdog_AVR.h" #include "watchdog_AVR.h"
#include "../../../Marlin.h" #include "../../Marlin.h"
// Initialize watchdog with a 4 sec interrupt time // Initialize watchdog with a 4 sec interrupt time
void watchdog_init() { void watchdog_init() {

View file

@ -74,9 +74,15 @@
#define strncpy_P(dest, src, num) strncpy((dest), (src), (num)) #define strncpy_P(dest, src, num) strncpy((dest), (src), (num))
#endif #endif
#ifndef vsnprintf_P
#define vsnprintf_P vsnprintf
#endif
// Fix bug in pgm_read_ptr // Fix bug in pgm_read_ptr
#undef pgm_read_ptr #undef pgm_read_ptr
#define pgm_read_ptr(addr) (*(addr)) #define pgm_read_ptr(addr) (*((void**)(addr)))
#undef pgm_read_word
#define pgm_read_word(addr) (*((uint16_t*)(addr)))
#define RST_POWER_ON 1 #define RST_POWER_ON 1
#define RST_EXTERNAL 2 #define RST_EXTERNAL 2

View file

@ -37,7 +37,7 @@
// Includes // Includes
// -------------------------------------------------------------------------- // --------------------------------------------------------------------------
#include "../../../MarlinConfig.h" #include "../../inc/MarlinConfig.h"
// -------------------------------------------------------------------------- // --------------------------------------------------------------------------
// Public Variables // Public Variables

View file

@ -40,7 +40,7 @@
#ifdef ARDUINO_ARCH_SAM #ifdef ARDUINO_ARCH_SAM
#include "../../../MarlinConfig.h" #include "../../inc/MarlinConfig.h"
#if HAS_SERVOS #if HAS_SERVOS

View file

@ -2,10 +2,7 @@
#include "../persistent_store_api.h" #include "../persistent_store_api.h"
#include "../../../types.h" #include "../../inc/MarlinConfig.h"
#include "../../../language.h"
#include "../../../serial.h"
#include "../../../utility.h"
#if ENABLED(EEPROM_SETTINGS) #if ENABLED(EEPROM_SETTINGS)

View file

@ -22,7 +22,7 @@
#ifdef ARDUINO_ARCH_SAM #ifdef ARDUINO_ARCH_SAM
#include "../../../MarlinConfig.h" #include "../../inc/MarlinConfig.h"
#if ENABLED(USE_WATCHDOG) #if ENABLED(USE_WATCHDOG)

View file

@ -23,10 +23,10 @@
#ifndef WATCHDOG_DUE_H #ifndef WATCHDOG_DUE_H
#define WATCHDOG_DUE_H #define WATCHDOG_DUE_H
//#include "../../../Marlin.h"
// Arduino Due core now has watchdog support // Arduino Due core now has watchdog support
#include "../HAL.h"
// Initialize watchdog with a 4 second interrupt time // Initialize watchdog with a 4 second interrupt time
void watchdog_init(); void watchdog_init();
@ -34,4 +34,4 @@ void watchdog_init();
// first watchdog_init or AVR will go into emergency procedures. // first watchdog_init or AVR will go into emergency procedures.
inline void watchdog_reset() { watchdogReset(); } inline void watchdog_reset() { watchdogReset(); }
#endif /* WATCHDOG_DUE_H */ #endif // WATCHDOG_DUE_H

View file

@ -18,16 +18,13 @@
along with this program. If not, see <http://www.gnu.org/licenses/>. along with this program. If not, see <http://www.gnu.org/licenses/>.
****************************************************************************/ ****************************************************************************/
/**
*
* For TARGET_LPC1768
*/
#ifdef TARGET_LPC1768 #ifdef TARGET_LPC1768
#include "../../../macros.h"
#include "../../core/macros.h"
#include "../HAL.h" #include "../HAL.h"
#include <stdint.h>
extern "C" { extern "C" {
//#include <lpc17xx_adc.h> //#include <lpc17xx_adc.h>
//#include <lpc17xx_pinsel.h> //#include <lpc17xx_pinsel.h>
@ -51,7 +48,7 @@ extern "C" void u8g_Delay(uint16_t val) {
//************************// //************************//
// return free heap space // return free heap space
int freeMemory(){ int freeMemory() {
char stack_end; char stack_end;
void *heap_start = malloc(sizeof(uint32_t)); void *heap_start = malloc(sizeof(uint32_t));
if (heap_start == 0) return 0; if (heap_start == 0) return 0;
@ -82,22 +79,22 @@ void HAL_adc_init(void) {
} }
// externals need to make the call to KILL compile // externals need to make the call to KILL compile
#include "../../../language.h" #include "../../core/language.h"
extern void kill(const char*); extern void kill(const char*);
extern const char errormagic[]; extern const char errormagic[];
void HAL_adc_enable_channel(int pin) { void HAL_adc_enable_channel(int pin) {
if (pin < 0 || pin >= NUM_ANALOG_INPUTS) { if (!WITHIN(pin, 0, NUM_ANALOG_INPUTS - 1)) {
usb_serial.printf("%sINVALID ANALOG PORT:%d\n", errormagic, pin); usb_serial.printf("%sINVALID ANALOG PORT:%d\n", errormagic, pin);
kill(MSG_KILLED); kill(MSG_KILLED);
} }
int8_t pin_port = adc_pin_map[pin].port; int8_t pin_port = adc_pin_map[pin].port,
int8_t pin_port_pin = adc_pin_map[pin].pin; pin_port_pin = adc_pin_map[pin].pin,
int8_t pinsel_start_bit = pin_port_pin > 15 ? 2 * (pin_port_pin - 16) : 2 * pin_port_pin; pinsel_start_bit = pin_port_pin > 15 ? 2 * (pin_port_pin - 16) : 2 * pin_port_pin;
uint8_t pin_sel_register = (pin_port == 0 && pin_port_pin <= 15) ? 0 : uint8_t pin_sel_register = (pin_port == 0 && pin_port_pin <= 15) ? 0 :
(pin_port == 0) ? 1 : pin_port == 0 ? 1 :
pin_port == 1 ? 3 : 10; pin_port == 1 ? 3 : 10;
switch (pin_sel_register) { switch (pin_sel_register) {
@ -117,24 +114,21 @@ void HAL_adc_enable_channel(int pin) {
} }
void HAL_adc_start_conversion(uint8_t adc_pin) { void HAL_adc_start_conversion(uint8_t adc_pin) {
if( (adc_pin >= NUM_ANALOG_INPUTS) || (adc_pin_map[adc_pin].port == 0xFF) ) { if (adc_pin >= (NUM_ANALOG_INPUTS) || adc_pin_map[adc_pin].port == 0xFF) {
usb_serial.printf("HAL: HAL_adc_start_conversion: no pinmap for %d\n",adc_pin); usb_serial.printf("HAL: HAL_adc_start_conversion: no pinmap for %d\n", adc_pin);
return; return;
} }
LPC_ADC->ADCR &= ~0xFF; // Reset LPC_ADC->ADCR &= ~0xFF; // Reset
LPC_ADC->ADCR |= ( 0x01 << adc_pin_map[adc_pin].adc ); // Select Channel SBI(LPC_ADC->ADCR, adc_pin_map[adc_pin].adc); // Select Channel
LPC_ADC->ADCR |= ( 0x01 << 24 ); // start conversion SBI(LPC_ADC->ADCR, 24); // Start conversion
} }
bool HAL_adc_finished(void) { bool HAL_adc_finished(void) { return LPC_ADC->ADGDR & ADC_DONE; }
return LPC_ADC->ADGDR & ADC_DONE;
}
uint16_t HAL_adc_get_result(void) { uint16_t HAL_adc_get_result(void) {
uint32_t data = LPC_ADC->ADGDR; uint32_t data = LPC_ADC->ADGDR;
LPC_ADC->ADCR &= ~(1 << 24); //stop conversion CBI(LPC_ADC->ADCR, 24); // Stop conversion
if ( data & ADC_OVERRUN ) return 0; return (data & ADC_OVERRUN) ? 0 : (data >> 6) & 0x3FF; // 10bit
return ((data >> 6) & 0x3ff); //10bit
} }
#define SBIT_CNTEN 0 #define SBIT_CNTEN 0

View file

@ -36,7 +36,7 @@
// Includes // Includes
// -------------------------------------------------------------------------- // --------------------------------------------------------------------------
#include "../../../MarlinConfig.h" #include "../../inc/MarlinConfig.h"
// -------------------------------------------------------------------------- // --------------------------------------------------------------------------
// Public Variables // Public Variables

View file

@ -22,7 +22,7 @@
#ifdef TARGET_LPC1768 #ifdef TARGET_LPC1768
#include "../../../macros.h" #include "../../core/macros.h"
#include "../HAL.h" #include "../HAL.h"
#include "HardwareSerial.h" #include "HardwareSerial.h"
#define UART3 3 #define UART3 3

View file

@ -60,7 +60,7 @@
* unless DEACTIVATE_SERVOS_AFTER_MOVE is enabled and a MOVE command was issued. * unless DEACTIVATE_SERVOS_AFTER_MOVE is enabled and a MOVE command was issued.
*/ */
#include "../../../MarlinConfig.h" #include "../../inc/MarlinConfig.h"
#if HAS_SERVOS && defined(TARGET_LPC1768) #if HAS_SERVOS && defined(TARGET_LPC1768)

View file

@ -34,29 +34,29 @@
#ifndef LPC1768_SERVO_H #ifndef LPC1768_SERVO_H
#define LPC1768_SERVO_H #define LPC1768_SERVO_H
#include <inttypes.h> #include <stdint.h>
class Servo { class Servo {
public: public:
Servo(); Servo();
int8_t attach(int pin); // attach the given pin to the next free channel, set pinMode, return channel number (-1 on fail) int8_t attach(int pin); // attach the given pin to the next free channel, set pinMode, return channel number (-1 on fail)
int8_t attach(int pin, int min, int max); // as above but also sets min and max values for writes. int8_t attach(int pin, int min, int max); // as above but also sets min and max values for writes.
void detach(); void detach();
void write(int value); // if value is < 200 it is treated as an angle, otherwise as pulse width in microseconds void write(int value); // if value is < 200 it is treated as an angle, otherwise as pulse width in microseconds
void writeMicroseconds(int value); // write pulse width in microseconds void writeMicroseconds(int value); // write pulse width in microseconds
void move(int value); // attach the servo, then move to value void move(int value); // attach the servo, then move to value
// if value is < 200 it is treated as an angle, otherwise as pulse width in microseconds // if value is < 200 it is treated as an angle, otherwise as pulse width in microseconds
// if DEACTIVATE_SERVOS_AFTER_MOVE wait SERVO_DELAY, then detach // if DEACTIVATE_SERVOS_AFTER_MOVE wait SERVO_DELAY, then detach
int read(); // returns current pulse width as an angle between 0 and 180 degrees int read(); // returns current pulse width as an angle between 0 and 180 degrees
int readMicroseconds(); // returns current pulse width in microseconds for this servo (was read_us() in first release) int readMicroseconds(); // returns current pulse width in microseconds for this servo (was read_us() in first release)
bool attached(); // return true if this servo is attached, otherwise false bool attached(); // return true if this servo is attached, otherwise false
private: private:
uint8_t servoIndex; // index into the channel data for this servo uint8_t servoIndex; // index into the channel data for this servo
int min; int min;
int max; int max;
}; };
#define HAL_SERVO_LIB Servo #define HAL_SERVO_LIB Servo
#endif // LPC1768_SERVO_H #endif // LPC1768_SERVO_H

View file

@ -35,7 +35,7 @@ http://arduiniana.org.
// Includes // Includes
// //
//#include <WInterrupts.h> //#include <WInterrupts.h>
#include "../../../macros.h" #include "../../core/macros.h"
#include "../HAL.h" #include "../HAL.h"
#include <stdint.h> #include <stdint.h>
#include <stdarg.h> #include <stdarg.h>

View file

@ -29,13 +29,13 @@ The latest version of this library can always be found at
http://arduiniana.org. http://arduiniana.org.
*/ */
#ifndef SoftwareSerial_h #ifndef SOFTWARESERIAL_H
#define SoftwareSerial_h #define SOFTWARESERIAL_H
#include "arduino.h" #include "arduino.h"
#include <inttypes.h> #include <stdint.h>
//#include "serial.h" //#include "serial.h"
#include <Stream.h> #include <Stream.h>
#include <Print.h> #include <Print.h>
/****************************************************************************** /******************************************************************************
@ -116,4 +116,4 @@ public:
#undef abs #undef abs
#undef round #undef round
#endif #endif // SOFTWARESERIAL_H

View file

@ -18,7 +18,7 @@
#ifdef TARGET_LPC1768 #ifdef TARGET_LPC1768
#include "../../../macros.h" #include "../../core/macros.h"
#include "../HAL.h" #include "../HAL.h"
#include "arduino.h" #include "arduino.h"
#include "pinmapping.h" #include "pinmapping.h"
@ -32,197 +32,159 @@ typedef void (*interruptCB)(void);
static interruptCB callbacksP0[GNUM]; static interruptCB callbacksP0[GNUM];
static interruptCB callbacksP2[GNUM]; static interruptCB callbacksP2[GNUM];
extern "C" void GpioEnableInt(uint32_t port, uint32_t pin, uint32_t mode); extern "C" void GpioEnableInt(const uint32_t port, const uint32_t pin, const uint32_t mode);
extern "C" void GpioDisableInt(uint32_t port, uint32_t pin); extern "C" void GpioDisableInt(const uint32_t port, const uint32_t pin);
//void deadloop(void) {} //void deadloop(void) {}
/* Configure PIO interrupt sources */ /* Configure PIO interrupt sources */
static void __initialize() { static void __initialize() {
int i; for (uint8_t i = 0; i < GNUM; i++) {
for (i=0; i<GNUM; i++) { callbacksP0[i] = 0;
callbacksP0[i] = 0; callbacksP2[i] = 0;
callbacksP2[i] = 0; }
} NVIC_EnableIRQ(EINT3_IRQn);
NVIC_EnableIRQ(EINT3_IRQn);
} }
void attachInterrupt(uint32_t pin, void (*callback)(void), uint32_t mode) void attachInterrupt(const uint32_t pin, void (*callback)(void), uint32_t mode) {
{ static int enabled = 0;
static int enabled = 0;
if(!INTERRUPT_PIN(pin)) return; if (!INTERRUPT_PIN(pin)) return;
if (!enabled) { if (!enabled) {
__initialize(); __initialize();
enabled = 1; ++enabled;
} }
uint8_t myport = pin_map[pin].port; uint8_t myport = pin_map[pin].port,
uint8_t mypin = pin_map[pin].pin; mypin = pin_map[pin].pin;
if (myport == 0)
callbacksP0[mypin] = callback;
else
callbacksP2[mypin] = callback;
if (myport == 0 ) // Enable interrupt
callbacksP0[mypin] = callback; GpioEnableInt(myport,mypin,mode);
else
callbacksP2[mypin] = callback;
// Enable interrupt
GpioEnableInt(myport,mypin,mode);
} }
void detachInterrupt(uint32_t pin) void detachInterrupt(const uint32_t pin) {
{ if (!INTERRUPT_PIN(pin)) return;
if(!INTERRUPT_PIN(pin)) return;
uint8_t myport = pin_map[pin].port; const uint8_t myport = pin_map[pin].port,
uint8_t mypin = pin_map[pin].pin; mypin = pin_map[pin].pin;
// Disable interrupt // Disable interrupt
GpioDisableInt(myport,mypin); GpioDisableInt(myport, mypin);
//unset callback // unset callback
if (myport == 0 ) if (myport == 0)
callbacksP0[mypin] = 0; callbacksP0[mypin] = 0;
else //if (myport == 2 ) else //if (myport == 2 )
callbacksP2[mypin] = 0; callbacksP2[mypin] = 0;
}
extern "C" void GpioEnableInt(uint32_t port, uint32_t pin, uint32_t mode) {
//pin here is the processor pin, not logical pin
if (port==0) {
LPC_GPIOINT->IO0IntClr = (1 << pin);
if (mode ==RISING) {
LPC_GPIOINT->IO0IntEnR |= (1<<pin);
LPC_GPIOINT->IO0IntEnF &= ~(1<<pin);
}
else if (mode==FALLING) {
LPC_GPIOINT->IO0IntEnF |= (1<<pin);
LPC_GPIOINT->IO0IntEnR &= ~(1<<pin);
}
else if (mode==CHANGE) {
LPC_GPIOINT->IO0IntEnR |= (1<<pin);
LPC_GPIOINT->IO0IntEnF |= (1<<pin);
}
}
else{
LPC_GPIOINT->IO2IntClr = (1 << pin);
if (mode ==RISING) {
LPC_GPIOINT->IO2IntEnR |= (1<<pin);
LPC_GPIOINT->IO2IntEnF &= ~(1<<pin);
}
else if (mode==FALLING) {
LPC_GPIOINT->IO2IntEnF |= (1<<pin);
LPC_GPIOINT->IO2IntEnR &= ~(1<<pin);
}
else if (mode==CHANGE) {
LPC_GPIOINT->IO2IntEnR |= (1<<pin);
LPC_GPIOINT->IO2IntEnF |= (1<<pin);
}
}
}
extern "C" void GpioDisableInt(uint32_t port, uint32_t pin)
{
if (port==0){
LPC_GPIOINT->IO0IntEnR &= ~(1<<pin);
LPC_GPIOINT->IO0IntEnF &= ~(1<<pin);
LPC_GPIOINT->IO0IntClr = 1 << pin;
}
else {
LPC_GPIOINT->IO2IntEnR &= ~(1<<pin);
LPC_GPIOINT->IO2IntEnF &= ~(1<<pin);
LPC_GPIOINT->IO2IntClr = 1 << pin;
}
} }
bool isPowerOf2(unsigned int n)
{ extern "C" void GpioEnableInt(uint32_t port, uint32_t pin, uint32_t mode) {
//pin here is the processor pin, not logical pin
if (port == 0) {
LPC_GPIOINT->IO0IntClr = _BV(pin);
if (mode == RISING) {
SBI(LPC_GPIOINT->IO0IntEnR, pin);
CBI(LPC_GPIOINT->IO0IntEnF, pin);
}
else if (mode == FALLING) {
SBI(LPC_GPIOINT->IO0IntEnF, pin);
CBI(LPC_GPIOINT->IO0IntEnR, pin);
}
else if (mode == CHANGE) {
SBI(LPC_GPIOINT->IO0IntEnR, pin);
SBI(LPC_GPIOINT->IO0IntEnF, pin);
}
}
else {
LPC_GPIOINT->IO2IntClr = _BV(pin);
if (mode == RISING) {
SBI(LPC_GPIOINT->IO2IntEnR, pin);
CBI(LPC_GPIOINT->IO2IntEnF, pin);
}
else if (mode == FALLING) {
SBI(LPC_GPIOINT->IO2IntEnF, pin);
CBI(LPC_GPIOINT->IO2IntEnR, pin);
}
else if (mode == CHANGE) {
SBI(LPC_GPIOINT->IO2IntEnR, pin);
SBI(LPC_GPIOINT->IO2IntEnF, pin);
}
}
}
return n == 1 || (n & (n-1)) == 0; extern "C" void GpioDisableInt(const uint32_t port, const uint32_t pin) {
if (port == 0) {
CBI(LPC_GPIOINT->IO0IntEnR, pin);
CBI(LPC_GPIOINT->IO0IntEnF, pin);
LPC_GPIOINT->IO0IntClr = _BV(pin);
}
else {
CBI(LPC_GPIOINT->IO2IntEnR, pin);
CBI(LPC_GPIOINT->IO2IntEnF, pin);
LPC_GPIOINT->IO2IntClr = _BV(pin);
}
}
bool isPowerOf2(unsigned int n) {
return n == 1 || (n & (n - 1)) == 0;
} }
#if 0 #if 0
extern "C" void EINT3_IRQHandler () { extern "C" void EINT3_IRQHandler () {
LPC_GPIOINT->IO0IntClr = LPC_GPIOINT->IO2IntClr = 0xFFFFFFFF; LPC_GPIOINT->IO0IntClr = LPC_GPIOINT->IO2IntClr = 0xFFFFFFFF;
TOGGLE(13); TOGGLE(13);
//NVIC_ClearPendingIRQ(EINT3_IRQn); //NVIC_ClearPendingIRQ(EINT3_IRQn);
} }
#else #else
extern "C" void EINT3_IRQHandler(void)
{ extern "C" void EINT3_IRQHandler(void) {
// Read in all current interrupt registers. We do this once as the // Read in all current interrupt registers. We do this once as the
// GPIO interrupt registers are on the APB bus, and this is slow. // GPIO interrupt registers are on the APB bus, and this is slow.
uint32_t rise0 = LPC_GPIOINT->IO0IntStatR; uint32_t rise0 = LPC_GPIOINT->IO0IntStatR,
uint32_t fall0 = LPC_GPIOINT->IO0IntStatF; fall0 = LPC_GPIOINT->IO0IntStatF,
uint32_t rise2 = LPC_GPIOINT->IO2IntStatR; rise2 = LPC_GPIOINT->IO2IntStatR,
uint32_t fall2 = LPC_GPIOINT->IO2IntStatF; fall2 = LPC_GPIOINT->IO2IntStatF;
//Clear teh interrupts ASAP // Clear the interrupts ASAP
LPC_GPIOINT->IO0IntClr = LPC_GPIOINT->IO2IntClr = 0xFFFFFFFF; LPC_GPIOINT->IO0IntClr = LPC_GPIOINT->IO2IntClr = 0xFFFFFFFF;
NVIC_ClearPendingIRQ(EINT3_IRQn); NVIC_ClearPendingIRQ(EINT3_IRQn);
uint8_t bitloc;
if (rise0 == 0) /* multiple pins changes happened.*/
goto fall0; if (rise0) while (rise0 > 0) { // Continue as long as there are interrupts pending
/* multiple pins changes happened.*/ const uint8_t bitloc = 31 - __CLZ(rise0); //CLZ returns number of leading zeros, 31 minus that is location of first pending interrupt
while(rise0 > 0) { //Continue as long as there are interrupts pending if (callbacksP0[bitloc] != NULL) callbacksP0[bitloc]();
bitloc = 31 - __CLZ(rise0); //CLZ returns number of leading zeros, 31 minus that is location of first pending interrupt rise0 -= _BV(bitloc);
if (callbacksP0[bitloc]!=0) }
callbacksP0[bitloc]();
rise0 -= 1<<bitloc; if (fall0) while (fall0 > 0) {
} const uint8_t bitloc = 31 - __CLZ(fall0);
fall0: if (callbacksP0[bitloc] != NULL) callbacksP0[bitloc]();
if (fall0==0) fall0 -= _BV(bitloc);
goto rise2; }
/* if (isPowerOf2(fall0) && callbacksP0[31 - __CLZ(rise0)])
callbacksP0[31 - __CLZ(rise0)](); */ if (rise2) while(rise2 > 0) {
//LPC_GPIOINT->IO0IntClr = fall0;*/ const uint8_t bitloc = 31 - __CLZ(rise2);
else { if (callbacksP2[bitloc] != NULL) callbacksP2[bitloc]();
while(fall0 > 0) { //LPC_GPIOINT->IO2IntClr = 1 << bitloc;
bitloc = 31 - __CLZ(fall0); rise2 -= _BV(bitloc);
if (callbacksP0[bitloc]!=0) }
callbacksP0[bitloc]();
fall0 -= 1<<bitloc; if (fall2) while (fall2 > 0) {
const uint8_t bitloc = 31 - __CLZ(fall2);
if (callbacksP2[bitloc] != NULL) callbacksP2[bitloc]();
//LPC_GPIOINT->IO2IntClr = 1 << bitloc;
fall2 -= _BV(bitloc);
}
//NVIC_ClearPendingIRQ(EINT3_IRQn);
//LPC_GPIOINT->IO0IntClr = LPC_GPIOINT->IO2IntClr = 0xFFFFFFFF;
//NVIC_ClearPendingIRQ(EINT3_IRQn);
} }
}
rise2:
if (rise2==0)
goto fall2;
/*if ((rise2 & (rise2 - 1)) == 0) {
callbacksP2[rise2]();
//LPC_GPIOINT->IO2IntClr = rise2;
}*/
else {
while(rise2 > 0) {
bitloc = 31 - __CLZ(rise2);
if (callbacksP2[bitloc]!=0)
callbacksP2[bitloc]();
//LPC_GPIOINT->IO2IntClr = 1 << bitloc;
rise2 -= 1<<bitloc;
}
}
fall2:
if (fall2==0)
goto end;
/*if ((fall2 & (fall2 - 1)) == 0) {
callbacksP2[fall2]();
//LPC_GPIOINT->IO2IntClr = fall2;
}*/
else {
while(fall2 > 0) {
bitloc = 31 - __CLZ(fall2);
if (callbacksP2[bitloc]!=0)
callbacksP2[bitloc]();
//LPC_GPIOINT->IO2IntClr = 1 << bitloc;
fall2 -= 1<<bitloc;
}
end:
//NVIC_ClearPendingIRQ(EINT3_IRQn);
//LPC_GPIOINT->IO0IntClr = LPC_GPIOINT->IO2IntClr = 0xFFFFFFFF;
//NVIC_ClearPendingIRQ(EINT3_IRQn);
return; //silences warning
}
}
#endif #endif
#endif // TARGET_LPC1768 #endif // TARGET_LPC1768

View file

@ -21,19 +21,15 @@
*/ */
#ifdef TARGET_LPC1768 #ifdef TARGET_LPC1768
#include <lpc17xx_pinsel.h> #include <lpc17xx_pinsel.h>
#include "HAL.h" #include "HAL.h"
#include "../../macros.h" #include "../../core/macros.h"
// Interrupts // Interrupts
void cli(void) { __disable_irq(); } // Disable void cli(void) { __disable_irq(); } // Disable
void sei(void) { __enable_irq(); } // Enable void sei(void) { __enable_irq(); } // Enable
// Program Memory
void serialprintPGM(const char * str){
usb_serial.print(str);
}
// Time functions // Time functions
void _delay_ms(int delay_ms) { void _delay_ms(int delay_ms) {
delay (delay_ms); delay (delay_ms);

View file

@ -38,7 +38,7 @@
#define _BV(bit) (1 << (bit)) #define _BV(bit) (1 << (bit))
#define E2END 4096 //EEPROM end address #define E2END 0xFFF // EEPROM end address
typedef uint8_t byte; typedef uint8_t byte;
#define PROGMEM #define PROGMEM
@ -49,10 +49,10 @@ typedef uint8_t byte;
#define max(a,b) ((a)>(b)?(a):(b)) #define max(a,b) ((a)>(b)?(a):(b))
#define abs(x) ((x)>0?(x):-(x)) #define abs(x) ((x)>0?(x):-(x))
#ifndef isnan #ifndef isnan
#define isnan std::isnan #define isnan std::isnan
#endif #endif
#ifndef isinf #ifndef isinf
#define isinf std::isinf #define isinf std::isinf
#endif #endif
//not constexpr until c++14 //not constexpr until c++14
@ -73,15 +73,15 @@ extern "C" void GpioEnableInt(uint32_t port, uint32_t pin, uint32_t mode);
extern "C" void GpioDisableInt(uint32_t port, uint32_t pin); extern "C" void GpioDisableInt(uint32_t port, uint32_t pin);
// Program Memory // Program Memory
#define pgm_read_ptr(address_short) (*(address_short)) #define pgm_read_ptr(addr) (*((void**)(addr)))
#define pgm_read_byte_near(address_short) (*address_short) #define pgm_read_byte_near(addr) (*((uint8_t*)(addr)))
#define pgm_read_byte(address_short) pgm_read_byte_near(address_short) #define pgm_read_float_near(addr) (*((float*)(addr)))
#define pgm_read_float_near(address_short) (*address_short) #define pgm_read_word_near(addr) (*((uint16_t*)(addr)))
#define pgm_read_float(address_short) pgm_read_float_near(address_short) #define pgm_read_dword_near(addr) (*((uint32_t*)(addr)))
#define pgm_read_word_near(address_short) (*address_short) #define pgm_read_byte(addr) pgm_read_byte_near(addr)
#define pgm_read_word(address_short) pgm_read_word_near(address_short) #define pgm_read_float(addr) pgm_read_float_near(addr)
#define pgm_read_dword_near(address_short) (*address_short) #define pgm_read_word(addr) pgm_read_word_near(addr)
#define pgm_read_dword(address_short) pgm_read_dword_near(address_short) #define pgm_read_dword(addr) pgm_read_dword_near(addr)
#define sprintf_P sprintf #define sprintf_P sprintf
#define strstr_P strstr #define strstr_P strstr
@ -90,8 +90,6 @@ extern "C" void GpioDisableInt(uint32_t port, uint32_t pin);
#define strcpy_P strcpy #define strcpy_P strcpy
#define snprintf_P snprintf #define snprintf_P snprintf
void serialprintPGM(const char *);
// Time functions // Time functions
extern "C" { extern "C" {
void delay(int milis); void delay(int milis);

View file

@ -1,4 +1,4 @@
#dynaomic build flags for generic compile options #dynamic build flags for generic compile options
if __name__ == "__main__": if __name__ == "__main__":
print " ".join([ "-std=gnu11", print " ".join([ "-std=gnu11",
"-std=gnu++11", "-std=gnu++11",

View file

@ -1,21 +1,17 @@
#ifdef TARGET_LPC1768 #ifdef TARGET_LPC1768
#include "../persistent_store_api.h"
#include "../../../types.h" #include "../../inc/MarlinConfig.h"
#include "../../../language.h"
#include "../../../serial.h" #if ENABLED(EEPROM_SETTINGS)
#include "../../../utility.h"
#include "../persistent_store_api.h"
#include "chanfs/diskio.h" #include "chanfs/diskio.h"
#include "chanfs/ff.h" #include "chanfs/ff.h"
#if ENABLED(EEPROM_SETTINGS)
namespace HAL { namespace HAL {
namespace PersistentStore { namespace PersistentStore {
FATFS fat_fs; FATFS fat_fs;
FIL eeprom_file; FIL eeprom_file;
@ -25,7 +21,7 @@ bool access_start() {
return (res == FR_OK); return (res == FR_OK);
} }
bool access_finish(){ bool access_finish() {
f_close(&eeprom_file); f_close(&eeprom_file);
f_unmount(""); f_unmount("");
return true; return true;
@ -48,8 +44,8 @@ void read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc) {
pos = pos + size; pos = pos + size;
} }
} } // PersistentStore
} } // HAL
#endif // EEPROM_SETTINGS #endif // EEPROM_SETTINGS
#endif // ARDUINO_ARCH_AVR #endif // TARGET_LPC1768

View file

@ -22,12 +22,12 @@
#ifndef __HAL_PINMAPPING_H__ #ifndef __HAL_PINMAPPING_H__
#define __HAL_PINMAPPING_H__ #define __HAL_PINMAPPING_H__
#include "../../../macros.h" #include "../../core/macros.h"
struct pin_data { uint8_t port, pin; }; struct pin_data { uint8_t port, pin; };
struct adc_pin_data { uint8_t port, pin, adc; }; struct adc_pin_data { uint8_t port, pin, adc; };
#if defined(IS_REARM) #if ENABLED(IS_REARM)
#include "pinmap_re_arm.h" #include "pinmap_re_arm.h"
#else #else
#error "HAL: LPC1768: No defined pin-mapping" #error "HAL: LPC1768: No defined pin-mapping"

View file

@ -48,11 +48,10 @@
*/ */
#ifndef servo_private_h #ifndef SERVO_PRIVATE_H
#define servo_private_h #define SERVO_PRIVATE_H
#include <inttypes.h>
#include <stdint.h>
// Macros // Macros
//values in microseconds //values in microseconds
@ -83,5 +82,4 @@ typedef struct {
extern uint8_t ServoCount; extern uint8_t ServoCount;
extern ServoInfo_t servo_info[MAX_SERVOS]; extern ServoInfo_t servo_info[MAX_SERVOS];
#endif // SERVO_PRIVATE_H
#endif

View file

@ -22,7 +22,7 @@
#ifdef TARGET_LPC1768 #ifdef TARGET_LPC1768
#include "../../../MarlinConfig.h" #include "../../inc/MarlinConfig.h"
#include "lpc17xx_wdt.h" #include "lpc17xx_wdt.h"
#include "watchdog.h" #include "watchdog.h"

View file

@ -2,7 +2,7 @@
#include "HAL_Servo_Teensy.h" #include "HAL_Servo_Teensy.h"
#include "../../../MarlinConfig.h" #include "../../inc/MarlinConfig.h"
int8_t libServo::attach(int pin) { int8_t libServo::attach(int pin) {

View file

@ -30,8 +30,6 @@
// Includes // Includes
// -------------------------------------------------------------------------- // --------------------------------------------------------------------------
#include <stdint.h>
#include "Arduino.h" #include "Arduino.h"
#include "fastio_Teensy.h" #include "fastio_Teensy.h"
@ -39,10 +37,13 @@
#include "HAL_timers_Teensy.h" #include "HAL_timers_Teensy.h"
#include <stdint.h>
// -------------------------------------------------------------------------- // --------------------------------------------------------------------------
// Defines // Defines
// -------------------------------------------------------------------------- // --------------------------------------------------------------------------
#undef MOTHERBOARD
#define MOTHERBOARD BOARD_TEENSY35_36 #define MOTHERBOARD BOARD_TEENSY35_36
#define IS_32BIT_TEENSY (defined(__MK64FX512__) || defined(__MK66FX1M0__)) #define IS_32BIT_TEENSY (defined(__MK64FX512__) || defined(__MK66FX1M0__))
@ -79,9 +80,10 @@
// Fix bug in pgm_read_ptr // Fix bug in pgm_read_ptr
#undef pgm_read_ptr #undef pgm_read_ptr
#define pgm_read_ptr(addr) (*(addr)) #define pgm_read_ptr(addr) (*((void**)(addr)))
// Add type-checking to pgm_read_word
#undef pgm_read_word #undef pgm_read_word
#define pgm_read_word(addr) (*(addr)) #define pgm_read_word(addr) (*((uint16_t*)(addr)))
#define RST_POWER_ON 1 #define RST_POWER_ON 1
#define RST_EXTERNAL 2 #define RST_EXTERNAL 2

View file

@ -4,7 +4,7 @@
#include <SPI.h> #include <SPI.h>
#include <pins_arduino.h> #include <pins_arduino.h>
#include "spi_pins.h" #include "spi_pins.h"
#include "../../../macros.h" #include "../../core/macros.h"
static SPISettings spiConfig; static SPISettings spiConfig;

View file

@ -25,7 +25,6 @@
* Teensy3.6 (__MK66FX1M0__) * Teensy3.6 (__MK66FX1M0__)
*/ */
#ifndef _HAL_TIMERS_TEENSY_H #ifndef _HAL_TIMERS_TEENSY_H
#define _HAL_TIMERS_TEENSY_H #define _HAL_TIMERS_TEENSY_H

View file

@ -1,14 +1,11 @@
#if defined(__MK64FX512__) || defined(__MK66FX1M0__) #if defined(__MK64FX512__) || defined(__MK66FX1M0__)
#include "../persistent_store_api.h" #include "../../inc/MarlinConfig.h"
#include "../../../types.h"
#include "../../../language.h"
#include "../../../serial.h"
#include "../../../utility.h"
#if ENABLED(EEPROM_SETTINGS) #if ENABLED(EEPROM_SETTINGS)
#include "../persistent_store_api.h"
namespace HAL { namespace HAL {
namespace PersistentStore { namespace PersistentStore {
@ -16,7 +13,7 @@ bool access_start() {
return true; return true;
} }
bool access_finish(){ bool access_finish() {
return true; return true;
} }
@ -51,8 +48,8 @@ void read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc) {
} while (--size); } while (--size);
} }
} } // PersistentStore
} } // HAL
#endif // EEPROM_SETTINGS #endif // EEPROM_SETTINGS
#endif // ARDUINO_ARCH_AVR #endif // __MK64FX512__ || __MK66FX1M0__

View file

@ -22,7 +22,7 @@
#if defined(__MK64FX512__) || defined(__MK66FX1M0__) #if defined(__MK64FX512__) || defined(__MK66FX1M0__)
#include "../../../Marlin.h" #include "../../Marlin.h"
#if ENABLED(USE_WATCHDOG) #if ENABLED(USE_WATCHDOG)

View file

@ -23,16 +23,16 @@
#ifndef WATCHDOG_TEENSY_H #ifndef WATCHDOG_TEENSY_H
#define WATCHDOG_TEENSY_H #define WATCHDOG_TEENSY_H
//#include "../../../Marlin.h" #include "../HAL.h"
// Arduino Due core now has watchdog support // Arduino Due core now has watchdog support
void watchdog_init(); void watchdog_init();
inline void watchdog_reset() { inline void watchdog_reset() {
// Watchdog refresh sequence // Watchdog refresh sequence
WDOG_REFRESH = 0xA602; WDOG_REFRESH = 0xA602;
WDOG_REFRESH = 0xB480; WDOG_REFRESH = 0xB480;
} }
#endif /* WATCHDOG_TEENSY_H */ #endif // WATCHDOG_TEENSY_H

View file

@ -23,8 +23,6 @@
#ifndef HAL_SPI_PINS_H_ #ifndef HAL_SPI_PINS_H_
#define HAL_SPI_PINS_H_ #define HAL_SPI_PINS_H_
#include "../../MarlinConfig.h"
#ifdef ARDUINO_ARCH_SAM #ifdef ARDUINO_ARCH_SAM
#include "HAL_DUE/spi_pins.h" #include "HAL_DUE/spi_pins.h"

View file

@ -25,7 +25,7 @@
* Not platform dependent. * Not platform dependent.
*/ */
#include "../../MarlinConfig.h" #include "../inc/MarlinConfig.h"
#if ENABLED(I2C_EEPROM) #if ENABLED(I2C_EEPROM)

View file

@ -25,7 +25,7 @@
* Not platform dependent. * Not platform dependent.
*/ */
#include "../../MarlinConfig.h" #include "../inc/MarlinConfig.h"
#if ENABLED(SPI_EEPROM) #if ENABLED(SPI_EEPROM)

View file

@ -30,4 +30,4 @@
#define MultiU32X32toH32(intRes, longIn1, longIn2) intRes = ((uint64_t)longIn1 * longIn2 + 0x80000000) >> 32 #define MultiU32X32toH32(intRes, longIn1, longIn2) intRes = ((uint64_t)longIn1 * longIn2 + 0x80000000) >> 32
#define MultiU32X24toH32(intRes, longIn1, longIn2) intRes = ((uint64_t)longIn1 * longIn2 + 0x00800000) >> 24 #define MultiU32X24toH32(intRes, longIn1, longIn2) intRes = ((uint64_t)longIn1 * longIn2 + 0x00800000) >> 24
#endif #endif // MATH_32BIT_H

View file

@ -12,8 +12,7 @@ bool access_finish();
bool write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc); bool write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc);
void read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc) ; void read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc) ;
} } // PersistentStore
} } // HAL
#endif // _PERSISTENT_STORE_H_
#endif /* _PERSISTANT_STORE_H_ */

View file

@ -52,7 +52,7 @@
*/ */
#include "../../MarlinConfig.h" #include "../inc/MarlinConfig.h"
#include "HAL.h" #include "HAL.h"

View file

@ -76,7 +76,7 @@
#include "HAL_LPC1768/LPC1768_Servo.h" #include "HAL_LPC1768/LPC1768_Servo.h"
#else #else
#include <inttypes.h> #include <stdint.h>
#if defined(ARDUINO_ARCH_AVR) || defined(ARDUINO_ARCH_SAM) #if defined(ARDUINO_ARCH_AVR) || defined(ARDUINO_ARCH_SAM)
// we're good to go // we're good to go

View file

@ -21,7 +21,7 @@
*/ */
/** /**
servo.h - Interrupt driven Servo library for Arduino using 16 bit timers- Version 2 servo_private.h - Interrupt driven Servo library for Arduino using 16 bit timers- Version 2
Copyright (c) 2009 Michael Margolis. All right reserved. Copyright (c) 2009 Michael Margolis. All right reserved.
This library is free software; you can redistribute it and/or This library is free software; you can redistribute it and/or
@ -39,10 +39,10 @@
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/ */
#ifndef servo_private_h #ifndef SERVO_PRIVATE_H
#define servo_private_h #define SERVO_PRIVATE_H
#include <inttypes.h> #include <stdint.h>
// Architecture specific include // Architecture specific include
#ifdef ARDUINO_ARCH_AVR #ifdef ARDUINO_ARCH_AVR
@ -99,5 +99,4 @@ extern ServoInfo_t servo_info[MAX_SERVOS];
extern void initISR(timer16_Sequence_t timer); extern void initISR(timer16_Sequence_t timer);
extern void finISR(timer16_Sequence_t timer); extern void finISR(timer16_Sequence_t timer);
#endif // SERVO_PRIVATE_H
#endif