[2.0.x] LPC176x Serial cleanup (#11032)

This commit is contained in:
Chris Pepper 2018-06-17 02:59:22 +01:00 committed by Scott Lahteine
parent c1269c2ec1
commit 0312c42f9d
17 changed files with 152 additions and 290 deletions

View file

@ -123,8 +123,8 @@ void HardwareSerial::begin(uint32_t baudrate) {
Baudrate = baudrate; Baudrate = baudrate;
} }
int HardwareSerial::peek() { int16_t HardwareSerial::peek() {
int byte = -1; int16_t byte = -1;
// Temporarily lock out UART receive interrupts during this read so the UART receive // Temporarily lock out UART receive interrupts during this read so the UART receive
// interrupt won't cause problems with the index values // interrupt won't cause problems with the index values
@ -139,8 +139,8 @@ int HardwareSerial::peek() {
return byte; return byte;
} }
int HardwareSerial::read() { int16_t HardwareSerial::read() {
int byte = -1; int16_t byte = -1;
// Temporarily lock out UART receive interrupts during this read so the UART receive // Temporarily lock out UART receive interrupts during this read so the UART receive
// interrupt won't cause problems with the index values // interrupt won't cause problems with the index values
@ -201,7 +201,7 @@ size_t HardwareSerial::write(uint8_t send) {
} }
#endif #endif
int HardwareSerial::available() { size_t HardwareSerial::available() {
return (RxQueueWritePos + RX_BUFFER_SIZE - RxQueueReadPos) % RX_BUFFER_SIZE; return (RxQueueWritePos + RX_BUFFER_SIZE - RxQueueReadPos) % RX_BUFFER_SIZE;
} }
@ -210,16 +210,17 @@ void HardwareSerial::flush() {
RxQueueReadPos = 0; RxQueueReadPos = 0;
} }
void HardwareSerial::printf(const char *format, ...) { size_t HardwareSerial::printf(const char *format, ...) {
char RxBuffer[256]; char RxBuffer[256];
va_list vArgs; va_list vArgs;
va_start(vArgs, format); va_start(vArgs, format);
int length = vsnprintf(RxBuffer, 256, format, vArgs); int length = vsnprintf(RxBuffer, 256, format, vArgs);
va_end(vArgs); va_end(vArgs);
if (length > 0 && length < 256) { if (length > 0 && length < 256) {
for (int i = 0; i < length; ++i) for (size_t i = 0; i < (size_t)length; ++i)
write(RxBuffer[i]); write(RxBuffer[i]);
} }
return length;
} }
void HardwareSerial::IRQHandler() { void HardwareSerial::IRQHandler() {

View file

@ -72,120 +72,20 @@ public:
} }
void begin(uint32_t baudrate); void begin(uint32_t baudrate);
int peek(); int16_t peek();
int read(); int16_t read();
size_t write(uint8_t send); size_t write(uint8_t send);
#if TX_BUFFER_SIZE > 0 #if TX_BUFFER_SIZE > 0
void flushTX(); void flushTX();
#endif #endif
int available(); size_t available();
void flush(); void flush();
void printf(const char *format, ...); size_t printf(const char *format, ...);
operator bool() { return true; } operator bool() { return true; }
void IRQHandler(); void IRQHandler();
#define DEC 10
#define HEX 16
#define OCT 8
#define BIN 2
void print_bin(uint32_t value, uint8_t num_digits) {
uint32_t mask = 1 << (num_digits -1);
for (uint8_t i = 0; i < num_digits; i++) {
if (!(i % 4) && i) printf(" ");
if (!(i % 16) && i) printf(" ");
if (value & mask) printf("1");
else printf("0");
value <<= 1;
}
}
void print(const char value[]) {
printf("%s" , value);
}
void print(char value, int nbase = 0) {
if (nbase == BIN) print_bin(value,8);
else if (nbase == OCT) printf("%3o", value);
else if (nbase == HEX) printf("%2X", value);
else if (nbase == DEC ) printf("%d", value);
else printf("%c" , value);
}
void print(unsigned char value, int nbase = 0) {
if (nbase == BIN) print_bin(value,8);
else if (nbase == OCT) printf("%3o", value);
else if (nbase == HEX) printf("%2X", value);
else printf("%u" , value);
}
void print(int value, int nbase = 0) {
if (nbase == BIN) print_bin(value,16);
else if (nbase == OCT) printf("%6o", value);
else if (nbase == HEX) printf("%4X", value);
else printf("%d", value);
}
void print(unsigned int value, int nbase = 0) {
if (nbase == BIN) print_bin(value,16);
else if (nbase == OCT) printf("%6o", value);
else if (nbase == HEX) printf("%4X", value);
else printf("%u" , value);
}
void print(long value, int nbase = 0) {
if (nbase == BIN) print_bin(value,32);
else if (nbase == OCT) printf("%11o", value);
else if (nbase == HEX) printf("%8X", value);
else printf("%ld" , value);
}
void print(unsigned long value, int nbase = 0) {
if (nbase == BIN) print_bin(value,32);
else if (nbase == OCT) printf("%11o", value);
else if (nbase == HEX) printf("%8X", value);
else printf("%lu" , value);
}
void print(float value, int round = 6) {
printf("%f" , value);
}
void print(double value, int round = 6) {
printf("%f" , value );
}
void println(const char value[]) {
printf("%s\n" , value);
}
void println(char value, int nbase = 0) {
print(value, nbase);
println();
}
void println(unsigned char value, int nbase = 0) {
print(value, nbase);
println();
}
void println(int value, int nbase = 0) {
print(value, nbase);
println();
}
void println(unsigned int value, int nbase = 0) {
print(value, nbase);
println();
}
void println(long value, int nbase = 0) {
print(value, nbase);
println();
}
void println(unsigned long value, int nbase = 0) {
print(value, nbase);
println();
}
void println(float value, int round = 6) {
printf("%f\n" , value );
}
void println(double value, int round = 6) {
printf("%f\n" , value );
}
void println(void) {
print('\n');
}
}; };
#endif // MARLIN_SRC_HAL_HAL_SERIAL_H_ #endif // MARLIN_SRC_HAL_HAL_SERIAL_H_

View file

@ -60,9 +60,11 @@
* 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.
*/ */
#ifdef TARGET_LPC1768
#include "../../inc/MarlinConfig.h" #include "../../inc/MarlinConfig.h"
#if HAS_SERVOS && defined(TARGET_LPC1768) #if HAS_SERVOS
#include "LPC1768_PWM.h" #include "LPC1768_PWM.h"
#include "LPC1768_Servo.h" #include "LPC1768_Servo.h"
@ -157,4 +159,5 @@
} }
} }
#endif // HAS_SERVOS && TARGET_LPC1768 #endif // HAS_SERVOS
#endif // TARGET_LPC1768

View file

@ -29,10 +29,10 @@
* For TARGET_LPC1768 * For TARGET_LPC1768
*/ */
#include "../../inc/MarlinConfig.h"
#ifdef TARGET_LPC1768 #ifdef TARGET_LPC1768
#include "../../inc/MarlinConfig.h"
// -------------------------------------------------------------------------- // --------------------------------------------------------------------------
// Software SPI // Software SPI
// -------------------------------------------------------------------------- // --------------------------------------------------------------------------

View file

@ -253,7 +253,7 @@ void SoftwareSerial::end() {
// Read data from buffer // Read data from buffer
int SoftwareSerial::read() { int16_t SoftwareSerial::read() {
if (!isListening()) return -1; if (!isListening()) return -1;
// Empty buffer? // Empty buffer?
@ -265,7 +265,7 @@ int SoftwareSerial::read() {
return d; return d;
} }
int SoftwareSerial::available() { size_t SoftwareSerial::available() {
if (!isListening()) return 0; if (!isListening()) return 0;
return (_receive_buffer_tail + _SS_MAX_RX_BUFF - _receive_buffer_head) % _SS_MAX_RX_BUFF; return (_receive_buffer_tail + _SS_MAX_RX_BUFF - _receive_buffer_head) % _SS_MAX_RX_BUFF;
@ -314,7 +314,7 @@ void SoftwareSerial::flush() {
sei(); sei();
} }
int SoftwareSerial::peek() { int16_t SoftwareSerial::peek() {
if (!isListening()) if (!isListening())
return -1; return -1;

View file

@ -93,11 +93,11 @@ public:
bool isListening() { return this == active_object; } bool isListening() { return this == active_object; }
bool stopListening(); bool stopListening();
bool overflow() { bool ret = _buffer_overflow; if (ret) _buffer_overflow = false; return ret; } bool overflow() { bool ret = _buffer_overflow; if (ret) _buffer_overflow = false; return ret; }
int peek(); int16_t peek();
virtual size_t write(uint8_t byte); virtual size_t write(uint8_t byte);
virtual int read(); virtual int16_t read();
virtual int available(); virtual size_t available();
virtual void flush(); virtual void flush();
operator bool() { return true; } operator bool() { return true; }

View file

@ -23,6 +23,8 @@
// adapted from I2C/master/master.c example // adapted from I2C/master/master.c example
// https://www-users.cs.york.ac.uk/~pcc/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html // https://www-users.cs.york.ac.uk/~pcc/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html
#ifdef TARGET_LPC1768
#include "../../../inc/MarlinConfigPre.h" #include "../../../inc/MarlinConfigPre.h"
#if MB(MKS_SBASE) #if MB(MKS_SBASE)
@ -135,3 +137,4 @@ uint8_t digipot_mcp4451_send_byte(uint8_t data) {
#endif #endif
#endif // MB(MKS_SBASE) #endif // MB(MKS_SBASE)
#endif // TARGET_LPC1768

View file

@ -30,177 +30,131 @@
#include <stdarg.h> #include <stdarg.h>
#include <stdio.h> #include <stdio.h>
#include <Print.h>
/** /**
* Generic RingBuffer * Generic RingBuffer
* T type of the buffer array * T type of the buffer array
* S size of the buffer (must be power of 2) * S size of the buffer (must be power of 2)
*
* todo: optimise
*/ */
template <typename T, uint32_t S> class RingBuffer { template <typename T, uint32_t S> class RingBuffer {
public: public:
RingBuffer() { index_read = index_write = 0; } RingBuffer() {index_read = index_write = 0;}
uint32_t available() volatile { return buffer_mask & (index_write - index_read); }
uint32_t free() volatile { return buffer_size - available(); } uint32_t available() {return mask(index_write - index_read);}
bool empty() volatile { return (buffer_mask & index_read) == (buffer_mask & index_write); } uint32_t free() {return buffer_size - available();}
bool full() volatile { return index_read == buffer_mask & (index_write + 1); } bool empty() {return index_read == index_write;}
void clear() volatile { index_read = index_write = 0; } bool full() {return next(index_write) == index_read;}
bool peek(T *value) volatile { void clear() {index_read = index_write = 0;}
if (value == 0 || available() == 0)
return false; bool peek(T *const value) {
*value = buffer[buffer_mask & index_read]; if (value == nullptr || empty()) return false;
*value = buffer[index_read];
return true; return true;
} }
int read() volatile {
if ((buffer_mask & index_read) == (buffer_mask & index_write)) return -1; uint32_t read(T *const value) {
T val = buffer[buffer_mask & index_read]; if (value == nullptr || empty()) return 0;
++index_read; *value = buffer[index_read];
return val; index_read = next(index_read);
return 1;
} }
bool write(T value) volatile {
uint32_t next_head = buffer_mask & (index_write + 1); uint32_t write(T value) {
if (next_head != index_read) { uint32_t next_head = next(index_write);
buffer[buffer_mask & index_write] = value; if (next_head == index_read) return 0; // buffer full
index_write = next_head; buffer[index_write] = value;
return true; index_write = next_head;
} return 1;
return false;
} }
private: private:
inline uint32_t mask(uint32_t val) {
return val & buffer_mask;
}
inline uint32_t next(uint32_t val) {
return mask(val + 1);
}
static const uint32_t buffer_size = S; static const uint32_t buffer_size = S;
static const uint32_t buffer_mask = buffer_size - 1; static const uint32_t buffer_mask = buffer_size - 1;
volatile T buffer[buffer_size]; T buffer[buffer_size];
volatile uint32_t index_write; volatile uint32_t index_write;
volatile uint32_t index_read; volatile uint32_t index_read;
}; };
class HalSerial { /**
* Serial Interface Class
* Data is injected directly into, and consumed from, the fifo buffers
*/
class HalSerial: public Print {
public: public:
#if ENABLED(EMERGENCY_PARSER) #if ENABLED(EMERGENCY_PARSER)
EmergencyParser::State emergency_state; EmergencyParser::State emergency_state;
#endif #endif
HalSerial() { host_connected = false; } HalSerial() : host_connected(false) { }
virtual ~HalSerial() { }
void begin(int32_t baud) { operator bool() { return host_connected; }
}
int peek() { void begin(int32_t baud) { }
int16_t peek() {
uint8_t value; uint8_t value;
return receive_buffer.peek(&value) ? value : -1; return receive_buffer.peek(&value) ? value : -1;
} }
int read() { return receive_buffer.read(); } int16_t read() {
uint8_t value;
size_t write(char c) { return host_connected ? transmit_buffer.write((uint8_t)c) : 0; } return receive_buffer.read(&value) ? value : -1;
operator bool() { return host_connected; }
uint16_t available() {
return (uint16_t)receive_buffer.available();
} }
void flush() { receive_buffer.clear(); } size_t write(const uint8_t c) {
if (!host_connected) return 0; // Do not fill buffer when host disconnected
while (transmit_buffer.write(c) == 0) { // Block until there is free room in buffer
if (!host_connected) return 0; // Break infinite loop on host disconect
}
return 1;
}
uint8_t availableForWrite(void){ size_t available() {
return (size_t)receive_buffer.available();
}
void flush() {
receive_buffer.clear();
}
uint8_t availableForWrite(void) {
return transmit_buffer.free() > 255 ? 255 : (uint8_t)transmit_buffer.free(); return transmit_buffer.free() > 255 ? 255 : (uint8_t)transmit_buffer.free();
} }
void flushTX(void){ void flushTX(void) {
if (host_connected) while (transmit_buffer.available() && host_connected) { /* nada */}
while (transmit_buffer.available()) { /* nada */ }
} }
void printf(const char *format, ...) { size_t printf(const char *format, ...) {
static char buffer[256]; static char buffer[256];
va_list vArgs; va_list vArgs;
va_start(vArgs, format); va_start(vArgs, format);
int length = vsnprintf((char *) buffer, 256, (char const *) format, vArgs); int length = vsnprintf((char *) buffer, 256, (char const *) format, vArgs);
va_end(vArgs); va_end(vArgs);
size_t i = 0;
if (length > 0 && length < 256) { if (length > 0 && length < 256) {
if (host_connected) { while (i < (size_t)length && host_connected) {
for (int i = 0; i < length;) { i += transmit_buffer.write(buffer[i]);
if (transmit_buffer.write(buffer[i])) {
++i;
}
}
} }
} }
return i;
} }
#define DEC 10 RingBuffer<uint8_t, 128> receive_buffer;
#define HEX 16 RingBuffer<uint8_t, 128> transmit_buffer;
#define OCT 8
#define BIN 2
void print_bin(uint32_t value, uint8_t num_digits) {
uint32_t mask = 1 << (num_digits -1);
for (uint8_t i = 0; i < num_digits; i++) {
if (!(i % 4) && i) write(' ');
if (!(i % 16) && i) write(' ');
if (value & mask) write('1');
else write('0');
value <<= 1;
}
}
void print(const char value[]) { printf("%s" , value); }
void print(char value, int nbase = 0) {
if (nbase == BIN) print_bin(value, 8);
else if (nbase == OCT) printf("%3o", value);
else if (nbase == HEX) printf("%2X", value);
else if (nbase == DEC ) printf("%d", value);
else printf("%c" , value);
}
void print(unsigned char value, int nbase = 0) {
if (nbase == BIN) print_bin(value, 8);
else if (nbase == OCT) printf("%3o", value);
else if (nbase == HEX) printf("%2X", value);
else printf("%u" , value);
}
void print(int value, int nbase = 0) {
if (nbase == BIN) print_bin(value, 16);
else if (nbase == OCT) printf("%6o", value);
else if (nbase == HEX) printf("%4X", value);
else printf("%d", value);
}
void print(unsigned int value, int nbase = 0) {
if (nbase == BIN) print_bin(value, 16);
else if (nbase == OCT) printf("%6o", value);
else if (nbase == HEX) printf("%4X", value);
else printf("%u" , value);
}
void print(long value, int nbase = 0) {
if (nbase == BIN) print_bin(value, 32);
else if (nbase == OCT) printf("%11o", value);
else if (nbase == HEX) printf("%8X", value);
else printf("%ld" , value);
}
void print(unsigned long value, int nbase = 0) {
if (nbase == BIN) print_bin(value, 32);
else if (nbase == OCT) printf("%11o", value);
else if (nbase == HEX) printf("%8X", value);
else printf("%lu" , value);
}
void print(float value, int round = 6) { printf("%f" , value); }
void print(double value, int round = 6) { printf("%f" , value); }
void println(const char value[]) { printf("%s\n" , value); }
void println(char value, int nbase = 0) { print(value, nbase); println(); }
void println(unsigned char value, int nbase = 0) { print(value, nbase); println(); }
void println(int value, int nbase = 0) { print(value, nbase); println(); }
void println(unsigned int value, int nbase = 0) { print(value, nbase); println(); }
void println(long value, int nbase = 0) { print(value, nbase); println(); }
void println(unsigned long value, int nbase = 0) { print(value, nbase); println(); }
void println(float value, int round = 6) { printf("%f\n" , value); }
void println(double value, int round = 6) { printf("%f\n" , value); }
void println(void) { print('\n'); }
volatile RingBuffer<uint8_t, 128> receive_buffer;
volatile RingBuffer<uint8_t, 128> transmit_buffer;
volatile bool host_connected; volatile bool host_connected;
}; };

View file

@ -49,7 +49,7 @@ else:
"-fno-threadsafe-statics" "-fno-threadsafe-statics"
], ],
LINKFLAGS=[ LINKFLAGS=[
"-Wl,-Tframeworks/CMSIS/LPC1768/Re-ARM/LPC1768.ld,--gc-sections", "-Wl,-Tframeworks/CMSIS/LPC1768/system/LPC1768.ld,--gc-sections",
"-Os", "-Os",
"-mcpu=cortex-m3", "-mcpu=cortex-m3",
"-mthumb", "-mthumb",

View file

@ -35,53 +35,52 @@ extern "C" {
#include "LPC1768_PWM.h" #include "LPC1768_PWM.h"
static __INLINE uint32_t SysTick_Config(uint32_t ticks) { static __INLINE uint32_t SysTick_Config(uint32_t ticks) {
if (ticks > SysTick_LOAD_RELOAD_Msk) if (ticks > SysTick_LOAD_RELOAD_Msk) return 1;
return (1); /* Reload value impossible */
SysTick->LOAD = (ticks & SysTick_LOAD_RELOAD_Msk) - 1; /* set reload register */ SysTick->LOAD = (ticks & SysTick_LOAD_RELOAD_Msk) - 1; // Set reload register
NVIC_SetPriority(SysTick_IRQn, NVIC_EncodePriority(0, 0, 0)); /* set Priority for Cortex-M3 System Interrupts */ SysTick->VAL = 0; // Load the SysTick Counter Value
SysTick->VAL = 0; /* Load the SysTick Counter Value */
SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk |
SysTick_CTRL_TICKINT_Msk | SysTick_CTRL_TICKINT_Msk |
SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ SysTick_CTRL_ENABLE_Msk; // Enable SysTick IRQ and SysTick Timer
return (0); /* Function successful */
NVIC_SetPriority(SysTick_IRQn, NVIC_EncodePriority(0, 0, 0)); // Set Priority for Cortex-M3 System Interrupts
return 0;
} }
extern "C" { extern "C" {
extern void disk_timerproc(void); extern int isLPC1769();
volatile uint32_t _millis; extern void disk_timerproc(void);
void SysTick_Handler(void) { volatile uint32_t _millis;
++_millis;
disk_timerproc(); /* Disk timer process */
}
}
// runs after clock init and before global static constructors void SysTick_Handler(void) {
extern "C" void SystemPostInit() { ++_millis;
_millis = 0; // initialise the millisecond counter value; disk_timerproc();
SysTick_Config(SystemCoreClock / 1000); // start millisecond global counter
GPIO_SetDir(4, 1UL << 28, 1);
for (int i = 0; i < 4; ++i) {
GPIO_SetValue(4, 1UL << 28);
delay(100);
GPIO_ClearValue(4, 1UL << 28);
delay(100);
} }
}
// detect 17x[4-8] (100MHz) or 17x9 (120MHz) // Runs after clock init and before global static constructors
static bool isLPC1769() { void SystemPostInit() {
#define IAP_LOCATION 0x1FFF1FF1 _millis = 0; // Initialise the millisecond counter value;
uint32_t command[1]; SysTick_Config(SystemCoreClock / 1000); // Start millisecond global counter
uint32_t result[5];
typedef void (*IAP)(uint32_t*, uint32_t*);
IAP iap = (IAP) IAP_LOCATION;
command[0] = 54; // Runs before setup() need to configure LED_PIN and use to indicate succsessful bootloader execution
iap(command, result); #if PIN_EXISTS(LED)
SET_DIR_OUTPUT(LED_PIN);
WRITE_PIN_CLR(LED_PIN);
return ((result[1] & 0x00100000) != 0); //MKS-SBASE has 3 other LEDS the bootloader uses during flashing, clear them
SET_DIR_OUTPUT(P1_19);
WRITE_PIN_CLR(P1_19);
SET_DIR_OUTPUT(P1_20);
WRITE_PIN_CLR(P1_20);
SET_DIR_OUTPUT(P1_21);
WRITE_PIN_CLR(P1_21);
for (int i = 0; i < 6; ++i) {
TOGGLE(LED_PIN);
delay(100);
}
#endif
}
} }
extern uint32_t MSC_SD_Init(uint8_t pdrv); extern uint32_t MSC_SD_Init(uint8_t pdrv);
@ -96,7 +95,6 @@ int main(void) {
const uint32_t usb_timeout = millis() + 2000; const uint32_t usb_timeout = millis() + 2000;
while (!USB_Configuration && PENDING(millis(), usb_timeout)) { while (!USB_Configuration && PENDING(millis(), usb_timeout)) {
delay(50); delay(50);
#if PIN_EXISTS(LED) #if PIN_EXISTS(LED)
TOGGLE(LED_PIN); // Flash fast while USB initialisation completes TOGGLE(LED_PIN); // Flash fast while USB initialisation completes
#endif #endif
@ -107,7 +105,7 @@ int main(void) {
#if NUM_SERIAL > 1 #if NUM_SERIAL > 1
MYSERIAL1.begin(BAUDRATE); MYSERIAL1.begin(BAUDRATE);
#endif #endif
SERIAL_PRINTF("\n\n%s (%dMhz) UART0 Initialised\n", isLPC1769() ? "LPC1769" : "LPC1768", SystemCoreClock / 1000000); SERIAL_PRINTF("\n\necho:%s (%dMhz) Initialised\n", isLPC1769() ? "LPC1769" : "LPC1768", SystemCoreClock / 1000000);
SERIAL_FLUSHTX(); SERIAL_FLUSHTX();
#endif #endif

View file

@ -40,6 +40,8 @@
#define PIN_P0_28 P0_28 #define PIN_P0_28 P0_28
*/ */
#define LED_PIN P1_18 // LED2 P1_19, LED3 P1_20, LED4 P1_21
// //
// Servo pin // Servo pin
// //

View file

@ -40,7 +40,8 @@ class Print {
void setWriteError(const int err = 1) { write_error = err; } void setWriteError(const int err = 1) { write_error = err; }
public: public:
Print() : write_error(0) {} Print() : write_error(0) {}
virtual ~Print() {}
int getWriteError() { return write_error; } int getWriteError() { return write_error; }
void clearWriteError() { setWriteError(0); } void clearWriteError() { setWriteError(0); }
@ -74,7 +75,7 @@ class Print {
size_t println(double, int = 2); size_t println(double, int = 2);
size_t println(const Printable&); size_t println(const Printable&);
size_t println(void); size_t println(void);
size_t printf(const char *argList, ...); virtual size_t printf(const char *argList, ...);
}; };
#endif // _CMSIS_PRINT_H_ #endif // _CMSIS_PRINT_H_

View file

@ -47,9 +47,9 @@ class Stream : public Print
int peekNextDigit(); // returns the next numeric digit in the stream or -1 if timeout int peekNextDigit(); // returns the next numeric digit in the stream or -1 if timeout
public: public:
virtual int available() = 0; virtual size_t available() = 0;
virtual int read() = 0; virtual int16_t read() = 0; // signed int required for error (empty buffer) value
virtual int peek() = 0; virtual int16_t peek() = 0;
virtual void flush() = 0; virtual void flush() = 0;
Stream() {_timeout=1000;} Stream() {_timeout=1000;}

View file

@ -211,7 +211,7 @@ void CDC_BulkIn(void) {
if (numBytesAvail > 0) { if (numBytesAvail > 0) {
numBytesAvail = numBytesAvail > (USB_CDC_BUFSIZE - 1) ? (USB_CDC_BUFSIZE - 1) : numBytesAvail; numBytesAvail = numBytesAvail > (USB_CDC_BUFSIZE - 1) ? (USB_CDC_BUFSIZE - 1) : numBytesAvail;
for(uint32_t i = 0; i < numBytesAvail; ++i) { for(uint32_t i = 0; i < numBytesAvail; ++i) {
BulkBufIn[i] = usb_serial.transmit_buffer.read(); //todo: optimise usb_serial.transmit_buffer.read(&BulkBufIn[i]);
} }
USB_WriteEP(CDC_DEP_IN, &BulkBufIn[0], numBytesAvail); USB_WriteEP(CDC_DEP_IN, &BulkBufIn[0], numBytesAvail);
} else { } else {

View file

@ -499,7 +499,7 @@ void SystemCoreClockUpdate (void) /* Get Core Clock Frequency */
} }
// detect 17x[4-8] (100MHz) or 17x9 (120MHz) // detect 17x[4-8] (100MHz) or 17x9 (120MHz)
static int can_120MHz() { int isLPC1769() {
#define IAP_LOCATION 0x1FFF1FF1 #define IAP_LOCATION 0x1FFF1FF1
uint32_t command[1]; uint32_t command[1];
uint32_t result[5]; uint32_t result[5];
@ -558,7 +558,7 @@ void SystemInit (void)
LPC_SC->CCLKCFG = 0x00000002; /* Setup CPU Clock Divider */ LPC_SC->CCLKCFG = 0x00000002; /* Setup CPU Clock Divider */
if(can_120MHz()) { if(isLPC1769()) {
LPC_SC->PLL0CFG = 0x0000000E; /* configure PLL0 */ LPC_SC->PLL0CFG = 0x0000000E; /* configure PLL0 */
LPC_SC->PLL0FEED = 0xAA; LPC_SC->PLL0FEED = 0xAA;
LPC_SC->PLL0FEED = 0x55; LPC_SC->PLL0FEED = 0x55;