diff --git a/GyverCore/boards.txt b/GyverCore/boards.txt index 3894e81..d3fec86 100644 --- a/GyverCore/boards.txt +++ b/GyverCore/boards.txt @@ -1,6 +1,7 @@ # See: http://code.google.com/p/arduino/wiki/Platforms -menu.cpu=Processor +menu.cpu=CPU & BOOT +menu.timers=Timers ###################### @@ -16,26 +17,37 @@ nano.bootloader.lock_bits=0x0F nano.build.f_cpu=16000000L nano.build.board=AVR_NANO nano.build.core=arduino -nano.build.variant=eightanaloginputs +## почему у оптибута неправильно стоят фьюзы? https://github.com/arduino/ArduinoCore-avr/issues/10 -## GyverCore w/ ATmega328P +## timer0 OVF ON/OFF ## -------------------------- -nano.menu.cpu.atmega328=ATmega328P +nano.menu.timers.yes_millis=yes millis +nano.menu.timers.yes_millis.build.variant=yesmillis +nano.menu.timers.no_millis=no millis +nano.menu.timers.no_millis.build.variant=nomillis + + +## ATmega328P - optiBoot +## -------------------------- +nano.menu.cpu.atmega328=ATmega328P - optiBoot + +##nano.menu.cpu.atmega328.upload.maximum_size=32256 nano.menu.cpu.atmega328.upload.maximum_size=30720 nano.menu.cpu.atmega328.upload.maximum_data_size=2048 nano.menu.cpu.atmega328.upload.speed=115200 nano.menu.cpu.atmega328.bootloader.low_fuses=0xFF nano.menu.cpu.atmega328.bootloader.high_fuses=0xDA +##nano.menu.cpu.atmega328.bootloader.high_fuses=0xDE nano.menu.cpu.atmega328.bootloader.extended_fuses=0xFD nano.menu.cpu.atmega328.bootloader.file=optiboot/optiboot_atmega328.hex nano.menu.cpu.atmega328.build.mcu=atmega328p -## GyverCore w/ ATmega328P (old bootloader) +## ATmega328P - old bootloader ## -------------------------- -nano.menu.cpu.atmega328old=ATmega328P (Old Bootloader) +nano.menu.cpu.atmega328old=ATmega328P - old bootloader nano.menu.cpu.atmega328old.upload.maximum_size=30720 nano.menu.cpu.atmega328old.upload.maximum_data_size=2048 @@ -48,18 +60,60 @@ nano.menu.cpu.atmega328old.bootloader.file=atmega/ATmegaBOOT_168_atmega328.hex nano.menu.cpu.atmega328old.build.mcu=atmega328p +## ATmega328P - NO bootloader +## -------------------------- +nano.menu.cpu.atmega328noBoot=ATmega328P - NO bootloader -## GyverCore w/ ATmega168 +nano.menu.cpu.atmega328noBoot.upload.maximum_size=32768 +nano.menu.cpu.atmega328noBoot.upload.maximum_data_size=2048 + +nano.menu.cpu.atmega328noBoot.bootloader.low_fuses=0xFF +nano.menu.cpu.atmega328noBoot.bootloader.high_fuses=0xDF +nano.menu.cpu.atmega328noBoot.bootloader.extended_fuses=0xFD + +nano.menu.cpu.atmega328noBoot.build.mcu=atmega328p + +## ATmega168 - optiBoot ## ------------------------- -nano.menu.cpu.atmega168=ATmega168 +nano.menu.cpu.atmega168=ATmega168 - optiBoot nano.menu.cpu.atmega168.upload.maximum_size=14336 +##nano.menu.cpu.atmega168.upload.maximum_size=15360 nano.menu.cpu.atmega168.upload.maximum_data_size=1024 -nano.menu.cpu.atmega168.upload.speed=19200 +nano.menu.cpu.atmega168.upload.speed=115200 nano.menu.cpu.atmega168.bootloader.low_fuses=0xff nano.menu.cpu.atmega168.bootloader.high_fuses=0xdd nano.menu.cpu.atmega168.bootloader.extended_fuses=0xF8 -nano.menu.cpu.atmega168.bootloader.file=atmega/ATmegaBOOT_168_diecimila.hex +##nano.menu.cpu.atmega168.bootloader.extended_fuses=0xFE +nano.menu.cpu.atmega168.bootloader.file=optiboot/optiboot_atmega168.hex -nano.menu.cpu.atmega168.build.mcu=atmega168 \ No newline at end of file +nano.menu.cpu.atmega168.build.mcu=atmega168 + +## ATmega168 - old bootloader +## ------------------------- +nano.menu.cpu.atmega168old=ATmega168 - old bootloader + +nano.menu.cpu.atmega168old.upload.maximum_size=14336 +nano.menu.cpu.atmega168old.upload.maximum_data_size=1024 +nano.menu.cpu.atmega168old.upload.speed=19200 + +nano.menu.cpu.atmega168old.bootloader.low_fuses=0xff +nano.menu.cpu.atmega168old.bootloader.high_fuses=0xdd +nano.menu.cpu.atmega168old.bootloader.extended_fuses=0xF8 +nano.menu.cpu.atmega168old.bootloader.file=atmega/ATmegaBOOT_168_diecimila.hex + +nano.menu.cpu.atmega168old.build.mcu=atmega168 + +## ATmega168 - NO bootloader +## ------------------------- +nano.menu.cpu.atmega168noBoot=ATmega168 - NO bootloader + +nano.menu.cpu.atmega168noBoot.upload.maximum_size=16144 +nano.menu.cpu.atmega168noBoot.upload.maximum_data_size=1024 + +nano.menu.cpu.atmega168noBoot.bootloader.low_fuses=0xff +nano.menu.cpu.atmega168noBoot.bootloader.high_fuses=0xdd +nano.menu.cpu.atmega168noBoot.bootloader.extended_fuses=0xff + +nano.menu.cpu.atmega168noBoot.build.mcu=atmega168 \ No newline at end of file diff --git a/GyverCore/cores/arduino/Arduino.h b/GyverCore/cores/arduino/Arduino.h index 09c1448..0abd64e 100644 --- a/GyverCore/cores/arduino/Arduino.h +++ b/GyverCore/cores/arduino/Arduino.h @@ -1,42 +1,47 @@ -/* - Arduino.h - Main include file for the Arduino SDK - Copyright (c) 2005-2013 Arduino Team. All right reserved. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library 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 - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA -*/ - + #ifndef Arduino_h #define Arduino_h +// ===== DEF LIBS ===== #include #include #include #include - #include #include #include -#include "binary.h" - #ifdef __cplusplus extern "C"{ #endif -void yield(void); +// ===== PINS ===== +#define digitalPinToPCICR(p) (((p) >= 0 && (p) <= 21) ? (&PCICR) : ((uint8_t *)0)) +#define digitalPinToPCICRbit(p) (((p) <= 7) ? 2 : (((p) <= 13) ? 0 : 1)) +#define digitalPinToPCMSK(p) (((p) <= 7) ? (&PCMSK2) : (((p) <= 13) ? (&PCMSK0) : (((p) <= 21) ? (&PCMSK1) : ((uint8_t *)0)))) +#define digitalPinToPCMSKbit(p) (((p) <= 7) ? (p) : (((p) <= 13) ? ((p) - 8) : ((p) - 14))) +#define digitalPinToInterrupt(p) ((p) == 2 ? 0 : ((p) == 3 ? 1 : NOT_AN_INTERRUPT)) +#define PIN_SPI_SS (10) +#define PIN_SPI_MOSI (11) +#define PIN_SPI_MISO (12) +#define PIN_SPI_SCK (13) +#define PIN_WIRE_SDA (18) +#define PIN_WIRE_SCL (19) +#define LED_BUILTIN 13 +#define A0 (14) +#define A1 (15) +#define A2 (16) +#define A3 (17) +#define A4 (18) +#define A5 (19) +#define A6 (20) +#define A7 (21) +#define EXTERNAL_INT_0 (0) +#define EXTERNAL_INT_1 (1) +#define EXTERNAL_NUM_INTERRUPTS 2 + +// ===== CONSTANTS ===== #define HIGH 0x1 #define LOW 0x0 @@ -61,30 +66,11 @@ void yield(void); #define FALLING 2 #define RISING 3 -#if defined(__AVR_ATtiny24__) || defined(__AVR_ATtiny44__) || defined(__AVR_ATtiny84__) - #define DEFAULT 0 - #define EXTERNAL 1 - #define INTERNAL1V1 2 - #define INTERNAL INTERNAL1V1 -#elif defined(__AVR_ATtiny25__) || defined(__AVR_ATtiny45__) || defined(__AVR_ATtiny85__) - #define DEFAULT 0 - #define EXTERNAL 4 - #define INTERNAL1V1 8 - #define INTERNAL INTERNAL1V1 - #define INTERNAL2V56 9 - #define INTERNAL2V56_EXTCAP 13 -#else -#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) || defined(__AVR_ATmega1284__) || defined(__AVR_ATmega1284P__) || defined(__AVR_ATmega644__) || defined(__AVR_ATmega644A__) || defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644PA__) -#define INTERNAL1V1 2 -#define INTERNAL2V56 3 -#else -#define INTERNAL 3 -#endif +#define INTERNAL 28 #define DEFAULT 1 #define EXTERNAL 0 -#endif - -// undefine stdlib's abs if encountered +#define THERMOMETR 22 +// ===== MATH MACRO ===== #ifdef abs #undef abs #endif @@ -112,30 +98,52 @@ void yield(void); #define bitSet(value, bit) ((value) |= (1UL << (bit))) #define bitClear(value, bit) ((value) &= ~(1UL << (bit))) #define bitWrite(value, bit, bitvalue) (bitvalue ? bitSet(value, bit) : bitClear(value, bit)) +#define bitToggle(value, bit) ((value) ^= (1 << bit)) + +#define cbi(sfr, bit) (_SFR_BYTE(sfr) &= ~_BV(bit)) +#define sbi(sfr, bit) (_SFR_BYTE(sfr) |= _BV(bit)) + +#define bit(b) (1UL << (b)) -// avr-libc defines _NOP() since 1.6.2 #ifndef _NOP #define _NOP() do { __asm__ volatile ("nop"); } while (0) #endif + +// ===== FUNCTIONS & TYPES ===== +static void __empty() { + // Empty +} +void yield(void) __attribute__ ((weak, alias("__empty"))); + +typedef void (*voidFuncPtr)(void); typedef unsigned int word; - -#define bit(b) (1UL << (b)) - typedef bool boolean; typedef uint8_t byte; void init(void); -void initVariant(void); -int atexit(void (*func)()) __attribute__((weak)); -void pinMode(uint8_t, uint8_t); -void digitalWrite(uint8_t, uint8_t); -int digitalRead(uint8_t); -int analogRead(uint8_t); +/* light uart*/ + + +// ===== PIN OPERATION ====== +// new +void setPWM_20kHz(byte pin); +void setPWM_9_10_resolution(boolean resolution); // 0 - 8 бит, 1 - 10 бит +void setPwmFreqnuency(byte pin, byte freq); //default, 8KHZ, 31KHZ +void setPWM_default(byte pin); +void analogStartConvert(byte pin); +void analogPrescaler(uint8_t prescl); +int analogGet(); +void digitalToggle(uint8_t pin); +// old +void pinMode(uint8_t pin, uint8_t mode); +void digitalWrite(uint8_t pin, uint8_t x); +int digitalRead (uint8_t pin); +int analogRead(uint8_t pin); void analogReference(uint8_t mode); -void analogWrite(uint8_t, int); +void analogWrite(uint8_t pin, int val); unsigned long millis(void); unsigned long micros(void); @@ -147,19 +155,14 @@ unsigned long pulseInLong(uint8_t pin, uint8_t state, unsigned long timeout); void shiftOut(uint8_t dataPin, uint8_t clockPin, uint8_t bitOrder, uint8_t val); uint8_t shiftIn(uint8_t dataPin, uint8_t clockPin, uint8_t bitOrder); -void attachInterrupt(uint8_t, void (*)(void), int mode); +void attachInterrupt(uint8_t num,void (*isr)(), uint8_t type); void detachInterrupt(uint8_t); void setup(void); void loop(void); -// Get the bit location within the hardware port of the given virtual pin. -// This comes from the pins_*.c file for the active board configuration. - #define analogInPinToBit(P) (P) -// On the ATmega1280, the addresses of some of the port registers are -// greater than 255, so we can't store them in uint8_t's. extern const uint16_t PROGMEM port_to_mode_PGM[]; extern const uint16_t PROGMEM port_to_input_PGM[]; extern const uint16_t PROGMEM port_to_output_PGM[]; @@ -169,11 +172,6 @@ extern const uint8_t PROGMEM digital_pin_to_port_PGM[]; extern const uint8_t PROGMEM digital_pin_to_bit_mask_PGM[]; extern const uint8_t PROGMEM digital_pin_to_timer_PGM[]; -// Get the bit location within the hardware port of the given virtual pin. -// This comes from the pins_*.c file for the active board configuration. -// -// These perform slightly better as macros compared to inline functions -// #define digitalPinToPort(P) ( pgm_read_byte( digital_pin_to_port_PGM + (P) ) ) #define digitalPinToBitMask(P) ( pgm_read_byte( digital_pin_to_bit_mask_PGM + (P) ) ) #define digitalPinToTimer(P) ( pgm_read_byte( digital_pin_to_timer_PGM + (P) ) ) @@ -187,7 +185,6 @@ extern const uint8_t PROGMEM digital_pin_to_timer_PGM[]; #define NOT_AN_INTERRUPT -1 -#ifdef ARDUINO_MAIN #define PA 1 #define PB 2 #define PC 3 @@ -199,7 +196,6 @@ extern const uint8_t PROGMEM digital_pin_to_timer_PGM[]; #define PJ 10 #define PK 11 #define PL 12 -#endif #define NOT_ON_TIMER 0 #define TIMER0A 1 @@ -227,13 +223,13 @@ extern const uint8_t PROGMEM digital_pin_to_timer_PGM[]; #endif #ifdef __cplusplus +// === FILES === +#include "binary.h" #include "WCharacter.h" #include "WString.h" #include "HardwareSerial.h" -#include "USBAPI.h" -#if defined(HAVE_HWSERIAL0) && defined(HAVE_CDCSERIAL) -#error "Targets with both UART0 and CDC serial not supported" -#endif +#include "uart.h" +//#include "USBAPI.h" uint16_t makeWord(uint16_t w); uint16_t makeWord(byte h, byte l); @@ -254,6 +250,4 @@ long map(long, long, long, long, long); #endif -#include "pins_arduino.h" - #endif diff --git a/GyverCore/cores/arduino/CDC.cpp b/GyverCore/cores/arduino/CDC.cpp deleted file mode 100644 index 142f8f6..0000000 --- a/GyverCore/cores/arduino/CDC.cpp +++ /dev/null @@ -1,302 +0,0 @@ - - -/* Copyright (c) 2011, Peter Barrett -** -** Permission to use, copy, modify, and/or distribute this software for -** any purpose with or without fee is hereby granted, provided that the -** above copyright notice and this permission notice appear in all copies. -** -** THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL -** WARRANTIES WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED -** WARRANTIES OF MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR -** BE LIABLE FOR ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES -** OR ANY DAMAGES WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, -** WHETHER IN AN ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, -** ARISING OUT OF OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS -** SOFTWARE. -*/ - -#include "USBAPI.h" -#include -#include - -#if defined(USBCON) - -typedef struct -{ - u32 dwDTERate; - u8 bCharFormat; - u8 bParityType; - u8 bDataBits; - u8 lineState; -} LineInfo; - -static volatile LineInfo _usbLineInfo = { 57600, 0x00, 0x00, 0x00, 0x00 }; -static volatile int32_t breakValue = -1; - -static u8 wdtcsr_save; - -#define WEAK __attribute__ ((weak)) - -extern const CDCDescriptor _cdcInterface PROGMEM; -const CDCDescriptor _cdcInterface = -{ - D_IAD(0,2,CDC_COMMUNICATION_INTERFACE_CLASS,CDC_ABSTRACT_CONTROL_MODEL,1), - - // CDC communication interface - D_INTERFACE(CDC_ACM_INTERFACE,1,CDC_COMMUNICATION_INTERFACE_CLASS,CDC_ABSTRACT_CONTROL_MODEL,0), - D_CDCCS(CDC_HEADER,0x10,0x01), // Header (1.10 bcd) - D_CDCCS(CDC_CALL_MANAGEMENT,1,1), // Device handles call management (not) - D_CDCCS4(CDC_ABSTRACT_CONTROL_MANAGEMENT,6), // SET_LINE_CODING, GET_LINE_CODING, SET_CONTROL_LINE_STATE supported - D_CDCCS(CDC_UNION,CDC_ACM_INTERFACE,CDC_DATA_INTERFACE), // Communication interface is master, data interface is slave 0 - D_ENDPOINT(USB_ENDPOINT_IN (CDC_ENDPOINT_ACM),USB_ENDPOINT_TYPE_INTERRUPT,0x10,0x40), - - // CDC data interface - D_INTERFACE(CDC_DATA_INTERFACE,2,CDC_DATA_INTERFACE_CLASS,0,0), - D_ENDPOINT(USB_ENDPOINT_OUT(CDC_ENDPOINT_OUT),USB_ENDPOINT_TYPE_BULK,USB_EP_SIZE,0), - D_ENDPOINT(USB_ENDPOINT_IN (CDC_ENDPOINT_IN ),USB_ENDPOINT_TYPE_BULK,USB_EP_SIZE,0) -}; - -bool isLUFAbootloader() -{ - return pgm_read_word(FLASHEND - 1) == NEW_LUFA_SIGNATURE; -} - -int CDC_GetInterface(u8* interfaceNum) -{ - interfaceNum[0] += 2; // uses 2 - return USB_SendControl(TRANSFER_PGM,&_cdcInterface,sizeof(_cdcInterface)); -} - -bool CDC_Setup(USBSetup& setup) -{ - u8 r = setup.bRequest; - u8 requestType = setup.bmRequestType; - - if (REQUEST_DEVICETOHOST_CLASS_INTERFACE == requestType) - { - if (CDC_GET_LINE_CODING == r) - { - USB_SendControl(0,(void*)&_usbLineInfo,7); - return true; - } - } - - if (REQUEST_HOSTTODEVICE_CLASS_INTERFACE == requestType) - { - if (CDC_SEND_BREAK == r) - { - breakValue = ((uint16_t)setup.wValueH << 8) | setup.wValueL; - } - - if (CDC_SET_LINE_CODING == r) - { - USB_RecvControl((void*)&_usbLineInfo,7); - } - - if (CDC_SET_CONTROL_LINE_STATE == r) - { - _usbLineInfo.lineState = setup.wValueL; - - // auto-reset into the bootloader is triggered when the port, already - // open at 1200 bps, is closed. this is the signal to start the watchdog - // with a relatively long period so it can finish housekeeping tasks - // like servicing endpoints before the sketch ends - - uint16_t magic_key_pos = MAGIC_KEY_POS; - -// If we don't use the new RAMEND directly, check manually if we have a newer bootloader. -// This is used to keep compatible with the old leonardo bootloaders. -// You are still able to set the magic key position manually to RAMEND-1 to save a few bytes for this check. -#if MAGIC_KEY_POS != (RAMEND-1) - // For future boards save the key in the inproblematic RAMEND - // Which is reserved for the main() return value (which will never return) - if (isLUFAbootloader()) { - // horray, we got a new bootloader! - magic_key_pos = (RAMEND-1); - } -#endif - - // We check DTR state to determine if host port is open (bit 0 of lineState). - if (1200 == _usbLineInfo.dwDTERate && (_usbLineInfo.lineState & 0x01) == 0) - { -#if MAGIC_KEY_POS != (RAMEND-1) - // Backup ram value if its not a newer bootloader and it hasn't already been saved. - // This should avoid memory corruption at least a bit, not fully - if (magic_key_pos != (RAMEND-1) && *(uint16_t *)magic_key_pos != MAGIC_KEY) { - *(uint16_t *)(RAMEND-1) = *(uint16_t *)magic_key_pos; - } -#endif - // Store boot key - *(uint16_t *)magic_key_pos = MAGIC_KEY; - // Save the watchdog state in case the reset is aborted. - wdtcsr_save = WDTCSR; - wdt_enable(WDTO_120MS); - } - else if (*(uint16_t *)magic_key_pos == MAGIC_KEY) - { - // Most OSs do some intermediate steps when configuring ports and DTR can - // twiggle more than once before stabilizing. - // To avoid spurious resets we set the watchdog to 120ms and eventually - // cancel if DTR goes back high. - // Cancellation is only done if an auto-reset was started, which is - // indicated by the magic key having been set. - - wdt_reset(); - // Restore the watchdog state in case the sketch was using it. - WDTCSR |= (1<= 0) { - return 1 + USB_Available(CDC_RX); - } - return USB_Available(CDC_RX); -} - -int Serial_::peek(void) -{ - if (peek_buffer < 0) - peek_buffer = USB_Recv(CDC_RX); - return peek_buffer; -} - -int Serial_::read(void) -{ - if (peek_buffer >= 0) { - int c = peek_buffer; - peek_buffer = -1; - return c; - } - return USB_Recv(CDC_RX); -} - -int Serial_::availableForWrite(void) -{ - return USB_SendSpace(CDC_TX); -} - -void Serial_::flush(void) -{ - USB_Flush(CDC_TX); -} - -size_t Serial_::write(uint8_t c) -{ - return write(&c, 1); -} - -size_t Serial_::write(const uint8_t *buffer, size_t size) -{ - /* only try to send bytes if the high-level CDC connection itself - is open (not just the pipe) - the OS should set lineState when the port - is opened and clear lineState when the port is closed. - bytes sent before the user opens the connection or after - the connection is closed are lost - just like with a UART. */ - - // TODO - ZE - check behavior on different OSes and test what happens if an - // open connection isn't broken cleanly (cable is yanked out, host dies - // or locks up, or host virtual serial port hangs) - if (_usbLineInfo.lineState > 0) { - int r = USB_Send(CDC_TX,buffer,size); - if (r > 0) { - return r; - } else { - setWriteError(); - return 0; - } - } - setWriteError(); - return 0; -} - -// This operator is a convenient way for a sketch to check whether the -// port has actually been configured and opened by the host (as opposed -// to just being connected to the host). It can be used, for example, in -// setup() before printing to ensure that an application on the host is -// actually ready to receive and display the data. -// We add a short delay before returning to fix a bug observed by Federico -// where the port is configured (lineState != 0) but not quite opened. -Serial_::operator bool() { - bool result = false; - if (_usbLineInfo.lineState > 0) - result = true; - delay(10); - return result; -} - -unsigned long Serial_::baud() { - // Disable interrupts while reading a multi-byte value - uint32_t baudrate; - ATOMIC_BLOCK(ATOMIC_RESTORESTATE) { - baudrate = _usbLineInfo.dwDTERate; - } - return baudrate; -} - -uint8_t Serial_::stopbits() { - return _usbLineInfo.bCharFormat; -} - -uint8_t Serial_::paritytype() { - return _usbLineInfo.bParityType; -} - -uint8_t Serial_::numbits() { - return _usbLineInfo.bDataBits; -} - -bool Serial_::dtr() { - return _usbLineInfo.lineState & 0x1; -} - -bool Serial_::rts() { - return _usbLineInfo.lineState & 0x2; -} - -int32_t Serial_::readBreak() { - int32_t ret; - // Disable IRQs while reading and clearing breakValue to make - // sure we don't overwrite a value just set by the ISR. - ATOMIC_BLOCK(ATOMIC_RESTORESTATE) { - ret = breakValue; - breakValue = -1; - } - return ret; -} - -Serial_ Serial; - -#endif /* if defined(USBCON) */ diff --git a/GyverCore/cores/arduino/Client.h b/GyverCore/cores/arduino/Client.h deleted file mode 100644 index b8e5d93..0000000 --- a/GyverCore/cores/arduino/Client.h +++ /dev/null @@ -1,45 +0,0 @@ -/* - Client.h - Base class that provides Client - Copyright (c) 2011 Adrian McEwen. All right reserved. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library 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 - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef client_h -#define client_h -#include "Print.h" -#include "Stream.h" -#include "IPAddress.h" - -class Client : public Stream { - -public: - virtual int connect(IPAddress ip, uint16_t port) =0; - virtual int connect(const char *host, uint16_t port) =0; - virtual size_t write(uint8_t) =0; - virtual size_t write(const uint8_t *buf, size_t size) =0; - virtual int available() = 0; - virtual int read() = 0; - virtual int read(uint8_t *buf, size_t size) = 0; - virtual int peek() = 0; - virtual void flush() = 0; - virtual void stop() = 0; - virtual uint8_t connected() = 0; - virtual operator bool() = 0; -protected: - uint8_t* rawIPAddress(IPAddress& addr) { return addr.raw_address(); }; -}; - -#endif diff --git a/GyverCore/cores/arduino/HardwareSerial.cpp b/GyverCore/cores/arduino/HardwareSerial.cpp index e99d503..053cfd4 100644 --- a/GyverCore/cores/arduino/HardwareSerial.cpp +++ b/GyverCore/cores/arduino/HardwareSerial.cpp @@ -21,13 +21,13 @@ Modified 14 August 2012 by Alarus Modified 3 December 2013 by Matthijs Kooijman */ - +#include "Arduino.h" #include #include #include #include #include -#include "Arduino.h" + #include "HardwareSerial.h" #include "HardwareSerial_private.h" @@ -75,6 +75,7 @@ void serialEventRun(void) #if defined(HAVE_HWSERIAL3) if (Serial3_available && serialEvent3 && Serial3_available()) serialEvent3(); #endif + } // macro to guard critical sections when needed for large TX buffer sizes diff --git a/GyverCore/cores/arduino/HardwareSerial0.cpp b/GyverCore/cores/arduino/HardwareSerial0.cpp index 1146eeb..0d2882f 100644 --- a/GyverCore/cores/arduino/HardwareSerial0.cpp +++ b/GyverCore/cores/arduino/HardwareSerial0.cpp @@ -62,6 +62,7 @@ ISR(USART_UDRE_vect) #endif { Serial._tx_udr_empty_irq(); + } #if defined(UBRRH) && defined(UBRRL) diff --git a/GyverCore/cores/arduino/HardwareSerial1.cpp b/GyverCore/cores/arduino/HardwareSerial1.cpp deleted file mode 100644 index 19625e2..0000000 --- a/GyverCore/cores/arduino/HardwareSerial1.cpp +++ /dev/null @@ -1,69 +0,0 @@ -/* - HardwareSerial1.cpp - Hardware serial library for Wiring - Copyright (c) 2006 Nicholas Zambetti. All right reserved. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library 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 - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA - - Modified 23 November 2006 by David A. Mellis - Modified 28 September 2010 by Mark Sproul - Modified 14 August 2012 by Alarus - Modified 3 December 2013 by Matthijs Kooijman -*/ - -#include "Arduino.h" -#include "HardwareSerial.h" -#include "HardwareSerial_private.h" - -// Each HardwareSerial is defined in its own file, sine the linker pulls -// in the entire file when any element inside is used. --gc-sections can -// additionally cause unused symbols to be dropped, but ISRs have the -// "used" attribute so are never dropped and they keep the -// HardwareSerial instance in as well. Putting each instance in its own -// file prevents the linker from pulling in any unused instances in the -// first place. - -#if defined(HAVE_HWSERIAL1) - -#if defined(UART1_RX_vect) -ISR(UART1_RX_vect) -#elif defined(USART1_RX_vect) -ISR(USART1_RX_vect) -#else -#error "Don't know what the Data Register Empty vector is called for Serial1" -#endif -{ - Serial1._rx_complete_irq(); -} - -#if defined(UART1_UDRE_vect) -ISR(UART1_UDRE_vect) -#elif defined(USART1_UDRE_vect) -ISR(USART1_UDRE_vect) -#else -#error "Don't know what the Data Register Empty vector is called for Serial1" -#endif -{ - Serial1._tx_udr_empty_irq(); -} - -HardwareSerial Serial1(&UBRR1H, &UBRR1L, &UCSR1A, &UCSR1B, &UCSR1C, &UDR1); - -// Function that can be weakly referenced by serialEventRun to prevent -// pulling in this file if it's not otherwise used. -bool Serial1_available() { - return Serial1.available(); -} - -#endif // HAVE_HWSERIAL1 diff --git a/GyverCore/cores/arduino/HardwareSerial2.cpp b/GyverCore/cores/arduino/HardwareSerial2.cpp deleted file mode 100644 index fd334ae..0000000 --- a/GyverCore/cores/arduino/HardwareSerial2.cpp +++ /dev/null @@ -1,57 +0,0 @@ -/* - HardwareSerial2.cpp - Hardware serial library for Wiring - Copyright (c) 2006 Nicholas Zambetti. All right reserved. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library 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 - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA - - Modified 23 November 2006 by David A. Mellis - Modified 28 September 2010 by Mark Sproul - Modified 14 August 2012 by Alarus - Modified 3 December 2013 by Matthijs Kooijman -*/ - -#include "Arduino.h" -#include "HardwareSerial.h" -#include "HardwareSerial_private.h" - -// Each HardwareSerial is defined in its own file, sine the linker pulls -// in the entire file when any element inside is used. --gc-sections can -// additionally cause unused symbols to be dropped, but ISRs have the -// "used" attribute so are never dropped and they keep the -// HardwareSerial instance in as well. Putting each instance in its own -// file prevents the linker from pulling in any unused instances in the -// first place. - -#if defined(HAVE_HWSERIAL2) - -ISR(USART2_RX_vect) -{ - Serial2._rx_complete_irq(); -} - -ISR(USART2_UDRE_vect) -{ - Serial2._tx_udr_empty_irq(); -} - -HardwareSerial Serial2(&UBRR2H, &UBRR2L, &UCSR2A, &UCSR2B, &UCSR2C, &UDR2); - -// Function that can be weakly referenced by serialEventRun to prevent -// pulling in this file if it's not otherwise used. -bool Serial2_available() { - return Serial2.available(); -} - -#endif // HAVE_HWSERIAL2 diff --git a/GyverCore/cores/arduino/HardwareSerial3.cpp b/GyverCore/cores/arduino/HardwareSerial3.cpp deleted file mode 100644 index a68095b..0000000 --- a/GyverCore/cores/arduino/HardwareSerial3.cpp +++ /dev/null @@ -1,57 +0,0 @@ -/* - HardwareSerial3.cpp - Hardware serial library for Wiring - Copyright (c) 2006 Nicholas Zambetti. All right reserved. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library 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 - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA - - Modified 23 November 2006 by David A. Mellis - Modified 28 September 2010 by Mark Sproul - Modified 14 August 2012 by Alarus - Modified 3 December 2013 by Matthijs Kooijman -*/ - -#include "Arduino.h" -#include "HardwareSerial.h" -#include "HardwareSerial_private.h" - -// Each HardwareSerial is defined in its own file, sine the linker pulls -// in the entire file when any element inside is used. --gc-sections can -// additionally cause unused symbols to be dropped, but ISRs have the -// "used" attribute so are never dropped and they keep the -// HardwareSerial instance in as well. Putting each instance in its own -// file prevents the linker from pulling in any unused instances in the -// first place. - -#if defined(HAVE_HWSERIAL3) - -ISR(USART3_RX_vect) -{ - Serial3._rx_complete_irq(); -} - -ISR(USART3_UDRE_vect) -{ - Serial3._tx_udr_empty_irq(); -} - -HardwareSerial Serial3(&UBRR3H, &UBRR3L, &UCSR3A, &UCSR3B, &UCSR3C, &UDR3); - -// Function that can be weakly referenced by serialEventRun to prevent -// pulling in this file if it's not otherwise used. -bool Serial3_available() { - return Serial3.available(); -} - -#endif // HAVE_HWSERIAL3 diff --git a/GyverCore/cores/arduino/HardwareSerial_private.h b/GyverCore/cores/arduino/HardwareSerial_private.h index 761a5e5..b8cf7e8 100644 --- a/GyverCore/cores/arduino/HardwareSerial_private.h +++ b/GyverCore/cores/arduino/HardwareSerial_private.h @@ -1,27 +1,6 @@ -/* - HardwareSerial_private.h - Hardware serial library for Wiring - Copyright (c) 2006 Nicholas Zambetti. All right reserved. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library 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 - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA - - Modified 23 November 2006 by David A. Mellis - Modified 28 September 2010 by Mark Sproul - Modified 14 August 2012 by Alarus -*/ - -#include "wiring_private.h" +#include +#include +#include "Arduino.h" // this next line disables the entire HardwareSerial.cpp, // this is so I can support Attiny series and any other chip without a uart diff --git a/GyverCore/cores/arduino/IPAddress.cpp b/GyverCore/cores/arduino/IPAddress.cpp deleted file mode 100644 index d9fe5be..0000000 --- a/GyverCore/cores/arduino/IPAddress.cpp +++ /dev/null @@ -1,114 +0,0 @@ -/* - IPAddress.cpp - Base class that provides IPAddress - Copyright (c) 2011 Adrian McEwen. All right reserved. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library 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 - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include - -IPAddress::IPAddress() -{ - _address.dword = 0; -} - -IPAddress::IPAddress(uint8_t first_octet, uint8_t second_octet, uint8_t third_octet, uint8_t fourth_octet) -{ - _address.bytes[0] = first_octet; - _address.bytes[1] = second_octet; - _address.bytes[2] = third_octet; - _address.bytes[3] = fourth_octet; -} - -IPAddress::IPAddress(uint32_t address) -{ - _address.dword = address; -} - -IPAddress::IPAddress(const uint8_t *address) -{ - memcpy(_address.bytes, address, sizeof(_address.bytes)); -} - -bool IPAddress::fromString(const char *address) -{ - uint16_t acc = 0; // Accumulator - uint8_t dots = 0; - - while (*address) - { - char c = *address++; - if (c >= '0' && c <= '9') - { - acc = acc * 10 + (c - '0'); - if (acc > 255) { - // Value out of [0..255] range - return false; - } - } - else if (c == '.') - { - if (dots == 3) { - // Too much dots (there must be 3 dots) - return false; - } - _address.bytes[dots++] = acc; - acc = 0; - } - else - { - // Invalid char - return false; - } - } - - if (dots != 3) { - // Too few dots (there must be 3 dots) - return false; - } - _address.bytes[3] = acc; - return true; -} - -IPAddress& IPAddress::operator=(const uint8_t *address) -{ - memcpy(_address.bytes, address, sizeof(_address.bytes)); - return *this; -} - -IPAddress& IPAddress::operator=(uint32_t address) -{ - _address.dword = address; - return *this; -} - -bool IPAddress::operator==(const uint8_t* addr) const -{ - return memcmp(addr, _address.bytes, sizeof(_address.bytes)) == 0; -} - -size_t IPAddress::printTo(Print& p) const -{ - size_t n = 0; - for (int i =0; i < 3; i++) - { - n += p.print(_address.bytes[i], DEC); - n += p.print('.'); - } - n += p.print(_address.bytes[3], DEC); - return n; -} - diff --git a/GyverCore/cores/arduino/IPAddress.h b/GyverCore/cores/arduino/IPAddress.h deleted file mode 100644 index d762f2c..0000000 --- a/GyverCore/cores/arduino/IPAddress.h +++ /dev/null @@ -1,78 +0,0 @@ -/* - IPAddress.h - Base class that provides IPAddress - Copyright (c) 2011 Adrian McEwen. All right reserved. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library 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 - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef IPAddress_h -#define IPAddress_h - -#include -#include "Printable.h" -#include "WString.h" - -// A class to make it easier to handle and pass around IP addresses - -class IPAddress : public Printable { -private: - union { - uint8_t bytes[4]; // IPv4 address - uint32_t dword; - } _address; - - // Access the raw byte array containing the address. Because this returns a pointer - // to the internal structure rather than a copy of the address this function should only - // be used when you know that the usage of the returned uint8_t* will be transient and not - // stored. - uint8_t* raw_address() { return _address.bytes; }; - -public: - // Constructors - IPAddress(); - IPAddress(uint8_t first_octet, uint8_t second_octet, uint8_t third_octet, uint8_t fourth_octet); - IPAddress(uint32_t address); - IPAddress(const uint8_t *address); - - bool fromString(const char *address); - bool fromString(const String &address) { return fromString(address.c_str()); } - - // Overloaded cast operator to allow IPAddress objects to be used where a pointer - // to a four-byte uint8_t array is expected - operator uint32_t() const { return _address.dword; }; - bool operator==(const IPAddress& addr) const { return _address.dword == addr._address.dword; }; - bool operator==(const uint8_t* addr) const; - - // Overloaded index operator to allow getting and setting individual octets of the address - uint8_t operator[](int index) const { return _address.bytes[index]; }; - uint8_t& operator[](int index) { return _address.bytes[index]; }; - - // Overloaded copy operators to allow initialisation of IPAddress objects from other types - IPAddress& operator=(const uint8_t *address); - IPAddress& operator=(uint32_t address); - - virtual size_t printTo(Print& p) const; - - friend class EthernetClass; - friend class UDP; - friend class Client; - friend class Server; - friend class DhcpClass; - friend class DNSClient; -}; - -const IPAddress INADDR_NONE(0,0,0,0); - -#endif diff --git a/GyverCore/cores/arduino/PluggableUSB.cpp b/GyverCore/cores/arduino/PluggableUSB.cpp deleted file mode 100644 index c489d9f..0000000 --- a/GyverCore/cores/arduino/PluggableUSB.cpp +++ /dev/null @@ -1,115 +0,0 @@ -/* - PluggableUSB.cpp - Copyright (c) 2015 Arduino LLC - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library 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 - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include "USBAPI.h" -#include "PluggableUSB.h" - -#if defined(USBCON) -#ifdef PLUGGABLE_USB_ENABLED - -extern uint8_t _initEndpoints[]; - -int PluggableUSB_::getInterface(uint8_t* interfaceCount) -{ - int sent = 0; - PluggableUSBModule* node; - for (node = rootNode; node; node = node->next) { - int res = node->getInterface(interfaceCount); - if (res < 0) - return -1; - sent += res; - } - return sent; -} - -int PluggableUSB_::getDescriptor(USBSetup& setup) -{ - PluggableUSBModule* node; - for (node = rootNode; node; node = node->next) { - int ret = node->getDescriptor(setup); - // ret!=0 -> request has been processed - if (ret) - return ret; - } - return 0; -} - -void PluggableUSB_::getShortName(char *iSerialNum) -{ - PluggableUSBModule* node; - for (node = rootNode; node; node = node->next) { - iSerialNum += node->getShortName(iSerialNum); - } - *iSerialNum = 0; -} - -bool PluggableUSB_::setup(USBSetup& setup) -{ - PluggableUSBModule* node; - for (node = rootNode; node; node = node->next) { - if (node->setup(setup)) { - return true; - } - } - return false; -} - -bool PluggableUSB_::plug(PluggableUSBModule *node) -{ - if ((lastEp + node->numEndpoints) > USB_ENDPOINTS) { - return false; - } - - if (!rootNode) { - rootNode = node; - } else { - PluggableUSBModule *current = rootNode; - while (current->next) { - current = current->next; - } - current->next = node; - } - - node->pluggedInterface = lastIf; - node->pluggedEndpoint = lastEp; - lastIf += node->numInterfaces; - for (uint8_t i = 0; i < node->numEndpoints; i++) { - _initEndpoints[lastEp] = node->endpointType[i]; - lastEp++; - } - return true; - // restart USB layer??? -} - -PluggableUSB_& PluggableUSB() -{ - static PluggableUSB_ obj; - return obj; -} - -PluggableUSB_::PluggableUSB_() : lastIf(CDC_ACM_INTERFACE + CDC_INTERFACE_COUNT), - lastEp(CDC_FIRST_ENDPOINT + CDC_ENPOINT_COUNT), - rootNode(NULL) -{ - // Empty -} - -#endif - -#endif /* if defined(USBCON) */ diff --git a/GyverCore/cores/arduino/PluggableUSB.h b/GyverCore/cores/arduino/PluggableUSB.h deleted file mode 100644 index 507f0df..0000000 --- a/GyverCore/cores/arduino/PluggableUSB.h +++ /dev/null @@ -1,74 +0,0 @@ -/* - PluggableUSB.h - Copyright (c) 2015 Arduino LLC - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library 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 - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef PUSB_h -#define PUSB_h - -#include "USBAPI.h" -#include - -#if defined(USBCON) - -class PluggableUSBModule { -public: - PluggableUSBModule(uint8_t numEps, uint8_t numIfs, uint8_t *epType) : - numEndpoints(numEps), numInterfaces(numIfs), endpointType(epType) - { } - -protected: - virtual bool setup(USBSetup& setup) = 0; - virtual int getInterface(uint8_t* interfaceCount) = 0; - virtual int getDescriptor(USBSetup& setup) = 0; - virtual uint8_t getShortName(char *name) { name[0] = 'A'+pluggedInterface; return 1; } - - uint8_t pluggedInterface; - uint8_t pluggedEndpoint; - - const uint8_t numEndpoints; - const uint8_t numInterfaces; - const uint8_t *endpointType; - - PluggableUSBModule *next = NULL; - - friend class PluggableUSB_; -}; - -class PluggableUSB_ { -public: - PluggableUSB_(); - bool plug(PluggableUSBModule *node); - int getInterface(uint8_t* interfaceCount); - int getDescriptor(USBSetup& setup); - bool setup(USBSetup& setup); - void getShortName(char *iSerialNum); - -private: - uint8_t lastIf; - uint8_t lastEp; - PluggableUSBModule* rootNode; -}; - -// Replacement for global singleton. -// This function prevents static-initialization-order-fiasco -// https://isocpp.org/wiki/faq/ctors#static-init-order-on-first-use -PluggableUSB_& PluggableUSB(); - -#endif - -#endif diff --git a/GyverCore/cores/arduino/Server.h b/GyverCore/cores/arduino/Server.h deleted file mode 100644 index 69e3e39..0000000 --- a/GyverCore/cores/arduino/Server.h +++ /dev/null @@ -1,30 +0,0 @@ -/* - Server.h - Base class that provides Server - Copyright (c) 2011 Adrian McEwen. All right reserved. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library 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 - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef server_h -#define server_h - -#include "Print.h" - -class Server : public Print { -public: - virtual void begin() =0; -}; - -#endif diff --git a/GyverCore/cores/arduino/Tone.cpp b/GyverCore/cores/arduino/Tone.cpp index 1bfb3e3..4321898 100644 --- a/GyverCore/cores/arduino/Tone.cpp +++ b/GyverCore/cores/arduino/Tone.cpp @@ -37,7 +37,7 @@ Version Modified By Date Comments #include #include #include "Arduino.h" -#include "pins_arduino.h" +//#include "pins_arduino.h" #if defined(__AVR_ATmega8__) || defined(__AVR_ATmega128__) #define TCCR2A TCCR2 diff --git a/GyverCore/cores/arduino/USBAPI.h b/GyverCore/cores/arduino/USBAPI.h deleted file mode 100644 index 479ced9..0000000 --- a/GyverCore/cores/arduino/USBAPI.h +++ /dev/null @@ -1,207 +0,0 @@ -/* - USBAPI.h - Copyright (c) 2005-2014 Arduino. All right reserved. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library 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 - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef __USBAPI__ -#define __USBAPI__ - -#include -#include -#include -#include -#include - -typedef unsigned char u8; -typedef unsigned short u16; -typedef unsigned long u32; - -#include "Arduino.h" - -// This definitions is usefull if you want to reduce the EP_SIZE to 16 -// at the moment only 64 and 16 as EP_SIZE for all EPs are supported except the control endpoint -#ifndef USB_EP_SIZE -#define USB_EP_SIZE 64 -#endif - -#if defined(USBCON) - -#include "USBDesc.h" -#include "USBCore.h" - -//================================================================================ -//================================================================================ -// USB - -#define EP_TYPE_CONTROL (0x00) -#define EP_TYPE_BULK_IN ((1<256) -#error Please lower the CDC Buffer size -#endif - -class Serial_ : public Stream -{ -private: - int peek_buffer; -public: - Serial_() { peek_buffer = -1; }; - void begin(unsigned long); - void begin(unsigned long, uint8_t); - void end(void); - - virtual int available(void); - virtual int peek(void); - virtual int read(void); - virtual int availableForWrite(void); - virtual void flush(void); - virtual size_t write(uint8_t); - virtual size_t write(const uint8_t*, size_t); - using Print::write; // pull in write(str) and write(buf, size) from Print - operator bool(); - - volatile uint8_t _rx_buffer_head; - volatile uint8_t _rx_buffer_tail; - unsigned char _rx_buffer[SERIAL_BUFFER_SIZE]; - - // This method allows processing "SEND_BREAK" requests sent by - // the USB host. Those requests indicate that the host wants to - // send a BREAK signal and are accompanied by a single uint16_t - // value, specifying the duration of the break. The value 0 - // means to end any current break, while the value 0xffff means - // to start an indefinite break. - // readBreak() will return the value of the most recent break - // request, but will return it at most once, returning -1 when - // readBreak() is called again (until another break request is - // received, which is again returned once). - // This also mean that if two break requests are received - // without readBreak() being called in between, the value of the - // first request is lost. - // Note that the value returned is a long, so it can return - // 0-0xffff as well as -1. - int32_t readBreak(); - - // These return the settings specified by the USB host for the - // serial port. These aren't really used, but are offered here - // in case a sketch wants to act on these settings. - uint32_t baud(); - uint8_t stopbits(); - uint8_t paritytype(); - uint8_t numbits(); - bool dtr(); - bool rts(); - enum { - ONE_STOP_BIT = 0, - ONE_AND_HALF_STOP_BIT = 1, - TWO_STOP_BITS = 2, - }; - enum { - NO_PARITY = 0, - ODD_PARITY = 1, - EVEN_PARITY = 2, - MARK_PARITY = 3, - SPACE_PARITY = 4, - }; - -}; -extern Serial_ Serial; - -#define HAVE_CDCSERIAL - -//================================================================================ -//================================================================================ -// Low level API - -typedef struct -{ - uint8_t bmRequestType; - uint8_t bRequest; - uint8_t wValueL; - uint8_t wValueH; - uint16_t wIndex; - uint16_t wLength; -} USBSetup; - -//================================================================================ -//================================================================================ -// MSC 'Driver' - -int MSC_GetInterface(uint8_t* interfaceNum); -int MSC_GetDescriptor(int i); -bool MSC_Setup(USBSetup& setup); -bool MSC_Data(uint8_t rx,uint8_t tx); - -//================================================================================ -//================================================================================ -// CSC 'Driver' - -int CDC_GetInterface(uint8_t* interfaceNum); -int CDC_GetDescriptor(int i); -bool CDC_Setup(USBSetup& setup); - -//================================================================================ -//================================================================================ - -#define TRANSFER_PGM 0x80 -#define TRANSFER_RELEASE 0x40 -#define TRANSFER_ZERO 0x20 - -int USB_SendControl(uint8_t flags, const void* d, int len); -int USB_RecvControl(void* d, int len); -int USB_RecvControlLong(void* d, int len); - -uint8_t USB_Available(uint8_t ep); -uint8_t USB_SendSpace(uint8_t ep); -int USB_Send(uint8_t ep, const void* data, int len); // blocking -int USB_Recv(uint8_t ep, void* data, int len); // non-blocking -int USB_Recv(uint8_t ep); // non-blocking -void USB_Flush(uint8_t ep); - -#endif - -#endif /* if defined(USBCON) */ diff --git a/GyverCore/cores/arduino/USBCore.cpp b/GyverCore/cores/arduino/USBCore.cpp deleted file mode 100644 index 81f689d..0000000 --- a/GyverCore/cores/arduino/USBCore.cpp +++ /dev/null @@ -1,858 +0,0 @@ - - -/* Copyright (c) 2010, Peter Barrett -** Sleep/Wakeup support added by Michael Dreher -** -** Permission to use, copy, modify, and/or distribute this software for -** any purpose with or without fee is hereby granted, provided that the -** above copyright notice and this permission notice appear in all copies. -** -** THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL -** WARRANTIES WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED -** WARRANTIES OF MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR -** BE LIABLE FOR ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES -** OR ANY DAMAGES WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, -** WHETHER IN AN ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, -** ARISING OUT OF OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS -** SOFTWARE. -*/ - -#include "USBAPI.h" -#include "PluggableUSB.h" -#include - -#if defined(USBCON) - -/** Pulse generation counters to keep track of the number of milliseconds remaining for each pulse type */ -#define TX_RX_LED_PULSE_MS 100 -volatile u8 TxLEDPulse; /**< Milliseconds remaining for data Tx LED pulse */ -volatile u8 RxLEDPulse; /**< Milliseconds remaining for data Rx LED pulse */ - -//================================================================== -//================================================================== - -extern const u16 STRING_LANGUAGE[] PROGMEM; -extern const u8 STRING_PRODUCT[] PROGMEM; -extern const u8 STRING_MANUFACTURER[] PROGMEM; -extern const DeviceDescriptor USB_DeviceDescriptorIAD PROGMEM; - -const u16 STRING_LANGUAGE[2] = { - (3<<8) | (2+2), - 0x0409 // English -}; - -#ifndef USB_PRODUCT -// If no product is provided, use USB IO Board -#define USB_PRODUCT "USB IO Board" -#endif - -const u8 STRING_PRODUCT[] PROGMEM = USB_PRODUCT; - -#if USB_VID == 0x2341 -# if defined(USB_MANUFACTURER) -# undef USB_MANUFACTURER -# endif -# define USB_MANUFACTURER "Arduino LLC" -#elif USB_VID == 0x1b4f -# if defined(USB_MANUFACTURER) -# undef USB_MANUFACTURER -# endif -# define USB_MANUFACTURER "SparkFun" -#elif !defined(USB_MANUFACTURER) -// Fall through to unknown if no manufacturer name was provided in a macro -# define USB_MANUFACTURER "Unknown" -#endif - -const u8 STRING_MANUFACTURER[] PROGMEM = USB_MANUFACTURER; - - -#define DEVICE_CLASS 0x02 - -// DEVICE DESCRIPTOR -const DeviceDescriptor USB_DeviceDescriptorIAD = - D_DEVICE(0xEF,0x02,0x01,64,USB_VID,USB_PID,0x100,IMANUFACTURER,IPRODUCT,ISERIAL,1); - -//================================================================== -//================================================================== - -volatile u8 _usbConfiguration = 0; -volatile u8 _usbCurrentStatus = 0; // meaning of bits see usb_20.pdf, Figure 9-4. Information Returned by a GetStatus() Request to a Device -volatile u8 _usbSuspendState = 0; // copy of UDINT to check SUSPI and WAKEUPI bits - -static inline void WaitIN(void) -{ - while (!(UEINTX & (1< len) { - n = len; - } - - { - LockEP lock(ep); - // Frame may have been released by the SOF interrupt handler - if (!ReadWriteAllowed()) - continue; - - len -= n; - if (ep & TRANSFER_ZERO) - { - while (n--) - Send8(0); - } - else if (ep & TRANSFER_PGM) - { - while (n--) - Send8(pgm_read_byte(data++)); - } - else - { - while (n--) - Send8(*data++); - } - - if (sendZlp) { - ReleaseTX(); - sendZlp = false; - } else if (!ReadWriteAllowed()) { // ...release if buffer is full... - ReleaseTX(); - if (len == 0) sendZlp = true; - } else if ((len == 0) && (ep & TRANSFER_RELEASE)) { // ...or if forced with TRANSFER_RELEASE - // XXX: TRANSFER_RELEASE is never used can be removed? - ReleaseTX(); - } - } - } - TXLED1; // light the TX LED - TxLEDPulse = TX_RX_LED_PULSE_MS; - return r; -} - -u8 _initEndpoints[USB_ENDPOINTS] = -{ - 0, // Control Endpoint - - EP_TYPE_INTERRUPT_IN, // CDC_ENDPOINT_ACM - EP_TYPE_BULK_OUT, // CDC_ENDPOINT_OUT - EP_TYPE_BULK_IN, // CDC_ENDPOINT_IN - - // Following endpoints are automatically initialized to 0 -}; - -#define EP_SINGLE_64 0x32 // EP0 -#define EP_DOUBLE_64 0x36 // Other endpoints -#define EP_SINGLE_16 0x12 - -static -void InitEP(u8 index, u8 type, u8 size) -{ - UENUM = index; - UECONX = (1< 64){ - recvLength = 64; - } - - // Write data to fit to the end (not the beginning) of the array - WaitOUT(); - Recv((u8*)d + len - length, recvLength); - ClearOUT(); - length -= recvLength; - } - return len; -} - -static u8 SendInterfaces() -{ - u8 interfaces = 0; - - CDC_GetInterface(&interfaces); - -#ifdef PLUGGABLE_USB_ENABLED - PluggableUSB().getInterface(&interfaces); -#endif - - return interfaces; -} - -// Construct a dynamic configuration descriptor -// This really needs dynamic endpoint allocation etc -// TODO -static -bool SendConfiguration(int maxlen) -{ - // Count and measure interfaces - InitControl(0); - u8 interfaces = SendInterfaces(); - ConfigDescriptor config = D_CONFIG(_cmark + sizeof(ConfigDescriptor),interfaces); - - // Now send them - InitControl(maxlen); - USB_SendControl(0,&config,sizeof(ConfigDescriptor)); - SendInterfaces(); - return true; -} - -static -bool SendDescriptor(USBSetup& setup) -{ - int ret; - u8 t = setup.wValueH; - if (USB_CONFIGURATION_DESCRIPTOR_TYPE == t) - return SendConfiguration(setup.wLength); - - InitControl(setup.wLength); -#ifdef PLUGGABLE_USB_ENABLED - ret = PluggableUSB().getDescriptor(setup); - if (ret != 0) { - return (ret > 0 ? true : false); - } -#endif - - const u8* desc_addr = 0; - if (USB_DEVICE_DESCRIPTOR_TYPE == t) - { - desc_addr = (const u8*)&USB_DeviceDescriptorIAD; - } - else if (USB_STRING_DESCRIPTOR_TYPE == t) - { - if (setup.wValueL == 0) { - desc_addr = (const u8*)&STRING_LANGUAGE; - } - else if (setup.wValueL == IPRODUCT) { - return USB_SendStringDescriptor(STRING_PRODUCT, strlen(USB_PRODUCT), TRANSFER_PGM); - } - else if (setup.wValueL == IMANUFACTURER) { - return USB_SendStringDescriptor(STRING_MANUFACTURER, strlen(USB_MANUFACTURER), TRANSFER_PGM); - } - else if (setup.wValueL == ISERIAL) { -#ifdef PLUGGABLE_USB_ENABLED - char name[ISERIAL_MAX_LEN]; - PluggableUSB().getShortName(name); - return USB_SendStringDescriptor((uint8_t*)name, strlen(name), 0); -#endif - } - else - return false; - } - - if (desc_addr == 0) - return false; - u8 desc_length = pgm_read_byte(desc_addr); - - USB_SendControl(TRANSFER_PGM,desc_addr,desc_length); - return true; -} - -// Endpoint 0 interrupt -ISR(USB_COM_vect) -{ - SetEP(0); - if (!ReceivedSetupInt()) - return; - - USBSetup setup; - Recv((u8*)&setup,8); - ClearSetupInt(); - - u8 requestType = setup.bmRequestType; - if (requestType & REQUEST_DEVICETOHOST) - WaitIN(); - else - ClearIN(); - - bool ok = true; - if (REQUEST_STANDARD == (requestType & REQUEST_TYPE)) - { - // Standard Requests - u8 r = setup.bRequest; - u16 wValue = setup.wValueL | (setup.wValueH << 8); - if (GET_STATUS == r) - { - if (requestType == (REQUEST_DEVICETOHOST | REQUEST_STANDARD | REQUEST_DEVICE)) - { - Send8(_usbCurrentStatus); - Send8(0); - } - else - { - // TODO: handle the HALT state of an endpoint here - // see "Figure 9-6. Information Returned by a GetStatus() Request to an Endpoint" in usb_20.pdf for more information - Send8(0); - Send8(0); - } - } - else if (CLEAR_FEATURE == r) - { - if((requestType == (REQUEST_HOSTTODEVICE | REQUEST_STANDARD | REQUEST_DEVICE)) - && (wValue == DEVICE_REMOTE_WAKEUP)) - { - _usbCurrentStatus &= ~FEATURE_REMOTE_WAKEUP_ENABLED; - } - } - else if (SET_FEATURE == r) - { - if((requestType == (REQUEST_HOSTTODEVICE | REQUEST_STANDARD | REQUEST_DEVICE)) - && (wValue == DEVICE_REMOTE_WAKEUP)) - { - _usbCurrentStatus |= FEATURE_REMOTE_WAKEUP_ENABLED; - } - } - else if (SET_ADDRESS == r) - { - WaitIN(); - UDADDR = setup.wValueL | (1<> 8) & 0xFF) - -#define CDC_V1_10 0x0110 -#define CDC_COMMUNICATION_INTERFACE_CLASS 0x02 - -#define CDC_CALL_MANAGEMENT 0x01 -#define CDC_ABSTRACT_CONTROL_MODEL 0x02 -#define CDC_HEADER 0x00 -#define CDC_ABSTRACT_CONTROL_MANAGEMENT 0x02 -#define CDC_UNION 0x06 -#define CDC_CS_INTERFACE 0x24 -#define CDC_CS_ENDPOINT 0x25 -#define CDC_DATA_INTERFACE_CLASS 0x0A - -#define MSC_SUBCLASS_SCSI 0x06 -#define MSC_PROTOCOL_BULK_ONLY 0x50 - -#ifndef USB_VERSION -#define USB_VERSION 0x200 -#endif - -// Device -typedef struct { - u8 len; // 18 - u8 dtype; // 1 USB_DEVICE_DESCRIPTOR_TYPE - u16 usbVersion; // 0x200 or 0x210 - u8 deviceClass; - u8 deviceSubClass; - u8 deviceProtocol; - u8 packetSize0; // Packet 0 - u16 idVendor; - u16 idProduct; - u16 deviceVersion; // 0x100 - u8 iManufacturer; - u8 iProduct; - u8 iSerialNumber; - u8 bNumConfigurations; -} DeviceDescriptor; - -// Config -typedef struct { - u8 len; // 9 - u8 dtype; // 2 - u16 clen; // total length - u8 numInterfaces; - u8 config; - u8 iconfig; - u8 attributes; - u8 maxPower; -} ConfigDescriptor; - -// String - -// Interface -typedef struct -{ - u8 len; // 9 - u8 dtype; // 4 - u8 number; - u8 alternate; - u8 numEndpoints; - u8 interfaceClass; - u8 interfaceSubClass; - u8 protocol; - u8 iInterface; -} InterfaceDescriptor; - -// Endpoint -typedef struct -{ - u8 len; // 7 - u8 dtype; // 5 - u8 addr; - u8 attr; - u16 packetSize; - u8 interval; -} EndpointDescriptor; - -// Interface Association Descriptor -// Used to bind 2 interfaces together in CDC compostite device -typedef struct -{ - u8 len; // 8 - u8 dtype; // 11 - u8 firstInterface; - u8 interfaceCount; - u8 functionClass; - u8 funtionSubClass; - u8 functionProtocol; - u8 iInterface; -} IADDescriptor; - -// CDC CS interface descriptor -typedef struct -{ - u8 len; // 5 - u8 dtype; // 0x24 - u8 subtype; - u8 d0; - u8 d1; -} CDCCSInterfaceDescriptor; - -typedef struct -{ - u8 len; // 4 - u8 dtype; // 0x24 - u8 subtype; - u8 d0; -} CDCCSInterfaceDescriptor4; - -typedef struct -{ - u8 len; - u8 dtype; // 0x24 - u8 subtype; // 1 - u8 bmCapabilities; - u8 bDataInterface; -} CMFunctionalDescriptor; - -typedef struct -{ - u8 len; - u8 dtype; // 0x24 - u8 subtype; // 1 - u8 bmCapabilities; -} ACMFunctionalDescriptor; - -typedef struct -{ - // IAD - IADDescriptor iad; // Only needed on compound device - - // Control - InterfaceDescriptor cif; // - CDCCSInterfaceDescriptor header; - CMFunctionalDescriptor callManagement; // Call Management - ACMFunctionalDescriptor controlManagement; // ACM - CDCCSInterfaceDescriptor functionalDescriptor; // CDC_UNION - EndpointDescriptor cifin; - - // Data - InterfaceDescriptor dif; - EndpointDescriptor in; - EndpointDescriptor out; -} CDCDescriptor; - -typedef struct -{ - InterfaceDescriptor msc; - EndpointDescriptor in; - EndpointDescriptor out; -} MSCDescriptor; - - -#define D_DEVICE(_class,_subClass,_proto,_packetSize0,_vid,_pid,_version,_im,_ip,_is,_configs) \ - { 18, 1, USB_VERSION, _class,_subClass,_proto,_packetSize0,_vid,_pid,_version,_im,_ip,_is,_configs } - -#define D_CONFIG(_totalLength,_interfaces) \ - { 9, 2, _totalLength,_interfaces, 1, 0, USB_CONFIG_BUS_POWERED | USB_CONFIG_REMOTE_WAKEUP, USB_CONFIG_POWER_MA(500) } - -#define D_INTERFACE(_n,_numEndpoints,_class,_subClass,_protocol) \ - { 9, 4, _n, 0, _numEndpoints, _class,_subClass, _protocol, 0 } - -#define D_ENDPOINT(_addr,_attr,_packetSize, _interval) \ - { 7, 5, _addr,_attr,_packetSize, _interval } - -#define D_IAD(_firstInterface, _count, _class, _subClass, _protocol) \ - { 8, 11, _firstInterface, _count, _class, _subClass, _protocol, 0 } - -#define D_CDCCS(_subtype,_d0,_d1) { 5, 0x24, _subtype, _d0, _d1 } -#define D_CDCCS4(_subtype,_d0) { 4, 0x24, _subtype, _d0 } - -// Bootloader related fields -// Old Caterina bootloader places the MAGIC key into unsafe RAM locations (it can be rewritten -// by the running sketch before to actual reboot). -// Newer bootloaders, recognizable by the LUFA "signature" at the end of the flash, can handle both -// the usafe and the safe location. -#ifndef MAGIC_KEY -#define MAGIC_KEY 0x7777 -#endif - -#ifndef MAGIC_KEY_POS -#define MAGIC_KEY_POS 0x0800 -#endif - -#ifndef NEW_LUFA_SIGNATURE -#define NEW_LUFA_SIGNATURE 0xDCFB -#endif - -#endif diff --git a/GyverCore/cores/arduino/USBDesc.h b/GyverCore/cores/arduino/USBDesc.h deleted file mode 100644 index c0dce07..0000000 --- a/GyverCore/cores/arduino/USBDesc.h +++ /dev/null @@ -1,46 +0,0 @@ -/* - Copyright (c) 2011, Peter Barrett - Copyright (c) 2015, Arduino LLC - - Permission to use, copy, modify, and/or distribute this software for - any purpose with or without fee is hereby granted, provided that the - above copyright notice and this permission notice appear in all copies. - - THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL - WARRANTIES WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED - WARRANTIES OF MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR - BE LIABLE FOR ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES - OR ANY DAMAGES WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, - WHETHER IN AN ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, - ARISING OUT OF OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS - SOFTWARE. - */ - -#define PLUGGABLE_USB_ENABLED - -#if defined(EPRST6) -#define USB_ENDPOINTS 7 // AtMegaxxU4 -#else -#define USB_ENDPOINTS 5 // AtMegaxxU2 -#endif - -#define ISERIAL_MAX_LEN 20 - -#define CDC_INTERFACE_COUNT 2 -#define CDC_ENPOINT_COUNT 3 - -#define CDC_ACM_INTERFACE 0 // CDC ACM -#define CDC_DATA_INTERFACE 1 // CDC Data -#define CDC_FIRST_ENDPOINT 1 -#define CDC_ENDPOINT_ACM (CDC_FIRST_ENDPOINT) // CDC First -#define CDC_ENDPOINT_OUT (CDC_FIRST_ENDPOINT+1) -#define CDC_ENDPOINT_IN (CDC_FIRST_ENDPOINT+2) - -#define INTERFACE_COUNT (MSC_INTERFACE + MSC_INTERFACE_COUNT) - -#define CDC_RX CDC_ENDPOINT_OUT -#define CDC_TX CDC_ENDPOINT_IN - -#define IMANUFACTURER 1 -#define IPRODUCT 2 -#define ISERIAL 3 \ No newline at end of file diff --git a/GyverCore/cores/arduino/Udp.h b/GyverCore/cores/arduino/Udp.h deleted file mode 100644 index 89f31c6..0000000 --- a/GyverCore/cores/arduino/Udp.h +++ /dev/null @@ -1,89 +0,0 @@ -/* - * Udp.cpp: Library to send/receive UDP packets. - * - * NOTE: UDP is fast, but has some important limitations (thanks to Warren Gray for mentioning these) - * 1) UDP does not guarantee the order in which assembled UDP packets are received. This - * might not happen often in practice, but in larger network topologies, a UDP - * packet can be received out of sequence. - * 2) UDP does not guard against lost packets - so packets *can* disappear without the sender being - * aware of it. Again, this may not be a concern in practice on small local networks. - * For more information, see http://www.cafeaulait.org/course/week12/35.html - * - * MIT License: - * Copyright (c) 2008 Bjoern Hartmann - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in - * all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - * THE SOFTWARE. - * - * bjoern@cs.stanford.edu 12/30/2008 - */ - -#ifndef udp_h -#define udp_h - -#include -#include - -class UDP : public Stream { - -public: - virtual uint8_t begin(uint16_t) =0; // initialize, start listening on specified port. Returns 1 if successful, 0 if there are no sockets available to use - virtual uint8_t beginMulticast(IPAddress, uint16_t) { return 0; } // initialize, start listening on specified multicast IP address and port. Returns 1 if successful, 0 on failure - virtual void stop() =0; // Finish with the UDP socket - - // Sending UDP packets - - // Start building up a packet to send to the remote host specific in ip and port - // Returns 1 if successful, 0 if there was a problem with the supplied IP address or port - virtual int beginPacket(IPAddress ip, uint16_t port) =0; - // Start building up a packet to send to the remote host specific in host and port - // Returns 1 if successful, 0 if there was a problem resolving the hostname or port - virtual int beginPacket(const char *host, uint16_t port) =0; - // Finish off this packet and send it - // Returns 1 if the packet was sent successfully, 0 if there was an error - virtual int endPacket() =0; - // Write a single byte into the packet - virtual size_t write(uint8_t) =0; - // Write size bytes from buffer into the packet - virtual size_t write(const uint8_t *buffer, size_t size) =0; - - // Start processing the next available incoming packet - // Returns the size of the packet in bytes, or 0 if no packets are available - virtual int parsePacket() =0; - // Number of bytes remaining in the current packet - virtual int available() =0; - // Read a single byte from the current packet - virtual int read() =0; - // Read up to len bytes from the current packet and place them into buffer - // Returns the number of bytes read, or 0 if none are available - virtual int read(unsigned char* buffer, size_t len) =0; - // Read up to len characters from the current packet and place them into buffer - // Returns the number of characters read, or 0 if none are available - virtual int read(char* buffer, size_t len) =0; - // Return the next byte from the current packet without moving on to the next byte - virtual int peek() =0; - virtual void flush() =0; // Finish reading the current packet - - // Return the IP address of the host who sent the current incoming packet - virtual IPAddress remoteIP() =0; - // Return the port of the host who sent the current incoming packet - virtual uint16_t remotePort() =0; -protected: - uint8_t* rawIPAddress(IPAddress& addr) { return addr.raw_address(); }; -}; - -#endif diff --git a/GyverCore/cores/arduino/WInterrupts.c b/GyverCore/cores/arduino/WInterrupts.c index cef1106..e0b7ceb 100644 --- a/GyverCore/cores/arduino/WInterrupts.c +++ b/GyverCore/cores/arduino/WInterrupts.c @@ -1,324 +1,47 @@ -/* -*- mode: jde; c-basic-offset: 2; indent-tabs-mode: nil -*- */ - -/* - Part of the Wiring project - http://wiring.uniandes.edu.co - - Copyright (c) 2004-05 Hernando Barragan - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library 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 - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General - Public License along with this library; if not, write to the - Free Software Foundation, Inc., 59 Temple Place, Suite 330, - Boston, MA 02111-1307 USA - - Modified 24 November 2006 by David A. Mellis - Modified 1 August 2010 by Mark Sproul -*/ - +/* внешние прерывания*/ #include #include #include #include #include +#include "Arduino.h" -#include "wiring_private.h" +extern void (*ext_isr0)(); +extern void (*ext_isr1)(); +void (*ext_isr0)(); +void (*ext_isr1)(); -static void nothing(void) { +ISR(INT0_vect){ +(*ext_isr0)(); +} +ISR(INT1_vect){ +(*ext_isr1)(); } -static volatile voidFuncPtr intFunc[EXTERNAL_NUM_INTERRUPTS] = { -#if EXTERNAL_NUM_INTERRUPTS > 8 - #warning There are more than 8 external interrupts. Some callbacks may not be initialized. - nothing, -#endif -#if EXTERNAL_NUM_INTERRUPTS > 7 - nothing, -#endif -#if EXTERNAL_NUM_INTERRUPTS > 6 - nothing, -#endif -#if EXTERNAL_NUM_INTERRUPTS > 5 - nothing, -#endif -#if EXTERNAL_NUM_INTERRUPTS > 4 - nothing, -#endif -#if EXTERNAL_NUM_INTERRUPTS > 3 - nothing, -#endif -#if EXTERNAL_NUM_INTERRUPTS > 2 - nothing, -#endif -#if EXTERNAL_NUM_INTERRUPTS > 1 - nothing, -#endif -#if EXTERNAL_NUM_INTERRUPTS > 0 - nothing, -#endif -}; -// volatile static voidFuncPtr twiIntFunc; -void attachInterrupt(uint8_t interruptNum, void (*userFunc)(void), int mode) { - if(interruptNum < EXTERNAL_NUM_INTERRUPTS) { - intFunc[interruptNum] = userFunc; - - // Configure the interrupt mode (trigger on low input, any change, rising - // edge, or falling edge). The mode constants were chosen to correspond - // to the configuration bits in the hardware register, so we simply shift - // the mode into place. - - // Enable the interrupt. - - switch (interruptNum) { -#if defined(__AVR_ATmega32U4__) - // I hate doing this, but the register assignment differs between the 1280/2560 - // and the 32U4. Since avrlib defines registers PCMSK1 and PCMSK2 that aren't - // even present on the 32U4 this is the only way to distinguish between them. - case 0: - EICRA = (EICRA & ~((1< - -// Declared weak in Arduino.h to allow user redefinitions. -int atexit(void (* /*func*/ )()) { return 0; } - -// Weak empty variant initialization function. -// May be redefined by variant files. -void initVariant() __attribute__((weak)); -void initVariant() { } - -void setupUSB() __attribute__((weak)); -void setupUSB() { } - int main(void) { - init(); - - initVariant(); - -#if defined(USBCON) - USBDevice.attach(); -#endif - + WDTCSR = 0; // wdt disable + init(); setup(); - - for (;;) { + while (1) { loop(); if (serialEventRun) serialEventRun(); - } - + } return 0; } diff --git a/GyverCore/cores/arduino/pinOperation.cpp b/GyverCore/cores/arduino/pinOperation.cpp new file mode 100644 index 0000000..0d2d0d6 --- /dev/null +++ b/GyverCore/cores/arduino/pinOperation.cpp @@ -0,0 +1,391 @@ +/* +Нормальный ввод/вывод +*/ +#include "Arduino.h" +#include + +// ============= DIGITAL ============= + +void pinMode(uint8_t pin, uint8_t mode) +{ + switch (mode) { + case 0: // input + if (pin < 8) bitWrite(DDRD, pin, 0); // расставляем нули в DDRn + else if (pin < 14) bitWrite(DDRB, (pin - 8), 0); + else if (pin < 20) bitWrite(DDRC, (pin - 14), 0); + break; + case 1: // output + if (pin < 8) bitWrite(DDRD, pin, 1); // расставляем еденицы в DDRn + else if (pin < 14) bitWrite(DDRB, (pin - 8), 1); + else if (pin < 20) bitWrite(DDRC, (pin - 14), 1); + break; + case 2: // in_pullup + if (pin < 8) { + bitWrite(DDRD, pin, 0); // настраиваем как вх + bitWrite(PORTD, pin, 0); // вкл подтяжку + } + else if (pin < 14) { + bitWrite(DDRB, (pin - 8), 0); + bitWrite(PORTB, (pin - 8), 1); + } + else if (pin < 20) { + bitWrite(DDRC, (pin - 14), 0); + bitWrite(PORTC, (pin - 14), 1); + } + break; + } +} + +void digitalWrite(uint8_t pin, uint8_t x) { + switch (pin) { // откл pwm + case 3: // 2B + TCCR2A &= ~(1 << COM2B1); + break; + case 5: // 0B + TCCR0A &= ~(1 << COM0B1); + break; + case 6: // 0A + TCCR0A &= ~(1 << COM0A1); + break; + case 9: // 1A + TCCR1A &= ~(1 << COM1A1); + break; + case 10: // 1B + TCCR1A &= ~(1 << COM1B1); + break; + case 11: // 2A + TCCR2A &= ~(1 << COM2A1); + break; + } + if (pin < 8) bitWrite(PORTD, pin, x); + else if (pin < 14) bitWrite(PORTB, (pin - 8), x); + else if (pin < 20) bitWrite(PORTC, (pin - 14), x); +} + +int digitalRead (uint8_t pin) { + if (pin < 8) return bitRead(PIND, pin); + else if (pin < 14) return bitRead(PINB, pin - 8); + else if (pin < 20) return bitRead(PINC, pin - 14); +} + + +void digitalToggle(uint8_t pin){ + if (pin < 8) bitToggle(PORTD, pin); + else if (pin < 14) bitToggle(PORTB, pin - 8); + else if (pin < 20) bitToggle(PORTC, pin - 14); + /* + if (pin < 8) { + bitWrite(PORTD, pin, !bitRead(PORTD,pin)); + } + else if (pin < 14){ + bitWrite(PORTB, (pin - 8),!bitRead(PORTB,(pin-8))); + } + else if (pin < 20){ + bitWrite(PORTC, (pin - 14), !bitRead(PORTC,(pin-14))); + } + */ +} +// ============= ANALOG ============= +void analogPrescaler (uint8_t prescl) { + cli(); + switch (prescl) { + case 2: + ADCSRA &= ~((1 << ADPS2) | (1 << ADPS1) | (1 << ADPS0)); + break; + case 4: // (defalut) + ADCSRA &= ~((1 << ADPS2) | (1 << ADPS0)); + ADCSRA |= (1 << ADPS1); + break; + case 8: + ADCSRA &= ~ (1 << ADPS2); + ADCSRA |= ((1 << ADPS1) | (1 << ADPS0)); + break; + case 16: + ADCSRA &= ~((1 << ADPS1) | (1 << ADPS0)); + ADCSRA |= (1 << ADPS2); + break; + case 32: + ADCSRA &= ~ (1 << ADPS1); + ADCSRA |= ((1 << ADPS2) | (1 << ADPS0)); + break; + case 64: + ADCSRA &= ~ (1 << ADPS0); + ADCSRA |= ((1 << ADPS2) | (1 << ADPS1)); + break; + case 128: + ADCSRA |= ((1 << ADPS2) | (1 << ADPS1) | (1 << ADPS0)); + break; + } + sei(); +} + +void analogReference(uint8_t mode) +{ + switch (mode) { + case 0: //ext + ADMUX &= ~ ((1 << REFS1) | (1 << REFS0)); + break; + case 1: //def + ADMUX &= ~ (1 << REFS1); + ADMUX |= (1 << REFS0); + break; + case 28: // interal + ADMUX |= ((1 << REFS1) | (1 << REFS0)); + break; + } +} + +int analogRead(uint8_t pin) +{ + cli(); + pin = pin - 14; + ADMUX &= ~((1 << MUX3) | (1 << MUX2) | (1 << MUX1) | (1 << MUX0)); // обнуляем мультиплексор + ADMUX = ADMUX | pin; // задвигаем номер входа + sei(); + ADCSRA |= (1 << ADSC); // начинаем преобразование + while (ADCSRA & (1 << ADSC)); // ждем окончания + return ADCL | (ADCH << 8); // склеить и вернуть результат +} + +void analogStartConvert(byte pin) { + cli(); + pin = pin - 14; + ADMUX &= ~((1 << MUX3) | (1 << MUX2) | (1 << MUX1) | (1 << MUX0)); // обнуляем мультиплексор + ADMUX = ADMUX | pin; // задвигаем номер входа + sei(); + ADCSRA |= (1 << ADSC); // начинаем преобразование +} + +int analogGet() { + while (ADCSRA & (1 << ADSC)); // ждем окончания + return ADCL | (ADCH << 8); // склеить и вернуть результат +} + +// ============= PWM ============= + +boolean _TMR0_HF_PWM = false; +boolean _TMR1_HF_PWM = false; +boolean _TMR2_HF_PWM = false; +boolean _TMR1_HR_PWM = false; + +void analogWrite(uint8_t pin, int val) +{ + cli(); + switch (val) { + case 0: + digitalWrite(pin, 0); + break; + /*case 255: + digitalWrite(pin, 1); + break;*/ + default: + switch (pin) { // вкл pwm + case 3: // 2B + if (!_TMR2_HF_PWM) { + TCCR2A |= (1 << COM2B1); + OCR2A = val; + } else { + if (val == 0) { + bitClear(TCCR2A, COM2B1); + bitClear(PORTD, 3); + } else { + bitSet(TCCR2A, COM2B1); + OCR2B = map(val, 0, 255, 0, 99); + } + } + break; + case 5: // 0B + if (!_TMR0_HF_PWM) { + TCCR0A |= (1 << COM0B1); + OCR0B = val; + } else { + if (val == 0) { + bitClear(TCCR0A, COM0B1); + bitClear(PORTD, 5); + } else { + bitSet(TCCR0A, COM0B1); + OCR0B = map(val, 0, 255, 0, 99); + } + } + + break; + case 6: // 0A + TCCR0A |= (1 << COM0A1); + OCR0A = val; + break; + case 9: // 1A + if (!_TMR1_HF_PWM) { + TCCR1A |= (1 << COM1A1); + OCR1A = val; + } else { + if (!_TMR1_HR_PWM) val *= 3.13; + else val *= 0.78; + OCR1AH = highByte(val); + OCR1AL = lowByte(val); + } + break; + case 10: // 1B + if (!_TMR1_HF_PWM) { + TCCR1A |= (1 << COM1B1); + OCR1B = val; + } else { + if (!_TMR1_HR_PWM) val *= 3.13; + else val *= 0.78; + OCR1BH = highByte(val); + OCR1BL = lowByte(val); + } + break; + case 11: // 2A + TCCR2A |= (1 << COM2A1); + OCR2A = val; + break; + } + break; + } + sei(); +} + +/* +void setPWM_20kHz(byte pin); // установить частоту ШИМ 20 кГц (8 бит) на 3, 5, 9, 10 +void setPWM_9_10_resolution(boolean resolution); // разрешение ШИМ на пинах 9 и 10 для 20 кГц: 0 - 8 бит, 1 - 10 бит +void setPwmFreqnuency(pin, freq); // установить частоту ШИМ (8 бит) на 3, 5, 6, 9, 10, 11: default, 8KHZ, 31KHZ +void setPWM_default(byte pin); // настроить ШИМ по умолчанию +*/ + +void setPWM_20kHz(byte pin) { + cli(); + switch (pin) { // вкл pwm + case 3: // 2B + TCCR2A = 0b10100011; + TCCR2B = 0b00001010; + OCR2A = 99; + _TMR2_HF_PWM = true; + break; + case 5: // 0B + TCCR0A = 0b10100011; + TCCR0B = 0b00001010; + OCR0A = 99; + _TMR0_HF_PWM = true; + break; + case 9: // 1A + TCCR1A = 0b10100010; + TCCR1B = 0b00011001; + ICR1H = 3; // highByte(799) + ICR1L = 31; // lowByte(799) + _TMR1_HF_PWM = true; + break; + case 10: // 1B + TCCR1A = 0b10100010; + TCCR1B = 0b00011001; + ICR1H = 3; // highByte(799) + ICR1L = 31; // lowByte(799) + _TMR1_HF_PWM = true; + break; + } + sei(); +} + +// 0 - 8 бит, 1 - 10 бит +void setPWM_9_10_resolution(boolean resolution) { + if (resolution) _TMR1_HR_PWM = true; + else _TMR1_HR_PWM = false; +} + +void setPwmFreqnuency(byte pin, byte freq) { //default, 8KHZ, 31KHZ + cli(); + switch (pin) { + case 5: + case 6: //Timer0 + switch (freq) { + case 0: + TCCR0B = 0b00000011; // x64 + TCCR0A = 0b00000011; // fast pwm + break; + case 1: + TCCR0B = 0b00000010; // x8 + TCCR0A = 0b00000011; // fast pwm + break; + case 2: + TCCR0B = 0b00000001; // x1 + TCCR0A = 0b00000001; // phase correct + break; + } + break; + + case 9: + case 10: //Timer1 + _TMR1_HR_PWM = false; + switch (freq) { + case 0: + TCCR1A = 0b00000001; // 8bit + TCCR1B = 0b00000011; // x64 phase correct + break; + case 1: + TCCR1A = 0b00000001; // 8bit + TCCR1B = 0b00001010; // x8 fast pwm + break; + case 2: + TCCR1A = 0b00000001; // 8bit + TCCR1B = 0b00000001; // x1 phase correct + break; + } + break; + case 3: + case 11: //Timer2 + switch (freq) { + case 0: + TCCR2B = 0b00000100; // x64 + TCCR2A = 0b00000001; // phase correct + break; + case 1: + // Пины D3 и D11 - 8 кГц + TCCR2B = 0b00000010; // x8 + TCCR2A = 0b00000011; // fast pwm + break; + case 2: + TCCR2B = 0b00000001; // x1 + TCCR2A = 0b00000001; // phase correct + break; + } + break; + } + sei(); +} + +void setPWM_default(byte pin) { + cli(); + switch (pin) { + case 3: //Timer2_B // не хочешь /64 можешь сделать /1 + TCCR2A = 0b10100001; //default pwm 8 bit phaseCorrect + TCCR2B = 0b00000100; // prescaler /64 // крайние левые 3 бита поменять на 001 для делителя 1 + _TMR2_HF_PWM = false; + break; + case 5: //Timer0_B + TCCR0A = 0b10100011; //default pwm 8 bit FastPWM + TCCR0B = 0b00000011; // prescaler /64 + _TMR0_HF_PWM = false; + break; + case 6: //Timer0_A + TCCR0A = 0b10100011; //default pwm 8 bit FastPWM + TCCR0B = 0b00000011; // prescaler /64 + _TMR0_HF_PWM = false; + break; + case 9: //Timer1_A + TCCR1A = 0b10100001; // default pwm 8 bit phaseCorrect + TCCR1B = 0b00000011; // prescaler /64 // крайние левые 3 бита в 001 для делителя 1 + _TMR1_HF_PWM = false; + break; + case 10: //Timer1_B + TCCR1A = 0b10100001; // default pwm 8 bit phaseCorrect + TCCR1B = 0b00000011; // prescaler /64 + _TMR1_HF_PWM = false; + break; + case 11: //Timer2_A + TCCR2A = 0b10100011; //default pwm 8 bit FastPWM + TCCR2B = 0b00000011; // prescaler /64 + _TMR2_HF_PWM = false; + break; + } + sei(); +} + diff --git a/GyverCore/cores/arduino/time&init.cpp b/GyverCore/cores/arduino/time&init.cpp new file mode 100644 index 0000000..7fcc3cb --- /dev/null +++ b/GyverCore/cores/arduino/time&init.cpp @@ -0,0 +1,132 @@ +#include "Arduino.h" +#include "timeControl.h" + +#define MICROSECONDS_PER_TIMER0_OVERFLOW (clockCyclesToMicroseconds(64 * 256)) // 1024 +#define MILLIS_INC (MICROSECONDS_PER_TIMER0_OVERFLOW / 1000) // 1 +#define FRACT_INC ((MICROSECONDS_PER_TIMER0_OVERFLOW % 1000) >> 3) // 3 +#define FRACT_MAX (1000 >> 3) // 125 + +volatile unsigned long timer0_overflow_count = 0; +volatile unsigned long timer0_millis = 0; +static unsigned char timer0_fract = 0; + +#ifdef MILLIS_TMRS +ISR(TIMER0_OVF_vect) +{ + timer0_millis++; + timer0_fract += 3; + if (timer0_fract >= 128) { + timer0_fract -= 125; + timer0_millis++; + } + timer0_overflow_count++; +} +#endif + +unsigned long millis() { + cli(); + unsigned long m = timer0_millis; + sei(); + return m; +} + +unsigned long micros() { + cli(); + unsigned long m = timer0_overflow_count; + uint8_t t = TCNT0; + if ((TIFR0 & _BV(TOV0)) && (t < 255)) + m++; + sei(); + return (long)(((m << 8) + t) * 4); +} + +/* +void delayMicroseconds(unsigned int us) +{ + us *= 4; //1us = 4 цикла + __asm__ volatile + ( + "1: sbiw %0,1" "\n\t" //; вычесть из регистра значение N + "brne 1b" + : "=w" (us) + : "0" (us) + ); +} + +void delay(unsigned long ms) +{ + while(ms) + { + delayMicroseconds(999); + ms--; + } +} +*/ + +/* +#include +void delay(unsigned long ms) +{ + _delay_ms(ms); +} + +void delayMicroseconds(unsigned int us) +{ + _delay_us(us); +} +*/ + + +void delay(unsigned long ms) +{ + uint32_t start = micros(); + + while (ms > 0) { + yield(); + while ( ms > 0 && (micros() - start) >= 1000) { + ms--; + start += 1000; + } + } +} + + +void delayMicroseconds(unsigned int us) +{ + +#if F_CPU >= 16000000L + if (us <= 1) return; // = 3 cycles, (4 when true) + us <<= 2; // x4 us, = 4 cycles + us -= 5; +#endif + + // busy wait + __asm__ __volatile__ ( + "1: sbiw %0,1" "\n\t" // 2 cycles + "brne 1b" : "=w" (us) : "0" (us) // 2 cycles + ); + // return = 4 cycles +} + + +void init() +{ +cli(); +/* timer 0 */ +TCCR0A = 0b00000011; // fast pwm 8 bit +TCCR0B = 0b00000011; // prescaler 64 +TIMSK0 |= (1<> /2 010 >> /4 011 >> /8 100 >> /16 101 >> /32 110 >> /64 111 >> /128*/ +/* UART */ +UCSR0B = 0; +sei(); +} diff --git a/GyverCore/cores/arduino/uart.cpp b/GyverCore/cores/arduino/uart.cpp new file mode 100644 index 0000000..a241785 --- /dev/null +++ b/GyverCore/cores/arduino/uart.cpp @@ -0,0 +1,286 @@ +#include "uart.h" + +// ===== INIT ===== +void uartBegin(uint32_t baudrate){ + uint16_t speed = (2000000/baudrate)-1; + UBRR0H = highByte(speed); + UBRR0L = lowByte(speed); + UCSR0A = (1 << U2X0); + UCSR0B = ((1<= 0; i--) { + uartWrite(bytes[i] + '0'); + } +} + +void printBytes(uint32_t data, byte decimals) { + int8_t bytes[10]; + byte amount; + for (byte i = 0; i < 10; i++) { + bytes[i] = data % 10; + data /= 10; + if (data == 0) { + amount = i; + break; + } + } + for (int8_t i = amount; i >= amount - decimals + 1; i--) { + uartWrite(bytes[i] + '0'); + } +} + +void uartPrint(double data, byte decimals) { + if (data < 0) { + uartWrite(45); + data = -data; + } + uint32_t integer = data; + uint32_t fract = ((float)data - integer) * 1000000000; + printBytes(integer); + uartWrite(46); + printBytes(fract, decimals); +} + +void uartPrint(double data) { + uartPrint(data, 2); +} + +void uartPrintln(double data, byte decimals) { + uartPrint(data, decimals); + uartPrintln(); +} + +void uartPrintln(double data) { + uartPrint(data, 2); + uartPrintln(); +} + +void uartPrint(String data) { + byte stringSize = data.length(); + for (byte i = 0; i < stringSize; i++) { + uartWrite(data[i]); + } +} +void uartPrintln(String data) { + uartPrint(data); + uartPrintln(); +} + +void uartPrint(char data[]) { + byte i = 0; + while (data[i] != '\0') { + uartWrite(data[i]); + i++; + } +} +void uartPrintln(char data[]) { + uartPrint(data); + uartPrintln(); +} \ No newline at end of file diff --git a/GyverCore/cores/arduino/uart.h b/GyverCore/cores/arduino/uart.h new file mode 100644 index 0000000..3e3b442 --- /dev/null +++ b/GyverCore/cores/arduino/uart.h @@ -0,0 +1,52 @@ +#ifndef uart_h +#define uart_h + +#include "Arduino.h" +#include + +void uartBegin(void); +void uartBegin(uint32_t baudrate); +void uartEnd(); + +boolean uartAvailable(); +char uartRead(); +char uartPeek(); +void uartClear(); + +void uartSetTimeout(int timeout); +int32_t uartParseInt(); +float uartParseFloat(); +String uartReadString(); +boolean uartParsePacket(int *intArray); + +void uartWrite(byte data); +void uartPrintln(void); + +void uartPrint(int8_t data); +void uartPrint(uint8_t data); +void uartPrint(int16_t data); +void uartPrint(uint16_t data); +void uartPrint(int32_t data); +void uartPrint(uint32_t data); +void uartPrint(double data); +void uartPrint(double data, byte decimals); +void uartPrint(String data); +void uartPrint(char data[]); + +void uartPrintln(int8_t data); +void uartPrintln(uint8_t data); +void uartPrintln(int16_t data); +void uartPrintln(uint16_t data); +void uartPrintln(int32_t data); +void uartPrintln(uint32_t data); +void uartPrintln(double data); +void uartPrintln(double data, byte decimals); +void uartPrintln(String data); +void uartPrintln(char data[]); + +void printHelper(int32_t data); +void printHelper(uint32_t data); +void printBytes(uint32_t data); +void printBytes(uint32_t data, byte amount); + +#endif \ No newline at end of file diff --git a/GyverCore/cores/arduino/wiring.c b/GyverCore/cores/arduino/wiring.c deleted file mode 100644 index 9727135..0000000 --- a/GyverCore/cores/arduino/wiring.c +++ /dev/null @@ -1,392 +0,0 @@ -/* - wiring.c - Partial implementation of the Wiring API for the ATmega8. - Part of Arduino - http://www.arduino.cc/ - - Copyright (c) 2005-2006 David A. Mellis - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library 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 - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General - Public License along with this library; if not, write to the - Free Software Foundation, Inc., 59 Temple Place, Suite 330, - Boston, MA 02111-1307 USA -*/ - -#include "wiring_private.h" - -// the prescaler is set so that timer0 ticks every 64 clock cycles, and the -// the overflow handler is called every 256 ticks. -#define MICROSECONDS_PER_TIMER0_OVERFLOW (clockCyclesToMicroseconds(64 * 256)) - -// the whole number of milliseconds per timer0 overflow -#define MILLIS_INC (MICROSECONDS_PER_TIMER0_OVERFLOW / 1000) - -// the fractional number of milliseconds per timer0 overflow. we shift right -// by three to fit these numbers into a byte. (for the clock speeds we care -// about - 8 and 16 MHz - this doesn't lose precision.) -#define FRACT_INC ((MICROSECONDS_PER_TIMER0_OVERFLOW % 1000) >> 3) -#define FRACT_MAX (1000 >> 3) - -volatile unsigned long timer0_overflow_count = 0; -volatile unsigned long timer0_millis = 0; -static unsigned char timer0_fract = 0; - -#if defined(TIM0_OVF_vect) -ISR(TIM0_OVF_vect) -#else -ISR(TIMER0_OVF_vect) -#endif -{ - // copy these to local variables so they can be stored in registers - // (volatile variables must be read from memory on every access) - unsigned long m = timer0_millis; - unsigned char f = timer0_fract; - - m += MILLIS_INC; - f += FRACT_INC; - if (f >= FRACT_MAX) { - f -= FRACT_MAX; - m += 1; - } - - timer0_fract = f; - timer0_millis = m; - timer0_overflow_count++; -} - -unsigned long millis() -{ - unsigned long m; - uint8_t oldSREG = SREG; - - // disable interrupts while we read timer0_millis or we might get an - // inconsistent value (e.g. in the middle of a write to timer0_millis) - cli(); - m = timer0_millis; - SREG = oldSREG; - - return m; -} - -unsigned long micros() { - unsigned long m; - uint8_t oldSREG = SREG, t; - - cli(); - m = timer0_overflow_count; -#if defined(TCNT0) - t = TCNT0; -#elif defined(TCNT0L) - t = TCNT0L; -#else - #error TIMER 0 not defined -#endif - -#ifdef TIFR0 - if ((TIFR0 & _BV(TOV0)) && (t < 255)) - m++; -#else - if ((TIFR & _BV(TOV0)) && (t < 255)) - m++; -#endif - - SREG = oldSREG; - - return ((m << 8) + t) * (64 / clockCyclesPerMicrosecond()); -} - -void delay(unsigned long ms) -{ - uint32_t start = micros(); - - while (ms > 0) { - yield(); - while ( ms > 0 && (micros() - start) >= 1000) { - ms--; - start += 1000; - } - } -} - -/* Delay for the given number of microseconds. Assumes a 1, 8, 12, 16, 20 or 24 MHz clock. */ -void delayMicroseconds(unsigned int us) -{ - // call = 4 cycles + 2 to 4 cycles to init us(2 for constant delay, 4 for variable) - - // calling avrlib's delay_us() function with low values (e.g. 1 or - // 2 microseconds) gives delays longer than desired. - //delay_us(us); -#if F_CPU >= 24000000L - // for the 24 MHz clock for the aventurous ones, trying to overclock - - // zero delay fix - if (!us) return; // = 3 cycles, (4 when true) - - // the following loop takes a 1/6 of a microsecond (4 cycles) - // per iteration, so execute it six times for each microsecond of - // delay requested. - us *= 6; // x6 us, = 7 cycles - - // account for the time taken in the preceeding commands. - // we just burned 22 (24) cycles above, remove 5, (5*4=20) - // us is at least 6 so we can substract 5 - us -= 5; //=2 cycles - -#elif F_CPU >= 20000000L - // for the 20 MHz clock on rare Arduino boards - - // for a one-microsecond delay, simply return. the overhead - // of the function call takes 18 (20) cycles, which is 1us - __asm__ __volatile__ ( - "nop" "\n\t" - "nop" "\n\t" - "nop" "\n\t" - "nop"); //just waiting 4 cycles - if (us <= 1) return; // = 3 cycles, (4 when true) - - // the following loop takes a 1/5 of a microsecond (4 cycles) - // per iteration, so execute it five times for each microsecond of - // delay requested. - us = (us << 2) + us; // x5 us, = 7 cycles - - // account for the time taken in the preceeding commands. - // we just burned 26 (28) cycles above, remove 7, (7*4=28) - // us is at least 10 so we can substract 7 - us -= 7; // 2 cycles - -#elif F_CPU >= 16000000L - // for the 16 MHz clock on most Arduino boards - - // for a one-microsecond delay, simply return. the overhead - // of the function call takes 14 (16) cycles, which is 1us - if (us <= 1) return; // = 3 cycles, (4 when true) - - // the following loop takes 1/4 of a microsecond (4 cycles) - // per iteration, so execute it four times for each microsecond of - // delay requested. - us <<= 2; // x4 us, = 4 cycles - - // account for the time taken in the preceeding commands. - // we just burned 19 (21) cycles above, remove 5, (5*4=20) - // us is at least 8 so we can substract 5 - us -= 5; // = 2 cycles, - -#elif F_CPU >= 12000000L - // for the 12 MHz clock if somebody is working with USB - - // for a 1 microsecond delay, simply return. the overhead - // of the function call takes 14 (16) cycles, which is 1.5us - if (us <= 1) return; // = 3 cycles, (4 when true) - - // the following loop takes 1/3 of a microsecond (4 cycles) - // per iteration, so execute it three times for each microsecond of - // delay requested. - us = (us << 1) + us; // x3 us, = 5 cycles - - // account for the time taken in the preceeding commands. - // we just burned 20 (22) cycles above, remove 5, (5*4=20) - // us is at least 6 so we can substract 5 - us -= 5; //2 cycles - -#elif F_CPU >= 8000000L - // for the 8 MHz internal clock - - // for a 1 and 2 microsecond delay, simply return. the overhead - // of the function call takes 14 (16) cycles, which is 2us - if (us <= 2) return; // = 3 cycles, (4 when true) - - // the following loop takes 1/2 of a microsecond (4 cycles) - // per iteration, so execute it twice for each microsecond of - // delay requested. - us <<= 1; //x2 us, = 2 cycles - - // account for the time taken in the preceeding commands. - // we just burned 17 (19) cycles above, remove 4, (4*4=16) - // us is at least 6 so we can substract 4 - us -= 4; // = 2 cycles - -#else - // for the 1 MHz internal clock (default settings for common Atmega microcontrollers) - - // the overhead of the function calls is 14 (16) cycles - if (us <= 16) return; //= 3 cycles, (4 when true) - if (us <= 25) return; //= 3 cycles, (4 when true), (must be at least 25 if we want to substract 22) - - // compensate for the time taken by the preceeding and next commands (about 22 cycles) - us -= 22; // = 2 cycles - // the following loop takes 4 microseconds (4 cycles) - // per iteration, so execute it us/4 times - // us is at least 4, divided by 4 gives us 1 (no zero delay bug) - us >>= 2; // us div 4, = 4 cycles - - -#endif - - // busy wait - __asm__ __volatile__ ( - "1: sbiw %0,1" "\n\t" // 2 cycles - "brne 1b" : "=w" (us) : "0" (us) // 2 cycles - ); - // return = 4 cycles -} - -void init() -{ - // this needs to be called before setup() or some functions won't - // work there - sei(); - - // on the ATmega168, timer 0 is also used for fast hardware pwm - // (using phase-correct PWM would mean that timer 0 overflowed half as often - // resulting in different millis() behavior on the ATmega8 and ATmega168) -#if defined(TCCR0A) && defined(WGM01) - sbi(TCCR0A, WGM01); - sbi(TCCR0A, WGM00); -#endif - - // set timer 0 prescale factor to 64 -#if defined(__AVR_ATmega128__) - // CPU specific: different values for the ATmega128 - sbi(TCCR0, CS02); -#elif defined(TCCR0) && defined(CS01) && defined(CS00) - // this combination is for the standard atmega8 - sbi(TCCR0, CS01); - sbi(TCCR0, CS00); -#elif defined(TCCR0B) && defined(CS01) && defined(CS00) - // this combination is for the standard 168/328/1280/2560 - sbi(TCCR0B, CS01); - sbi(TCCR0B, CS00); -#elif defined(TCCR0A) && defined(CS01) && defined(CS00) - // this combination is for the __AVR_ATmega645__ series - sbi(TCCR0A, CS01); - sbi(TCCR0A, CS00); -#else - #error Timer 0 prescale factor 64 not set correctly -#endif - - // enable timer 0 overflow interrupt -#if defined(TIMSK) && defined(TOIE0) - sbi(TIMSK, TOIE0); -#elif defined(TIMSK0) && defined(TOIE0) - sbi(TIMSK0, TOIE0); -#else - #error Timer 0 overflow interrupt not set correctly -#endif - - // timers 1 and 2 are used for phase-correct hardware pwm - // this is better for motors as it ensures an even waveform - // note, however, that fast pwm mode can achieve a frequency of up - // 8 MHz (with a 16 MHz clock) at 50% duty cycle - -#if defined(TCCR1B) && defined(CS11) && defined(CS10) - TCCR1B = 0; - - // set timer 1 prescale factor to 64 - sbi(TCCR1B, CS11); -#if F_CPU >= 8000000L - sbi(TCCR1B, CS10); -#endif -#elif defined(TCCR1) && defined(CS11) && defined(CS10) - sbi(TCCR1, CS11); -#if F_CPU >= 8000000L - sbi(TCCR1, CS10); -#endif -#endif - // put timer 1 in 8-bit phase correct pwm mode -#if defined(TCCR1A) && defined(WGM10) - sbi(TCCR1A, WGM10); -#endif - - // set timer 2 prescale factor to 64 -#if defined(TCCR2) && defined(CS22) - sbi(TCCR2, CS22); -#elif defined(TCCR2B) && defined(CS22) - sbi(TCCR2B, CS22); -//#else - // Timer 2 not finished (may not be present on this CPU) -#endif - - // configure timer 2 for phase correct pwm (8-bit) -#if defined(TCCR2) && defined(WGM20) - sbi(TCCR2, WGM20); -#elif defined(TCCR2A) && defined(WGM20) - sbi(TCCR2A, WGM20); -//#else - // Timer 2 not finished (may not be present on this CPU) -#endif - -#if defined(TCCR3B) && defined(CS31) && defined(WGM30) - sbi(TCCR3B, CS31); // set timer 3 prescale factor to 64 - sbi(TCCR3B, CS30); - sbi(TCCR3A, WGM30); // put timer 3 in 8-bit phase correct pwm mode -#endif - -#if defined(TCCR4A) && defined(TCCR4B) && defined(TCCR4D) /* beginning of timer4 block for 32U4 and similar */ - sbi(TCCR4B, CS42); // set timer4 prescale factor to 64 - sbi(TCCR4B, CS41); - sbi(TCCR4B, CS40); - sbi(TCCR4D, WGM40); // put timer 4 in phase- and frequency-correct PWM mode - sbi(TCCR4A, PWM4A); // enable PWM mode for comparator OCR4A - sbi(TCCR4C, PWM4D); // enable PWM mode for comparator OCR4D -#else /* beginning of timer4 block for ATMEGA1280 and ATMEGA2560 */ -#if defined(TCCR4B) && defined(CS41) && defined(WGM40) - sbi(TCCR4B, CS41); // set timer 4 prescale factor to 64 - sbi(TCCR4B, CS40); - sbi(TCCR4A, WGM40); // put timer 4 in 8-bit phase correct pwm mode -#endif -#endif /* end timer4 block for ATMEGA1280/2560 and similar */ - -#if defined(TCCR5B) && defined(CS51) && defined(WGM50) - sbi(TCCR5B, CS51); // set timer 5 prescale factor to 64 - sbi(TCCR5B, CS50); - sbi(TCCR5A, WGM50); // put timer 5 in 8-bit phase correct pwm mode -#endif - -#if defined(ADCSRA) - // set a2d prescaler so we are inside the desired 50-200 KHz range. - #if F_CPU >= 16000000 // 16 MHz / 128 = 125 KHz - sbi(ADCSRA, ADPS2); - sbi(ADCSRA, ADPS1); - sbi(ADCSRA, ADPS0); - #elif F_CPU >= 8000000 // 8 MHz / 64 = 125 KHz - sbi(ADCSRA, ADPS2); - sbi(ADCSRA, ADPS1); - cbi(ADCSRA, ADPS0); - #elif F_CPU >= 4000000 // 4 MHz / 32 = 125 KHz - sbi(ADCSRA, ADPS2); - cbi(ADCSRA, ADPS1); - sbi(ADCSRA, ADPS0); - #elif F_CPU >= 2000000 // 2 MHz / 16 = 125 KHz - sbi(ADCSRA, ADPS2); - cbi(ADCSRA, ADPS1); - cbi(ADCSRA, ADPS0); - #elif F_CPU >= 1000000 // 1 MHz / 8 = 125 KHz - cbi(ADCSRA, ADPS2); - sbi(ADCSRA, ADPS1); - sbi(ADCSRA, ADPS0); - #else // 128 kHz / 2 = 64 KHz -> This is the closest you can get, the prescaler is 2 - cbi(ADCSRA, ADPS2); - cbi(ADCSRA, ADPS1); - sbi(ADCSRA, ADPS0); - #endif - // enable a2d conversions - sbi(ADCSRA, ADEN); -#endif - - // the bootloader connects pins 0 and 1 to the USART; disconnect them - // here so they can be used as normal digital i/o; they will be - // reconnected in Serial.begin() -#if defined(UCSRB) - UCSRB = 0; -#elif defined(UCSR0B) - UCSR0B = 0; -#endif -} diff --git a/GyverCore/cores/arduino/wiring_analog.c b/GyverCore/cores/arduino/wiring_analog.c deleted file mode 100644 index 967c2b9..0000000 --- a/GyverCore/cores/arduino/wiring_analog.c +++ /dev/null @@ -1,294 +0,0 @@ -/* - wiring_analog.c - analog input and output - Part of Arduino - http://www.arduino.cc/ - - Copyright (c) 2005-2006 David A. Mellis - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library 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 - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General - Public License along with this library; if not, write to the - Free Software Foundation, Inc., 59 Temple Place, Suite 330, - Boston, MA 02111-1307 USA - - Modified 28 September 2010 by Mark Sproul -*/ - -#include "wiring_private.h" -#include "pins_arduino.h" - -uint8_t analog_reference = DEFAULT; - -void analogReference(uint8_t mode) -{ - // can't actually set the register here because the default setting - // will connect AVCC and the AREF pin, which would cause a short if - // there's something connected to AREF. - analog_reference = mode; -} - -int analogRead(uint8_t pin) -{ - uint8_t low, high; - -#if defined(analogPinToChannel) -#if defined(__AVR_ATmega32U4__) - if (pin >= 18) pin -= 18; // allow for channel or pin numbers -#endif - pin = analogPinToChannel(pin); -#elif defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) - if (pin >= 54) pin -= 54; // allow for channel or pin numbers -#elif defined(__AVR_ATmega32U4__) - if (pin >= 18) pin -= 18; // allow for channel or pin numbers -#elif defined(__AVR_ATmega1284__) || defined(__AVR_ATmega1284P__) || defined(__AVR_ATmega644__) || defined(__AVR_ATmega644A__) || defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644PA__) - if (pin >= 24) pin -= 24; // allow for channel or pin numbers -#else - if (pin >= 14) pin -= 14; // allow for channel or pin numbers -#endif - -#if defined(ADCSRB) && defined(MUX5) - // the MUX5 bit of ADCSRB selects whether we're reading from channels - // 0 to 7 (MUX5 low) or 8 to 15 (MUX5 high). - ADCSRB = (ADCSRB & ~(1 << MUX5)) | (((pin >> 3) & 0x01) << MUX5); -#endif - - // set the analog reference (high two bits of ADMUX) and select the - // channel (low 4 bits). this also sets ADLAR (left-adjust result) - // to 0 (the default). -#if defined(ADMUX) -#if defined(__AVR_ATtiny25__) || defined(__AVR_ATtiny45__) || defined(__AVR_ATtiny85__) - ADMUX = (analog_reference << 4) | (pin & 0x07); -#else - ADMUX = (analog_reference << 6) | (pin & 0x07); -#endif -#endif - - // without a delay, we seem to read from the wrong channel - //delay(1); - -#if defined(ADCSRA) && defined(ADCL) - // start the conversion - sbi(ADCSRA, ADSC); - - // ADSC is cleared when the conversion finishes - while (bit_is_set(ADCSRA, ADSC)); - - // we have to read ADCL first; doing so locks both ADCL - // and ADCH until ADCH is read. reading ADCL second would - // cause the results of each conversion to be discarded, - // as ADCL and ADCH would be locked when it completed. - low = ADCL; - high = ADCH; -#else - // we dont have an ADC, return 0 - low = 0; - high = 0; -#endif - - // combine the two bytes - return (high << 8) | low; -} - -// Right now, PWM output only works on the pins with -// hardware support. These are defined in the appropriate -// pins_*.c file. For the rest of the pins, we default -// to digital output. -void analogWrite(uint8_t pin, int val) -{ - // We need to make sure the PWM output is enabled for those pins - // that support it, as we turn it off when digitally reading or - // writing with them. Also, make sure the pin is in output mode - // for consistenty with Wiring, which doesn't require a pinMode - // call for the analog output pins. - pinMode(pin, OUTPUT); - if (val == 0) - { - digitalWrite(pin, LOW); - } - else if (val == 255) - { - digitalWrite(pin, HIGH); - } - else - { - switch(digitalPinToTimer(pin)) - { - // XXX fix needed for atmega8 - #if defined(TCCR0) && defined(COM00) && !defined(__AVR_ATmega8__) - case TIMER0A: - // connect pwm to pin on timer 0 - sbi(TCCR0, COM00); - OCR0 = val; // set pwm duty - break; - #endif - - #if defined(TCCR0A) && defined(COM0A1) - case TIMER0A: - // connect pwm to pin on timer 0, channel A - sbi(TCCR0A, COM0A1); - OCR0A = val; // set pwm duty - break; - #endif - - #if defined(TCCR0A) && defined(COM0B1) - case TIMER0B: - // connect pwm to pin on timer 0, channel B - sbi(TCCR0A, COM0B1); - OCR0B = val; // set pwm duty - break; - #endif - - #if defined(TCCR1A) && defined(COM1A1) - case TIMER1A: - // connect pwm to pin on timer 1, channel A - sbi(TCCR1A, COM1A1); - OCR1A = val; // set pwm duty - break; - #endif - - #if defined(TCCR1A) && defined(COM1B1) - case TIMER1B: - // connect pwm to pin on timer 1, channel B - sbi(TCCR1A, COM1B1); - OCR1B = val; // set pwm duty - break; - #endif - - #if defined(TCCR1A) && defined(COM1C1) - case TIMER1C: - // connect pwm to pin on timer 1, channel B - sbi(TCCR1A, COM1C1); - OCR1C = val; // set pwm duty - break; - #endif - - #if defined(TCCR2) && defined(COM21) - case TIMER2: - // connect pwm to pin on timer 2 - sbi(TCCR2, COM21); - OCR2 = val; // set pwm duty - break; - #endif - - #if defined(TCCR2A) && defined(COM2A1) - case TIMER2A: - // connect pwm to pin on timer 2, channel A - sbi(TCCR2A, COM2A1); - OCR2A = val; // set pwm duty - break; - #endif - - #if defined(TCCR2A) && defined(COM2B1) - case TIMER2B: - // connect pwm to pin on timer 2, channel B - sbi(TCCR2A, COM2B1); - OCR2B = val; // set pwm duty - break; - #endif - - #if defined(TCCR3A) && defined(COM3A1) - case TIMER3A: - // connect pwm to pin on timer 3, channel A - sbi(TCCR3A, COM3A1); - OCR3A = val; // set pwm duty - break; - #endif - - #if defined(TCCR3A) && defined(COM3B1) - case TIMER3B: - // connect pwm to pin on timer 3, channel B - sbi(TCCR3A, COM3B1); - OCR3B = val; // set pwm duty - break; - #endif - - #if defined(TCCR3A) && defined(COM3C1) - case TIMER3C: - // connect pwm to pin on timer 3, channel C - sbi(TCCR3A, COM3C1); - OCR3C = val; // set pwm duty - break; - #endif - - #if defined(TCCR4A) - case TIMER4A: - //connect pwm to pin on timer 4, channel A - sbi(TCCR4A, COM4A1); - #if defined(COM4A0) // only used on 32U4 - cbi(TCCR4A, COM4A0); - #endif - OCR4A = val; // set pwm duty - break; - #endif - - #if defined(TCCR4A) && defined(COM4B1) - case TIMER4B: - // connect pwm to pin on timer 4, channel B - sbi(TCCR4A, COM4B1); - OCR4B = val; // set pwm duty - break; - #endif - - #if defined(TCCR4A) && defined(COM4C1) - case TIMER4C: - // connect pwm to pin on timer 4, channel C - sbi(TCCR4A, COM4C1); - OCR4C = val; // set pwm duty - break; - #endif - - #if defined(TCCR4C) && defined(COM4D1) - case TIMER4D: - // connect pwm to pin on timer 4, channel D - sbi(TCCR4C, COM4D1); - #if defined(COM4D0) // only used on 32U4 - cbi(TCCR4C, COM4D0); - #endif - OCR4D = val; // set pwm duty - break; - #endif - - - #if defined(TCCR5A) && defined(COM5A1) - case TIMER5A: - // connect pwm to pin on timer 5, channel A - sbi(TCCR5A, COM5A1); - OCR5A = val; // set pwm duty - break; - #endif - - #if defined(TCCR5A) && defined(COM5B1) - case TIMER5B: - // connect pwm to pin on timer 5, channel B - sbi(TCCR5A, COM5B1); - OCR5B = val; // set pwm duty - break; - #endif - - #if defined(TCCR5A) && defined(COM5C1) - case TIMER5C: - // connect pwm to pin on timer 5, channel C - sbi(TCCR5A, COM5C1); - OCR5C = val; // set pwm duty - break; - #endif - - case NOT_ON_TIMER: - default: - if (val < 128) { - digitalWrite(pin, LOW); - } else { - digitalWrite(pin, HIGH); - } - } - } -} - diff --git a/GyverCore/cores/arduino/wiring_digital.c b/GyverCore/cores/arduino/wiring_digital.c deleted file mode 100644 index 27a62fc..0000000 --- a/GyverCore/cores/arduino/wiring_digital.c +++ /dev/null @@ -1,179 +0,0 @@ -/* - wiring_digital.c - digital input and output functions - Part of Arduino - http://www.arduino.cc/ - - Copyright (c) 2005-2006 David A. Mellis - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library 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 - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General - Public License along with this library; if not, write to the - Free Software Foundation, Inc., 59 Temple Place, Suite 330, - Boston, MA 02111-1307 USA - - Modified 28 September 2010 by Mark Sproul -*/ - -#define ARDUINO_MAIN -#include "wiring_private.h" -#include "pins_arduino.h" - -void pinMode(uint8_t pin, uint8_t mode) -{ - uint8_t bit = digitalPinToBitMask(pin); - uint8_t port = digitalPinToPort(pin); - volatile uint8_t *reg, *out; - - if (port == NOT_A_PIN) return; - - // JWS: can I let the optimizer do this? - reg = portModeRegister(port); - out = portOutputRegister(port); - - if (mode == INPUT) { - uint8_t oldSREG = SREG; - cli(); - *reg &= ~bit; - *out &= ~bit; - SREG = oldSREG; - } else if (mode == INPUT_PULLUP) { - uint8_t oldSREG = SREG; - cli(); - *reg &= ~bit; - *out |= bit; - SREG = oldSREG; - } else { - uint8_t oldSREG = SREG; - cli(); - *reg |= bit; - SREG = oldSREG; - } -} - -// Forcing this inline keeps the callers from having to push their own stuff -// on the stack. It is a good performance win and only takes 1 more byte per -// user than calling. (It will take more bytes on the 168.) -// -// But shouldn't this be moved into pinMode? Seems silly to check and do on -// each digitalread or write. -// -// Mark Sproul: -// - Removed inline. Save 170 bytes on atmega1280 -// - changed to a switch statment; added 32 bytes but much easier to read and maintain. -// - Added more #ifdefs, now compiles for atmega645 -// -//static inline void turnOffPWM(uint8_t timer) __attribute__ ((always_inline)); -//static inline void turnOffPWM(uint8_t timer) -static void turnOffPWM(uint8_t timer) -{ - switch (timer) - { - #if defined(TCCR1A) && defined(COM1A1) - case TIMER1A: cbi(TCCR1A, COM1A1); break; - #endif - #if defined(TCCR1A) && defined(COM1B1) - case TIMER1B: cbi(TCCR1A, COM1B1); break; - #endif - #if defined(TCCR1A) && defined(COM1C1) - case TIMER1C: cbi(TCCR1A, COM1C1); break; - #endif - - #if defined(TCCR2) && defined(COM21) - case TIMER2: cbi(TCCR2, COM21); break; - #endif - - #if defined(TCCR0A) && defined(COM0A1) - case TIMER0A: cbi(TCCR0A, COM0A1); break; - #endif - - #if defined(TCCR0A) && defined(COM0B1) - case TIMER0B: cbi(TCCR0A, COM0B1); break; - #endif - #if defined(TCCR2A) && defined(COM2A1) - case TIMER2A: cbi(TCCR2A, COM2A1); break; - #endif - #if defined(TCCR2A) && defined(COM2B1) - case TIMER2B: cbi(TCCR2A, COM2B1); break; - #endif - - #if defined(TCCR3A) && defined(COM3A1) - case TIMER3A: cbi(TCCR3A, COM3A1); break; - #endif - #if defined(TCCR3A) && defined(COM3B1) - case TIMER3B: cbi(TCCR3A, COM3B1); break; - #endif - #if defined(TCCR3A) && defined(COM3C1) - case TIMER3C: cbi(TCCR3A, COM3C1); break; - #endif - - #if defined(TCCR4A) && defined(COM4A1) - case TIMER4A: cbi(TCCR4A, COM4A1); break; - #endif - #if defined(TCCR4A) && defined(COM4B1) - case TIMER4B: cbi(TCCR4A, COM4B1); break; - #endif - #if defined(TCCR4A) && defined(COM4C1) - case TIMER4C: cbi(TCCR4A, COM4C1); break; - #endif - #if defined(TCCR4C) && defined(COM4D1) - case TIMER4D: cbi(TCCR4C, COM4D1); break; - #endif - - #if defined(TCCR5A) - case TIMER5A: cbi(TCCR5A, COM5A1); break; - case TIMER5B: cbi(TCCR5A, COM5B1); break; - case TIMER5C: cbi(TCCR5A, COM5C1); break; - #endif - } -} - -void digitalWrite(uint8_t pin, uint8_t val) -{ - uint8_t timer = digitalPinToTimer(pin); - uint8_t bit = digitalPinToBitMask(pin); - uint8_t port = digitalPinToPort(pin); - volatile uint8_t *out; - - if (port == NOT_A_PIN) return; - - // If the pin that support PWM output, we need to turn it off - // before doing a digital write. - if (timer != NOT_ON_TIMER) turnOffPWM(timer); - - out = portOutputRegister(port); - - uint8_t oldSREG = SREG; - cli(); - - if (val == LOW) { - *out &= ~bit; - } else { - *out |= bit; - } - - SREG = oldSREG; -} - -int digitalRead(uint8_t pin) -{ - uint8_t timer = digitalPinToTimer(pin); - uint8_t bit = digitalPinToBitMask(pin); - uint8_t port = digitalPinToPort(pin); - - if (port == NOT_A_PIN) return LOW; - - // If the pin that support PWM output, we need to turn it off - // before getting a digital reading. - if (timer != NOT_ON_TIMER) turnOffPWM(timer); - - if (*portInputRegister(port) & bit) return HIGH; - return LOW; -} diff --git a/GyverCore/cores/arduino/wiring_private.h b/GyverCore/cores/arduino/wiring_private.h deleted file mode 100644 index a277b14..0000000 --- a/GyverCore/cores/arduino/wiring_private.h +++ /dev/null @@ -1,72 +0,0 @@ -/* - wiring_private.h - Internal header file. - Part of Arduino - http://www.arduino.cc/ - - Copyright (c) 2005-2006 David A. Mellis - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library 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 - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General - Public License along with this library; if not, write to the - Free Software Foundation, Inc., 59 Temple Place, Suite 330, - Boston, MA 02111-1307 USA -*/ - -#ifndef WiringPrivate_h -#define WiringPrivate_h - -#include -#include -#include -#include - -#include "Arduino.h" - -#ifdef __cplusplus -extern "C"{ -#endif - -#ifndef cbi -#define cbi(sfr, bit) (_SFR_BYTE(sfr) &= ~_BV(bit)) -#endif -#ifndef sbi -#define sbi(sfr, bit) (_SFR_BYTE(sfr) |= _BV(bit)) -#endif - -uint32_t countPulseASM(volatile uint8_t *port, uint8_t bit, uint8_t stateMask, unsigned long maxloops); - -#define EXTERNAL_INT_0 0 -#define EXTERNAL_INT_1 1 -#define EXTERNAL_INT_2 2 -#define EXTERNAL_INT_3 3 -#define EXTERNAL_INT_4 4 -#define EXTERNAL_INT_5 5 -#define EXTERNAL_INT_6 6 -#define EXTERNAL_INT_7 7 - -#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) || defined(__AVR_ATmega128RFA1__) || defined(__AVR_ATmega256RFR2__) || \ - defined(__AVR_AT90USB82__) || defined(__AVR_AT90USB162__) || defined(__AVR_ATmega32U2__) || defined(__AVR_ATmega16U2__) || defined(__AVR_ATmega8U2__) -#define EXTERNAL_NUM_INTERRUPTS 8 -#elif defined(__AVR_ATmega1284__) || defined(__AVR_ATmega1284P__) || defined(__AVR_ATmega644__) || defined(__AVR_ATmega644A__) || defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644PA__) -#define EXTERNAL_NUM_INTERRUPTS 3 -#elif defined(__AVR_ATmega32U4__) -#define EXTERNAL_NUM_INTERRUPTS 5 -#else -#define EXTERNAL_NUM_INTERRUPTS 2 -#endif - -typedef void (*voidFuncPtr)(void); - -#ifdef __cplusplus -} // extern "C" -#endif - -#endif diff --git a/GyverCore/cores/arduino/wiring_pulse.c b/GyverCore/cores/arduino/wiring_pulse.c index d6e0434..9a475bd 100644 --- a/GyverCore/cores/arduino/wiring_pulse.c +++ b/GyverCore/cores/arduino/wiring_pulse.c @@ -20,8 +20,117 @@ Boston, MA 02111-1307 USA */ -#include "wiring_private.h" -#include "pins_arduino.h" +//#include "wiring_private.h" +//#include "pins_arduino.h" +#include "Arduino.h" + +const uint16_t PROGMEM port_to_mode_PGM[] = { + NOT_A_PORT, + NOT_A_PORT, + (uint16_t) &DDRB, + (uint16_t) &DDRC, + (uint16_t) &DDRD, +}; + +const uint16_t PROGMEM port_to_output_PGM[] = { + NOT_A_PORT, + NOT_A_PORT, + (uint16_t) &PORTB, + (uint16_t) &PORTC, + (uint16_t) &PORTD, +}; + +const uint16_t PROGMEM port_to_input_PGM[] = { + NOT_A_PORT, + NOT_A_PORT, + (uint16_t) &PINB, + (uint16_t) &PINC, + (uint16_t) &PIND, +}; + +const uint8_t PROGMEM digital_pin_to_port_PGM[] = { + PD, /* 0 */ + PD, + PD, + PD, + PD, + PD, + PD, + PD, + PB, /* 8 */ + PB, + PB, + PB, + PB, + PB, + PC, /* 14 */ + PC, + PC, + PC, + PC, + PC, +}; + +const uint8_t PROGMEM digital_pin_to_bit_mask_PGM[] = { + _BV(0), /* 0, port D */ + _BV(1), + _BV(2), + _BV(3), + _BV(4), + _BV(5), + _BV(6), + _BV(7), + _BV(0), /* 8, port B */ + _BV(1), + _BV(2), + _BV(3), + _BV(4), + _BV(5), + _BV(0), /* 14, port C */ + _BV(1), + _BV(2), + _BV(3), + _BV(4), + _BV(5), +}; + +const uint8_t PROGMEM digital_pin_to_timer_PGM[] = { + NOT_ON_TIMER, /* 0 - port D */ + NOT_ON_TIMER, + NOT_ON_TIMER, + // on the ATmega168, digital pin 3 has hardware pwm +#if defined(__AVR_ATmega8__) + NOT_ON_TIMER, +#else + TIMER2B, +#endif + NOT_ON_TIMER, + // on the ATmega168, digital pins 5 and 6 have hardware pwm +#if defined(__AVR_ATmega8__) + NOT_ON_TIMER, + NOT_ON_TIMER, +#else + TIMER0B, + TIMER0A, +#endif + NOT_ON_TIMER, + NOT_ON_TIMER, /* 8 - port B */ + TIMER1A, + TIMER1B, +#if defined(__AVR_ATmega8__) + TIMER2, +#else + TIMER2A, +#endif + NOT_ON_TIMER, + NOT_ON_TIMER, + NOT_ON_TIMER, + NOT_ON_TIMER, /* 14 - port C */ + NOT_ON_TIMER, + NOT_ON_TIMER, + NOT_ON_TIMER, + NOT_ON_TIMER, +}; /* Measures the length (in microseconds) of a pulse on the pin; state is HIGH * or LOW, the type of pulse to measure. Works on pulses from 2-3 microseconds diff --git a/GyverCore/cores/arduino/wiring_shift.c b/GyverCore/cores/arduino/wiring_shift.c index 2b6f7a8..d941d5c 100644 --- a/GyverCore/cores/arduino/wiring_shift.c +++ b/GyverCore/cores/arduino/wiring_shift.c @@ -20,7 +20,7 @@ Boston, MA 02111-1307 USA */ -#include "wiring_private.h" +#include "Arduino.h" uint8_t shiftIn(uint8_t dataPin, uint8_t clockPin, uint8_t bitOrder) { uint8_t value = 0; diff --git a/GyverCore/keywords.txt b/GyverCore/keywords.txt new file mode 100644 index 0000000..ab19e07 --- /dev/null +++ b/GyverCore/keywords.txt @@ -0,0 +1,52 @@ +####################################### +# Syntax Coloring Map +####################################### + +####################################### +# Datatypes (KEYWORD1) +####################################### + +####################################### +# Methods and Functions (KEYWORD2) +####################################### +digitalToggle KEYWORD2 +bitToggle KEYWORD2 +analogPrescaler KEYWORD2 +_BV KEYWORD2 +cbi KEYWORD2 +sbi KEYWORD2 +setPWM_20kHz KEYWORD2 +setPWM_9_10_resolution KEYWORD2 +setPwmFreqnuency KEYWORD2 +setPWM_default KEYWORD2 +analogStartConvert KEYWORD2 +analogGet KEYWORD2 + +uartBegin KEYWORD2 +uartEnd KEYWORD2 +uartPeek KEYWORD2 +uartClear KEYWORD2 +uartRead KEYWORD2 +uartWrite KEYWORD2 +uartPrint KEYWORD2 +uartPrintln KEYWORD2 +uartAvailable KEYWORD2 +uartSetTimeout KEYWORD2 +uartParseInt KEYWORD2 +uartReadString KEYWORD2 +uartParseFloat KEYWORD2 +uartParsePacket KEYWORD2 + +###################################### +# Constants (LITERAL1) +####################################### +THERMOMETR LITERAL1 +A0 LITERAL1 +A1 LITERAL1 +A2 LITERAL1 +A3 LITERAL1 +A4 LITERAL1 +A5 LITERAL1 +A6 LITERAL1 +A7 LITERAL1 + diff --git a/GyverCore/variants/eightanaloginputs/pins_arduino.h b/GyverCore/variants/eightanaloginputs/pins_arduino.h deleted file mode 100644 index 4ccf8ba..0000000 --- a/GyverCore/variants/eightanaloginputs/pins_arduino.h +++ /dev/null @@ -1,25 +0,0 @@ -/* - pins_arduino.h - Pin definition functions for Arduino - Part of Arduino - http://www.arduino.cc/ - - Copyright (c) 2007 David A. Mellis - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library 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 - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General - Public License along with this library; if not, write to the - Free Software Foundation, Inc., 59 Temple Place, Suite 330, - Boston, MA 02111-1307 USA -*/ - -#include "../standard/pins_arduino.h" -#undef NUM_ANALOG_INPUTS -#define NUM_ANALOG_INPUTS 8 diff --git a/GyverCore/variants/nomillis/timeControl.h b/GyverCore/variants/nomillis/timeControl.h new file mode 100644 index 0000000..e69de29 diff --git a/GyverCore/variants/standard/pins_arduino.h b/GyverCore/variants/standard/pins_arduino.h deleted file mode 100644 index 2ea0190..0000000 --- a/GyverCore/variants/standard/pins_arduino.h +++ /dev/null @@ -1,254 +0,0 @@ -/* - pins_arduino.h - Pin definition functions for Arduino - Part of Arduino - http://www.arduino.cc/ - - Copyright (c) 2007 David A. Mellis - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library 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 - Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General - Public License along with this library; if not, write to the - Free Software Foundation, Inc., 59 Temple Place, Suite 330, - Boston, MA 02111-1307 USA -*/ - -#ifndef Pins_Arduino_h -#define Pins_Arduino_h - -#include - -#define NUM_DIGITAL_PINS 20 -#define NUM_ANALOG_INPUTS 6 -#define analogInputToDigitalPin(p) ((p < 6) ? (p) + 14 : -1) - -#if defined(__AVR_ATmega8__) -#define digitalPinHasPWM(p) ((p) == 9 || (p) == 10 || (p) == 11) -#else -#define digitalPinHasPWM(p) ((p) == 3 || (p) == 5 || (p) == 6 || (p) == 9 || (p) == 10 || (p) == 11) -#endif - -#define PIN_SPI_SS (10) -#define PIN_SPI_MOSI (11) -#define PIN_SPI_MISO (12) -#define PIN_SPI_SCK (13) - -static const uint8_t SS = PIN_SPI_SS; -static const uint8_t MOSI = PIN_SPI_MOSI; -static const uint8_t MISO = PIN_SPI_MISO; -static const uint8_t SCK = PIN_SPI_SCK; - -#define PIN_WIRE_SDA (18) -#define PIN_WIRE_SCL (19) - -static const uint8_t SDA = PIN_WIRE_SDA; -static const uint8_t SCL = PIN_WIRE_SCL; - -#define LED_BUILTIN 13 - -#define PIN_A0 (14) -#define PIN_A1 (15) -#define PIN_A2 (16) -#define PIN_A3 (17) -#define PIN_A4 (18) -#define PIN_A5 (19) -#define PIN_A6 (20) -#define PIN_A7 (21) - -static const uint8_t A0 = PIN_A0; -static const uint8_t A1 = PIN_A1; -static const uint8_t A2 = PIN_A2; -static const uint8_t A3 = PIN_A3; -static const uint8_t A4 = PIN_A4; -static const uint8_t A5 = PIN_A5; -static const uint8_t A6 = PIN_A6; -static const uint8_t A7 = PIN_A7; - -#define digitalPinToPCICR(p) (((p) >= 0 && (p) <= 21) ? (&PCICR) : ((uint8_t *)0)) -#define digitalPinToPCICRbit(p) (((p) <= 7) ? 2 : (((p) <= 13) ? 0 : 1)) -#define digitalPinToPCMSK(p) (((p) <= 7) ? (&PCMSK2) : (((p) <= 13) ? (&PCMSK0) : (((p) <= 21) ? (&PCMSK1) : ((uint8_t *)0)))) -#define digitalPinToPCMSKbit(p) (((p) <= 7) ? (p) : (((p) <= 13) ? ((p) - 8) : ((p) - 14))) - -#define digitalPinToInterrupt(p) ((p) == 2 ? 0 : ((p) == 3 ? 1 : NOT_AN_INTERRUPT)) - -#ifdef ARDUINO_MAIN - -// On the Arduino board, digital pins are also used -// for the analog output (software PWM). Analog input -// pins are a separate set. - -// ATMEL ATMEGA8 & 168 / ARDUINO -// -// +-\/-+ -// PC6 1| |28 PC5 (AI 5) -// (D 0) PD0 2| |27 PC4 (AI 4) -// (D 1) PD1 3| |26 PC3 (AI 3) -// (D 2) PD2 4| |25 PC2 (AI 2) -// PWM+ (D 3) PD3 5| |24 PC1 (AI 1) -// (D 4) PD4 6| |23 PC0 (AI 0) -// VCC 7| |22 GND -// GND 8| |21 AREF -// PB6 9| |20 AVCC -// PB7 10| |19 PB5 (D 13) -// PWM+ (D 5) PD5 11| |18 PB4 (D 12) -// PWM+ (D 6) PD6 12| |17 PB3 (D 11) PWM -// (D 7) PD7 13| |16 PB2 (D 10) PWM -// (D 8) PB0 14| |15 PB1 (D 9) PWM -// +----+ -// -// (PWM+ indicates the additional PWM pins on the ATmega168.) - -// ATMEL ATMEGA1280 / ARDUINO -// -// 0-7 PE0-PE7 works -// 8-13 PB0-PB5 works -// 14-21 PA0-PA7 works -// 22-29 PH0-PH7 works -// 30-35 PG5-PG0 works -// 36-43 PC7-PC0 works -// 44-51 PJ7-PJ0 works -// 52-59 PL7-PL0 works -// 60-67 PD7-PD0 works -// A0-A7 PF0-PF7 -// A8-A15 PK0-PK7 - - -// these arrays map port names (e.g. port B) to the -// appropriate addresses for various functions (e.g. reading -// and writing) -const uint16_t PROGMEM port_to_mode_PGM[] = { - NOT_A_PORT, - NOT_A_PORT, - (uint16_t) &DDRB, - (uint16_t) &DDRC, - (uint16_t) &DDRD, -}; - -const uint16_t PROGMEM port_to_output_PGM[] = { - NOT_A_PORT, - NOT_A_PORT, - (uint16_t) &PORTB, - (uint16_t) &PORTC, - (uint16_t) &PORTD, -}; - -const uint16_t PROGMEM port_to_input_PGM[] = { - NOT_A_PORT, - NOT_A_PORT, - (uint16_t) &PINB, - (uint16_t) &PINC, - (uint16_t) &PIND, -}; - -const uint8_t PROGMEM digital_pin_to_port_PGM[] = { - PD, /* 0 */ - PD, - PD, - PD, - PD, - PD, - PD, - PD, - PB, /* 8 */ - PB, - PB, - PB, - PB, - PB, - PC, /* 14 */ - PC, - PC, - PC, - PC, - PC, -}; - -const uint8_t PROGMEM digital_pin_to_bit_mask_PGM[] = { - _BV(0), /* 0, port D */ - _BV(1), - _BV(2), - _BV(3), - _BV(4), - _BV(5), - _BV(6), - _BV(7), - _BV(0), /* 8, port B */ - _BV(1), - _BV(2), - _BV(3), - _BV(4), - _BV(5), - _BV(0), /* 14, port C */ - _BV(1), - _BV(2), - _BV(3), - _BV(4), - _BV(5), -}; - -const uint8_t PROGMEM digital_pin_to_timer_PGM[] = { - NOT_ON_TIMER, /* 0 - port D */ - NOT_ON_TIMER, - NOT_ON_TIMER, - // on the ATmega168, digital pin 3 has hardware pwm -#if defined(__AVR_ATmega8__) - NOT_ON_TIMER, -#else - TIMER2B, -#endif - NOT_ON_TIMER, - // on the ATmega168, digital pins 5 and 6 have hardware pwm -#if defined(__AVR_ATmega8__) - NOT_ON_TIMER, - NOT_ON_TIMER, -#else - TIMER0B, - TIMER0A, -#endif - NOT_ON_TIMER, - NOT_ON_TIMER, /* 8 - port B */ - TIMER1A, - TIMER1B, -#if defined(__AVR_ATmega8__) - TIMER2, -#else - TIMER2A, -#endif - NOT_ON_TIMER, - NOT_ON_TIMER, - NOT_ON_TIMER, - NOT_ON_TIMER, /* 14 - port C */ - NOT_ON_TIMER, - NOT_ON_TIMER, - NOT_ON_TIMER, - NOT_ON_TIMER, -}; - -#endif - -// These serial port names are intended to allow libraries and architecture-neutral -// sketches to automatically default to the correct port name for a particular type -// of use. For example, a GPS module would normally connect to SERIAL_PORT_HARDWARE_OPEN, -// the first hardware serial port whose RX/TX pins are not dedicated to another use. -// -// SERIAL_PORT_MONITOR Port which normally prints to the Arduino Serial Monitor -// -// SERIAL_PORT_USBVIRTUAL Port which is USB virtual serial -// -// SERIAL_PORT_LINUXBRIDGE Port which connects to a Linux system via Bridge library -// -// SERIAL_PORT_HARDWARE Hardware serial port, physical RX & TX pins. -// -// SERIAL_PORT_HARDWARE_OPEN Hardware serial ports which are open for use. Their RX & TX -// pins are NOT connected to anything by default. -#define SERIAL_PORT_MONITOR Serial -#define SERIAL_PORT_HARDWARE Serial - -#endif diff --git a/GyverCore/variants/yesmillis/timeControl.h b/GyverCore/variants/yesmillis/timeControl.h new file mode 100644 index 0000000..4ba6fcf --- /dev/null +++ b/GyverCore/variants/yesmillis/timeControl.h @@ -0,0 +1 @@ +#define MILLIS_TMRS \ No newline at end of file diff --git a/README.md b/README.md index 1a125f0..d49797c 100644 --- a/README.md +++ b/README.md @@ -1,3 +1,19 @@ -# GyverCore - Быстрое ядро для Arduino IDE - В разработке +# GyverCore for ATmega328p/168p + Быстрое ядро для Arduino IDE. **В разработке** + Основано на оригинальном ядре Arduino версии 1.8.9, большинство функций заменены на более быстрые и лёгкие аналоги, убрано всё лишнее и не относящееся к микроконтроллеру ATmega328p, убран почти весь Wiring-мусор, код упрощён и причёсан. +# Изменения +## Облегчено и ускорено +Время выполнения функций, мкс +| Функция | Arduino | GyverCore | Быстрее в | +|----------------- |----------- |----------- |----------- | +| pinMode | 2.90 us | 0.57 us | 5.09 | +| digitalWrite | 2.90 us | 0.57 us | 5.09 | +| digitalRead | 2.45 us | 0.50 us | 4.90 | +| analogWrite | 4.15 us | 1.13 us | 3.67 | +| analogRead | 112.01 us | 5.41 us | 20.70 | +| analogReference | 0.00 us | 0.69 us | 0.00 | +| attachInterrupt | 1.20 us | 1.18 us | 1.02 | +| detachInterrupt | 0.82 us | 0.57 us | 1.44 | + + +## Добавлено