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

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

View File

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

View File

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

View File

@ -60,7 +60,7 @@
* 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)

View File

@ -34,29 +34,29 @@
#ifndef LPC1768_SERVO_H
#define LPC1768_SERVO_H
#include <inttypes.h>
#include <stdint.h>
class Servo {
public:
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, int min, int max); // as above but also sets min and max values for writes.
void detach();
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 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 DEACTIVATE_SERVOS_AFTER_MOVE wait SERVO_DELAY, then detach
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)
bool attached(); // return true if this servo is attached, otherwise false
class Servo {
public:
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, int min, int max); // as above but also sets min and max values for writes.
void detach();
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 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 DEACTIVATE_SERVOS_AFTER_MOVE wait SERVO_DELAY, then detach
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)
bool attached(); // return true if this servo is attached, otherwise false
private:
uint8_t servoIndex; // index into the channel data for this servo
int min;
int max;
};
private:
uint8_t servoIndex; // index into the channel data for this servo
int min;
int max;
};
#define HAL_SERVO_LIB Servo
#define HAL_SERVO_LIB Servo
#endif // LPC1768_SERVO_H

View File

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

View File

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

View File

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

View File

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

View File

@ -38,7 +38,7 @@
#define _BV(bit) (1 << (bit))
#define E2END 4096 //EEPROM end address
#define E2END 0xFFF // EEPROM end address
typedef uint8_t byte;
#define PROGMEM
@ -49,10 +49,10 @@ typedef uint8_t byte;
#define max(a,b) ((a)>(b)?(a):(b))
#define abs(x) ((x)>0?(x):-(x))
#ifndef isnan
#define isnan std::isnan
#define isnan std::isnan
#endif
#ifndef isinf
#define isinf std::isinf
#define isinf std::isinf
#endif
//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);
// Program Memory
#define pgm_read_ptr(address_short) (*(address_short))
#define pgm_read_byte_near(address_short) (*address_short)
#define pgm_read_byte(address_short) pgm_read_byte_near(address_short)
#define pgm_read_float_near(address_short) (*address_short)
#define pgm_read_float(address_short) pgm_read_float_near(address_short)
#define pgm_read_word_near(address_short) (*address_short)
#define pgm_read_word(address_short) pgm_read_word_near(address_short)
#define pgm_read_dword_near(address_short) (*address_short)
#define pgm_read_dword(address_short) pgm_read_dword_near(address_short)
#define pgm_read_ptr(addr) (*((void**)(addr)))
#define pgm_read_byte_near(addr) (*((uint8_t*)(addr)))
#define pgm_read_float_near(addr) (*((float*)(addr)))
#define pgm_read_word_near(addr) (*((uint16_t*)(addr)))
#define pgm_read_dword_near(addr) (*((uint32_t*)(addr)))
#define pgm_read_byte(addr) pgm_read_byte_near(addr)
#define pgm_read_float(addr) pgm_read_float_near(addr)
#define pgm_read_word(addr) pgm_read_word_near(addr)
#define pgm_read_dword(addr) pgm_read_dword_near(addr)
#define sprintf_P sprintf
#define strstr_P strstr
@ -90,8 +90,6 @@ extern "C" void GpioDisableInt(uint32_t port, uint32_t pin);
#define strcpy_P strcpy
#define snprintf_P snprintf
void serialprintPGM(const char *);
// Time functions
extern "C" {
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__":
print " ".join([ "-std=gnu11",
"-std=gnu++11",

View File

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

View File

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

View File

@ -81,4 +81,4 @@ if (pin == 7) return;
#define NAME_FORMAT(p) PSTR("%-##p##s")
// #define PRINT_ARRAY_NAME(x) do {sprintf_P(buffer, NAME_FORMAT(MAX_NAME_LENGTH) , pin_array[x].name); SERIAL_ECHO(buffer);} while (0)
#define PRINT_ARRAY_NAME(x) do {sprintf_P(buffer, PSTR("%-35s") , pin_array[x].name); SERIAL_ECHO(buffer);} while (0)
#define GET_ARRAY_IS_DIGITAL(x) !pin_Re_ARM_analog
#define GET_ARRAY_IS_DIGITAL(x) !pin_Re_ARM_analog

View File

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

View File

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