switch to setup for Arduino Boards Manager

This commit is contained in:
Erik Tylek Kettenburg
2015-06-23 12:42:35 -07:00
parent bc55c9bb45
commit 6ca6b114d5
3581 changed files with 93 additions and 51 deletions

View File

@@ -0,0 +1,282 @@
#ifndef Arduino_h
#define Arduino_h
#include <stdlib.h>
#include <string.h>
#include <math.h>
#include <avr/pgmspace.h>
#include <avr/io.h>
#include <avr/interrupt.h>
#include "binary.h"
#ifdef __cplusplus
extern "C"{
#endif
#define ATTINY_CORE 1
#define HIGH 0x1
#define LOW 0x0
#define INPUT 0x0
#define OUTPUT 0x1
#define INPUT_PULLUP 0x2
#define true 0x1
#define false 0x0
#define PI 3.1415926535897932384626433832795
#define HALF_PI 1.5707963267948966192313216916398
#define TWO_PI 6.283185307179586476925286766559
#define DEG_TO_RAD 0.017453292519943295769236907684886
#define RAD_TO_DEG 57.295779513082320876798154814105
#define SERIAL 0x0
#define DISPLAY 0x1
#define LSBFIRST 0
#define MSBFIRST 1
#define CHANGE 1
#define FALLING 2
#define RISING 3
// undefine stdlib's abs if encountered
#ifdef abs
#undef abs
#endif
#define min(a,b) ((a)<(b)?(a):(b))
#define max(a,b) ((a)>(b)?(a):(b))
#define abs(x) ((x)>0?(x):-(x))
#define constrain(amt,low,high) ((amt)<(low)?(low):((amt)>(high)?(high):(amt)))
#if __AVR_LIBC_VERSION__ < 10701UL
#define round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5))
#endif
#define radians(deg) ((deg)*DEG_TO_RAD)
#define degrees(rad) ((rad)*RAD_TO_DEG)
#define sq(x) ((x)*(x))
#define interrupts() sei()
#define noInterrupts() cli()
#if F_CPU < 1000000L
//Prevent a divide by 0 is
#warning Clocks per microsecond < 1. To prevent divide by 0, it is rounded up to 1.
static inline unsigned long clockCyclesPerMicrosecond() __attribute__ ((always_inline));
static inline unsigned long clockCyclesPerMicrosecond()
{
//Inline function will be optimised out.
return 1;
}
#else
#define clockCyclesPerMicrosecond() ( F_CPU / 1000000L )
#endif
#define clockCyclesToMicroseconds(a) ( ((a) * 1000L) / (F_CPU / 1000L) )
#define microsecondsToClockCycles(a) ( ((a) * (F_CPU / 1000L)) / 1000L )
#define lowByte(w) ((uint8_t) ((w) & 0xff))
#define highByte(w) ((uint8_t) ((w) >> 8))
#define bitRead(value, bit) (((value) >> (bit)) & 0x01)
#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))
typedef unsigned int word;
#define bit(b) (1UL << (b))
typedef uint8_t boolean;
typedef uint8_t byte;
void initToneTimer(void);
void init(void);
void pinMode(uint8_t, uint8_t);
void digitalWrite(uint8_t, uint8_t);
int digitalRead(uint8_t);
int analogRead(uint8_t);
void analogReference(uint8_t mode);
void analogWrite(uint8_t, int);
void pwmWrite(uint8_t, int);
void pwmConnect(uint8_t);
void pwmDisconnect(uint8_t);
void pwmReset(void);
unsigned long millis(void);
unsigned long micros(void);
void delay(unsigned long);
void delayMicroseconds(unsigned int us);
unsigned long pulseIn(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 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)
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[];
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) ) )
#define analogInPinToBit(P) (P)
#define portOutputRegister(P) ( (volatile uint8_t *)( pgm_read_word( port_to_output_PGM + (P))) )
#define portInputRegister(P) ( (volatile uint8_t *)( pgm_read_word( port_to_input_PGM + (P))) )
#define portModeRegister(P) ( (volatile uint8_t *)( pgm_read_word( port_to_mode_PGM + (P))) )
#define NOT_A_PIN 0
#define NOT_A_PORT 0
#define PA 1
#define PB 2
#define PC 3
#define PD 4
#define NOT_ON_TIMER 0
#define TIMER0A 1
#define TIMER0B 2
#define TIMER1A 3
#define TIMER1B 4
#define TIMER1D 5
#define CHANNELA 3 //TIMER1A
#define CHANNELB 4 //TIMER1B
#include "pins_arduino.h"
#ifndef USE_SOFTWARE_SERIAL
//Default to hardware serial.
#define USE_SOFTWARE_SERIAL 0
#endif
/*=============================================================================
Allow the ADC to be optional for low-power applications
=============================================================================*/
#ifndef TIMER_TO_USE_FOR_MILLIS
#define TIMER_TO_USE_FOR_MILLIS 0
#endif
/*
Tone goes on whichever timer was not used for millis.
*/
#if TIMER_TO_USE_FOR_MILLIS == 1
#define TIMER_TO_USE_FOR_TONE 0
#else
#define TIMER_TO_USE_FOR_TONE 1
#endif
#if NUM_ANALOG_INPUTS > 0
#define HAVE_ADC 1
#ifndef INITIALIZE_ANALOG_TO_DIGITAL_CONVERTER
#define INITIALIZE_ANALOG_TO_DIGITAL_CONVERTER 1
#endif
#else
#define HAVE_ADC 0
#if defined(INITIALIZE_ANALOG_TO_DIGITAL_CONVERTER)
#undef INITIALIZE_ANALOG_TO_DIGITAL_CONVERTER
#endif
#define INITIALIZE_ANALOG_TO_DIGITAL_CONVERTER 0
#endif
#if !HAVE_ADC
#undef INITIALIZE_ANALOG_TO_DIGITAL_CONVERTER
#define INITIALIZE_ANALOG_TO_DIGITAL_CONVERTER 0
#else
#ifndef INITIALIZE_ANALOG_TO_DIGITAL_CONVERTER
#define INITIALIZE_ANALOG_TO_DIGITAL_CONVERTER 1
#endif
#endif
/*=============================================================================
Allow the "secondary timers" to be optional for low-power applications
=============================================================================*/
#ifndef INITIALIZE_SECONDARY_TIMERS
#define INITIALIZE_SECONDARY_TIMERS 1
#endif
#ifdef __cplusplus
} // extern "C"
#endif
#ifdef __cplusplus
#include "WCharacter.h"
#include "WString.h"
#include "HardwareSerial.h"
#include "TinySoftwareSerial.h"
uint16_t makeWord(uint16_t w);
uint16_t makeWord(byte h, byte l);
#define word(...) makeWord(__VA_ARGS__)
unsigned long pulseIn(uint8_t pin, uint8_t state, unsigned long timeout = 1000000L);
void tone(uint8_t _pin, unsigned int frequency, unsigned long duration = 0);
void noTone(uint8_t _pin = 255);
// WMath prototypes
long random(long);
long random(long, long);
void randomSeed(unsigned int);
long map(long, long, long, long, long);
#endif
/*=============================================================================
Aliases for the interrupt service routine vector numbers so the code
doesn't have to be riddled with #ifdefs.
=============================================================================*/
#if defined( TIM0_COMPA_vect ) && ! defined( TIMER0_COMPA_vect )
#define TIMER0_COMPA_vect TIM0_COMPA_vect
#endif
#if defined( TIM0_COMPB_vect ) && ! defined( TIMER0_COMPB_vect )
#define TIMER0_COMPB_vect TIM0_COMPB_vect
#endif
#if defined( TIM0_OVF_vect ) && ! defined( TIMER0_OVF_vect )
#define TIMER0_OVF_vect TIM0_OVF_vect
#endif
#if defined( TIM1_COMPA_vect ) && ! defined( TIMER1_COMPA_vect )
#define TIMER1_COMPA_vect TIM1_COMPA_vect
#endif
#if defined( TIM1_COMPB_vect ) && ! defined( TIMER1_COMPB_vect )
#define TIMER1_COMPB_vect TIM1_COMPB_vect
#endif
#if defined( TIM1_OVF_vect ) && ! defined( TIMER1_OVF_vect )
#define TIMER1_OVF_vect TIM1_OVF_vect
#endif
#endif

View File

@@ -0,0 +1,411 @@
/*
HardwareSerial.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
*/
#include <stdlib.h>
#include <stdio.h>
#include <string.h>
#include <inttypes.h>
#include "Arduino.h"
#include "wiring_private.h"
// this next line disables the entire HardwareSerial.cpp,
// this is so I can support Attiny series and any other chip without a uart
#if ( defined(UBRRH) || defined(UBRR0H) || defined(UBRR1H) || defined(LINBRRH)) && !USE_SOFTWARE_SERIAL
#include "HardwareSerial.h"
// Define constants and variables for buffering incoming serial data. We're
// using a ring buffer (I think), in which rx_buffer_head is the index of the
// location to which to write the next incoming character and rx_buffer_tail
// is the index of the location from which to read.
#ifndef SERIAL_BUFFER_SIZE
#if (RAMEND < 1000)
#define SERIAL_BUFFER_SIZE 16
#else
#define SERIAL_BUFFER_SIZE 64
#endif
#endif
struct ring_buffer
{
unsigned char buffer[SERIAL_BUFFER_SIZE];
byte head;
byte tail;
};
#if defined(UBRRH) || defined(UBRR0H) || defined(LINBRRH)
ring_buffer rx_buffer = { { 0 }, 0, 0 };
ring_buffer tx_buffer = { { 0 }, 0, 0 };
#endif
#if defined(UBRR1H)
ring_buffer rx_buffer1 = { { 0 }, 0, 0 };
ring_buffer tx_buffer1 = { { 0 }, 0, 0 };
#endif
inline void store_char(unsigned char c, ring_buffer *buffer)
{
byte i = (buffer->head + 1) % SERIAL_BUFFER_SIZE;
// if we should be storing the received character into the location
// just before the tail (meaning that the head would advance to the
// current location of the tail), we're about to overflow the buffer
// and so we don't write the character or advance the head.
if (i != buffer->tail) {
buffer->buffer[buffer->head] = c;
buffer->head = i;
}
}
#if defined(USART_RX_vect)
SIGNAL(USART_RX_vect)
{
#if defined(UDR0)
unsigned char c = UDR0;
#elif defined(UDR)
unsigned char c = UDR; // atmega8535
#else
#error UDR not defined
#endif
store_char(c, &rx_buffer);
}
#elif defined(SIG_USART0_RECV) && defined(UDR0)
SIGNAL(SIG_USART0_RECV)
{
unsigned char c = UDR0;
store_char(c, &rx_buffer);
}
#elif defined(SIG_UART0_RECV) && defined(UDR0)
SIGNAL(SIG_UART0_RECV)
{
unsigned char c = UDR0;
store_char(c, &rx_buffer);
}
//#elif defined(SIG_USART_RECV)
#elif defined(USART0_RX_vect)
// fixed by Mark Sproul this is on the 644/644p
//SIGNAL(SIG_USART_RECV)
SIGNAL(USART0_RX_vect)
{
#if defined(UDR0)
unsigned char c = UDR0;
#elif defined(UDR)
unsigned char c = UDR; // atmega8, atmega32
#else
#error UDR not defined
#endif
store_char(c, &rx_buffer);
}
#elif defined(SIG_UART_RECV)
// this is for atmega8
SIGNAL(SIG_UART_RECV)
{
#if defined(UDR0)
unsigned char c = UDR0; // atmega645
#elif defined(UDR)
unsigned char c = UDR; // atmega8
#endif
store_char(c, &rx_buffer);
}
#elif defined(LIN_TC_vect)
// this is for attinyX7
SIGNAL(LIN_TC_vect)
{
if(LINSIR & _BV(LRXOK)) {
unsigned char c = LINDAT;
store_char(c, &rx_buffer);
}
if(LINSIR & _BV(LTXOK)){
PINA |= _BV(PINA5);
if (tx_buffer.head == tx_buffer.tail) {
// Buffer empty, so disable interrupts
cbi(LINENIR,LENTXOK);
} else {
// There is more data in the output buffer. Send the next byte
unsigned char c = tx_buffer.buffer[tx_buffer.tail];
tx_buffer.tail = (tx_buffer.tail + 1) % SERIAL_BUFFER_SIZE;
LINDAT = c;
}
}
}
#else
#error No interrupt handler for usart 0
#endif
//#if defined(SIG_USART1_RECV)
#if defined(USART1_RX_vect)
//SIGNAL(SIG_USART1_RECV)
SIGNAL(USART1_RX_vect)
{
unsigned char c = UDR1;
store_char(c, &rx_buffer1);
}
#elif defined(SIG_USART1_RECV)
#error SIG_USART1_RECV
#endif
#if !defined(UART0_UDRE_vect) && !defined(UART_UDRE_vect) && !defined(USART0_UDRE_vect) && !defined(USART_UDRE_vect) && !defined(LIN_TC_vect)
#error "Don't know what the Data Register Empty vector is called for the first UART"
#elif ( defined(UBRRH) || defined(UBRR0H) || defined(UBRR1H))
#if defined(UART0_UDRE_vect)
ISR(UART0_UDRE_vect)
#elif defined(UART_UDRE_vect)
ISR(UART_UDRE_vect)
#elif defined(USART0_UDRE_vect)
ISR(USART0_UDRE_vect)
#elif defined(USART_UDRE_vect)
ISR(USART_UDRE_vect)
#endif
{
if (tx_buffer.head == tx_buffer.tail) {
// Buffer empty, so disable interrupts
#if defined(UCSR0B)
cbi(UCSR0B, UDRIE0);
#else
cbi(UCSRB, UDRIE);
#endif
}
else {
// There is more data in the output buffer. Send the next byte
unsigned char c = tx_buffer.buffer[tx_buffer.tail];
tx_buffer.tail = (tx_buffer.tail + 1) % SERIAL_BUFFER_SIZE;
#if defined(UDR0)
UDR0 = c;
#elif defined(UDR)
UDR = c;
#else
#error UDR not defined
#endif
}
}
#endif
#ifdef USART1_UDRE_vect
ISR(USART1_UDRE_vect)
{
if (tx_buffer1.head == tx_buffer1.tail) {
// Buffer empty, so disable interrupts
cbi(UCSR1B, UDRIE1);
}
else {
// There is more data in the output buffer. Send the next byte
unsigned char c = tx_buffer1.buffer[tx_buffer1.tail];
tx_buffer1.tail = (tx_buffer1.tail + 1) % SERIAL_BUFFER_SIZE;
UDR1 = c;
}
}
#endif
// Constructors ////////////////////////////////////////////////////////////////
HardwareSerial::HardwareSerial(ring_buffer *rx_buffer, ring_buffer *tx_buffer
#if ( defined(UBRRH) || defined(UBRR0H) || defined(UBRR1H))
,
volatile uint8_t *ubrrh, volatile uint8_t *ubrrl,
volatile uint8_t *ucsra, volatile uint8_t *ucsrb,
volatile uint8_t *udr,
uint8_t rxen, uint8_t txen, uint8_t rxcie, uint8_t udrie, uint8_t u2x
)
{
_rx_buffer = rx_buffer;
_tx_buffer = tx_buffer;
_ubrrh = ubrrh;
_ubrrl = ubrrl;
_ucsra = ucsra;
_ucsrb = ucsrb;
_udr = udr;
_rxen = rxen;
_txen = txen;
_rxcie = rxcie;
_udrie = udrie;
_u2x = u2x;
}
#else
)
{
_rx_buffer = rx_buffer;
_tx_buffer = tx_buffer;
}
#endif
// Public Methods //////////////////////////////////////////////////////////////
void HardwareSerial::begin(long baud)
{
#if ( defined(UBRRH) || defined(UBRR0H) || defined(UBRR1H))
uint16_t baud_setting;
bool use_u2x = true;
#if F_CPU == 16000000UL
// hardcoded exception for compatibility with the bootloader shipped
// with the Duemilanove and previous boards and the firmware on the 8U2
// on the Uno and Mega 2560.
if (baud == 57600) {
use_u2x = false;
}
#endif
try_again:
if (use_u2x) {
*_ucsra = 1 << _u2x;
baud_setting = (F_CPU / 4 / baud - 1) / 2;
} else {
*_ucsra = 0;
baud_setting = (F_CPU / 8 / baud - 1) / 2;
}
if ((baud_setting > 4095) && use_u2x)
{
use_u2x = false;
goto try_again;
}
// assign the baud_setting, a.k.a. ubbr (USART Baud Rate Register)
*_ubrrh = baud_setting >> 8;
*_ubrrl = baud_setting;
sbi(*_ucsrb, _rxen);
sbi(*_ucsrb, _txen);
sbi(*_ucsrb, _rxcie);
cbi(*_ucsrb, _udrie);
#else
LINCR = (1 << LSWRES);
LINBRR = (((F_CPU * 10L / 16L / baud) + 5L) / 10L) - 1;
LINBTR = (1 << LDISR) | (16 << LBT0);
LINCR = _BV(LENA) | _BV(LCMD2) | _BV(LCMD1) | _BV(LCMD0);
sbi(LINENIR,LENRXOK);
#endif
}
void HardwareSerial::end()
{
while (_tx_buffer->head != _tx_buffer->tail)
;
#if ( defined(UBRRH) || defined(UBRR0H) || defined(UBRR1H))
cbi(*_ucsrb, _rxen);
cbi(*_ucsrb, _txen);
cbi(*_ucsrb, _rxcie);
cbi(*_ucsrb, _udrie);
#else
cbi(LINENIR,LENTXOK);
cbi(LINENIR,LENRXOK);
cbi(LINCR,LENA);
cbi(LINCR,LCMD0);
cbi(LINCR,LCMD1);
cbi(LINCR,LCMD2);
#endif
_rx_buffer->head = _rx_buffer->tail;
}
int HardwareSerial::available(void)
{
return (unsigned int)(SERIAL_BUFFER_SIZE + _rx_buffer->head - _rx_buffer->tail) % SERIAL_BUFFER_SIZE;
}
int HardwareSerial::peek(void)
{
if (_rx_buffer->head == _rx_buffer->tail) {
return -1;
} else {
return _rx_buffer->buffer[_rx_buffer->tail];
}
}
int HardwareSerial::read(void)
{
// if the head isn't ahead of the tail, we don't have any characters
if (_rx_buffer->head == _rx_buffer->tail) {
return -1;
} else {
unsigned char c = _rx_buffer->buffer[_rx_buffer->tail];
_rx_buffer->tail = (_rx_buffer->tail + 1) % SERIAL_BUFFER_SIZE;
return c;
}
}
void HardwareSerial::flush()
{
while (_tx_buffer->head != _tx_buffer->tail)
;
}
unsigned int HardwareSerial::txfree()
{
if (_tx_buffer->head >= _tx_buffer->tail) return SERIAL_BUFFER_SIZE - 1 - _tx_buffer->head + _tx_buffer->tail;
return _tx_buffer->tail - _tx_buffer->head - 1;
}
size_t HardwareSerial::write(uint8_t c)
{
byte i = (_tx_buffer->head + 1) % SERIAL_BUFFER_SIZE;
// If the output buffer is full, there's nothing for it other than to
// wait for the interrupt handler to empty it a bit
// ???: return 0 here instead?
while (txfree() == 0);
_tx_buffer->buffer[_tx_buffer->head] = c;
_tx_buffer->head = i;
#if ( defined(UBRRH) || defined(UBRR0H) || defined(UBRR1H) )
sbi(*_ucsrb, _udrie);
#else
if(!(LINENIR & _BV(LENTXOK))){
//The buffer was previously empty, so enable TX Complete interrupt and load first byte.
sbi(LINENIR,LENTXOK);
unsigned char c = tx_buffer.buffer[tx_buffer.tail];
tx_buffer.tail = (tx_buffer.tail + 1) % SERIAL_BUFFER_SIZE;
LINDAT = c;
}
#endif
return 1;
}
HardwareSerial::operator bool() {
return true;
}
// Preinstantiate Objects //////////////////////////////////////////////////////
#if defined(UBRRH) && defined(UBRRL)
HardwareSerial Serial(&rx_buffer, &tx_buffer, &UBRRH, &UBRRL, &UCSRA, &UCSRB, &UDR, RXEN, TXEN, RXCIE, UDRE, U2X);
#elif defined(UBRR0H) && defined(UBRR0L)
HardwareSerial Serial(&rx_buffer, &tx_buffer, &UBRR0H, &UBRR0L, &UCSR0A, &UCSR0B, &UDR0, RXEN0, TXEN0, RXCIE0, UDRE0, U2X0);
#elif defined(LINBRRH)
HardwareSerial Serial(&rx_buffer, &tx_buffer);
#endif
#if defined(UBRR1H)
HardwareSerial Serial1(&rx_buffer1, &tx_buffer1, &UBRR1H, &UBRR1L, &UCSR1A, &UCSR1B, &UDR1, RXEN1, TXEN1, RXCIE1, UDRE1, U2X1);
#endif
#elif !USE_SOFTWARE_SERIAL
#warning There is no Hardware UART, and Sofware Serial is not enabled. There will be no serial port.
#endif // whole file

View File

@@ -0,0 +1,80 @@
/*
HardwareSerial.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 28 September 2010 by Mark Sproul
*/
#ifndef HardwareSerial_h
#define HardwareSerial_h
#if ( defined(UBRRH) || defined(UBRR0H) || defined(UBRR1H) || defined(LINBRRH)) && !USE_SOFTWARE_SERIAL
#include <inttypes.h>
#include "Stream.h"
struct ring_buffer;
class HardwareSerial : public Stream
{
private:
ring_buffer *_rx_buffer;
ring_buffer *_tx_buffer;
#if ( defined(UBRRH) || defined(UBRR0H) || defined(UBRR1H))
volatile uint8_t *_ubrrh;
volatile uint8_t *_ubrrl;
volatile uint8_t *_ucsra;
volatile uint8_t *_ucsrb;
volatile uint8_t *_udr;
uint8_t _rxen;
uint8_t _txen;
uint8_t _rxcie;
uint8_t _udrie;
uint8_t _u2x;
#endif
public:
HardwareSerial(ring_buffer *rx_buffer, ring_buffer *tx_buffer
#if ( defined(UBRRH) || defined(UBRR0H) || defined(UBRR1H))
,
volatile uint8_t *ubrrh, volatile uint8_t *ubrrl,
volatile uint8_t *ucsra, volatile uint8_t *ucsrb,
volatile uint8_t *udr,
uint8_t rxen, uint8_t txen, uint8_t rxcie, uint8_t udrie, uint8_t u2x);
#else
);
#endif
void begin(long);
void end();
virtual int available(void);
virtual int peek(void);
virtual unsigned int txfree(void);
virtual int read(void);
virtual void flush(void);
virtual size_t write(uint8_t);
using Print::write; // pull in write(str) and write(buf, size) from Print
operator bool();
};
#endif
#if (defined(UBRRH) || defined(UBRR0H) || defined(LINBRRH)) && !USE_SOFTWARE_SERIAL
extern HardwareSerial Serial;
#endif
#if defined(UBRR1H)
extern HardwareSerial Serial1;
#endif
#endif

View File

@@ -0,0 +1,262 @@
/*
Print.cpp - Base class that provides print() and println()
Copyright (c) 2008 David A. Mellis. 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
*/
#include <stdlib.h>
#include <stdio.h>
#include <string.h>
#include <math.h>
#include "Arduino.h"
#include "Print.h"
// Public Methods //////////////////////////////////////////////////////////////
/* default implementation: may be overridden */
size_t Print::write(const uint8_t *buffer, size_t size)
{
size_t n = 0;
while (size--) {
n += write(*buffer++);
}
return n;
}
size_t Print::print(const String &s)
{
size_t n = 0;
for (uint16_t i = 0; i < s.length(); i++) {
n += write(s[i]);
}
return n;
}
size_t Print::print(const char str[])
{
return write(str);
}
size_t Print::print(char c)
{
return write(c);
}
size_t Print::print(unsigned char b, int base)
{
return print((unsigned long) b, base);
}
size_t Print::print(int n, int base)
{
return print((long) n, base);
}
size_t Print::print(unsigned int n, int base)
{
return print((unsigned long) n, base);
}
size_t Print::print(long n, int base)
{
if (base == 0) {
return write(n);
} else if (base == 10) {
int t = 0;
if (n < 0) {
t = print('-');
n = -n;
}
return printNumber(n, 10) + t;
} else {
return printNumber(n, base);
}
}
size_t Print::print(unsigned long n, int base)
{
if (base == 0) return write(n);
else return printNumber(n, base);
}
size_t Print::print(double n, int digits)
{
return printFloat(n, digits);
}
size_t Print::print( fstr_t* s )
{
size_t n = 0;
char ch;
ch = pgm_read_byte( s );
while ( ch != 0 )
{
write( ch );
++s;
++n;
ch = pgm_read_byte( s );
}
return( n );
}
size_t Print::println(void)
{
size_t n = print('\r');
n += print('\n');
return n;
}
size_t Print::println(const String &s)
{
size_t n = print(s);
n += println();
return n;
}
size_t Print::println(const char c[])
{
size_t n = print(c);
n += println();
return n;
}
size_t Print::println(char c)
{
size_t n = print(c);
n += println();
return n;
}
size_t Print::println(unsigned char b, int base)
{
size_t n = print(b, base);
n += println();
return n;
}
size_t Print::println(int num, int base)
{
size_t n = print(num, base);
n += println();
return n;
}
size_t Print::println(unsigned int num, int base)
{
size_t n = print(num, base);
n += println();
return n;
}
size_t Print::println(long num, int base)
{
size_t n = print(num, base);
n += println();
return n;
}
size_t Print::println(long long num, int base)
{
size_t n = print(num, base);
n += println();
return n;
}
size_t Print::println(unsigned long num, int base)
{
size_t n = print(num, base);
n += println();
return n;
}
size_t Print::println(double num, int digits)
{
size_t n = print(num, digits);
n += println();
return n;
}
size_t Print::println( fstr_t* s )
{
size_t n = print( s );
n += println();
return( n );
}
// Private Methods /////////////////////////////////////////////////////////////
size_t Print::printNumber(unsigned long n, uint8_t base) {
char buf[8 * sizeof(long) + 1]; // Assumes 8-bit chars plus zero byte.
char *str = &buf[sizeof(buf) - 1];
*str = '\0';
// prevent crash if called with base == 1
if (base < 2) base = 10;
do {
unsigned long m = n;
n /= base;
char c = m - base * n;
*--str = c < 10 ? c + '0' : c + 'A' - 10;
} while(n);
return write(str);
}
size_t Print::printFloat(double number, uint8_t digits)
{
size_t n = 0;
// Handle negative numbers
if (number < 0.0)
{
n += print('-');
number = -number;
}
// Round correctly so that print(1.999, 2) prints as "2.00"
double rounding = 0.5;
for (uint8_t i=0; i<digits; ++i)
rounding /= 10.0;
number += rounding;
// Extract the integer part of the number and print it
unsigned long int_part = (unsigned long)number;
double remainder = number - (double)int_part;
n += print(int_part);
// Print the decimal point, but only if there are digits beyond
if (digits > 0) {
n += print(".");
}
// Extract digits from the remainder one at a time
while (digits-- > 0)
{
remainder *= 10.0;
int toPrint = int(remainder);
n += print(toPrint);
remainder -= toPrint;
}
return n;
}

View File

@@ -0,0 +1,108 @@
/*
Print.h - Base class that provides print() and println()
Copyright (c) 2008 David A. Mellis. 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 20-11-2010 by B.Cook ...
http://arduiniana.org/libraries/flash/
Printable support thanks to Mikal Hart
*/
#ifndef Print_h
#define Print_h
#include <inttypes.h>
#include <stdio.h> // for size_t
#include "WString.h"
#define DEC 10
#define HEX 16
#define OCT 8
#ifdef BIN
#define ABIN BIN
//One of the ATtiny84 registers has a bit called BIN, so rename it to avoid compiler warnings.
#undef BIN
#endif
#define BIN 2
#define ARDUINO_CORE_PRINTABLE_SUPPORT
class Print;
/* Printable...*/
class _Printable
{
public:
virtual void print(Print &stream) const = 0;
};
/* ...Printable */
typedef struct
{
char c;
}
fstr_t;
class Print
{
private:
int write_error;
size_t printNumber(unsigned long, uint8_t);
size_t printFloat(double, uint8_t);
protected:
void setWriteError(int err = 1) { write_error = err; }
public:
Print() : write_error(0) {}
int getWriteError() { return write_error; }
void clearWriteError() { setWriteError(0); }
virtual size_t write(uint8_t) = 0;
size_t write(const char *str) { return write((const uint8_t *)str, strlen(str)); }
virtual size_t write(const uint8_t *buffer, size_t size);
size_t print(fstr_t*);
size_t print(const String &);
size_t print(const char[]);
size_t print(char);
size_t print(unsigned char, int = DEC);
size_t print(int, int = DEC);
size_t print(unsigned int, int = DEC);
size_t print(long, int = DEC);
size_t print(long long, int = DEC);
size_t print(unsigned long, int = DEC);
size_t print(double, int = 2);
size_t println(fstr_t*);
size_t println(const String &s);
size_t println(const char[]);
size_t println(char);
size_t println(unsigned char, int = DEC);
size_t println(int, int = DEC);
size_t println(unsigned int, int = DEC);
size_t println(long, int = DEC);
size_t println(long long, int = DEC);
size_t println(unsigned long, int = DEC);
size_t println(double, int = 2);
size_t println(void);
};
#endif

View File

@@ -0,0 +1,40 @@
/*
Printable.h - Interface class that allows printing of complex types
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 Printable_h
#define Printable_h
#include <new.h>
class Print;
/** The Printable class provides a way for new classes to allow themselves to be printed.
By deriving from Printable and implementing the printTo method, it will then be possible
for users to print out instances of this class by passing them into the usual
Print::print and Print::println methods.
*/
class Printable
{
public:
virtual size_t printTo(Print& p) const = 0;
};
#endif

View File

@@ -0,0 +1,270 @@
/*
Stream.cpp - adds parsing methods to Stream class
Copyright (c) 2008 David A. Mellis. 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
Created July 2011
parsing functions based on TextFinder library by Michael Margolis
*/
#include "Arduino.h"
#include "Stream.h"
#define PARSE_TIMEOUT 1000 // default number of milli-seconds to wait
#define NO_SKIP_CHAR 1 // a magic char not found in a valid ASCII numeric field
// private method to read stream with timeout
int Stream::timedRead()
{
int c;
_startMillis = millis();
do {
c = read();
if (c >= 0) return c;
} while(millis() - _startMillis < _timeout);
return -1; // -1 indicates timeout
}
// private method to peek stream with timeout
int Stream::timedPeek()
{
int c;
_startMillis = millis();
do {
c = peek();
if (c >= 0) return c;
} while(millis() - _startMillis < _timeout);
return -1; // -1 indicates timeout
}
// returns peek of the next digit in the stream or -1 if timeout
// discards non-numeric characters
int Stream::peekNextDigit()
{
int c;
while (1) {
c = timedPeek();
if (c < 0) return c; // timeout
if (c == '-') return c;
if (c >= '0' && c <= '9') return c;
read(); // discard non-numeric
}
}
// Public Methods
//////////////////////////////////////////////////////////////
void Stream::setTimeout(unsigned long timeout) // sets the maximum number of milliseconds to wait
{
_timeout = timeout;
}
// find returns true if the target string is found
bool Stream::find(char *target)
{
return findUntil(target, "");
}
// reads data from the stream until the target string of given length is found
// returns true if target string is found, false if timed out
bool Stream::find(char *target, size_t length)
{
return findUntil(target, length, NULL, 0);
}
// as find but search ends if the terminator string is found
bool Stream::findUntil(char *target, char *terminator)
{
return findUntil(target, strlen(target), terminator, strlen(terminator));
}
// reads data from the stream until the target string of the given length is found
// search terminated if the terminator string is found
// returns true if target string is found, false if terminated or timed out
bool Stream::findUntil(char *target, size_t targetLen, char *terminator, size_t termLen)
{
size_t index = 0; // maximum target string length is 64k bytes!
size_t termIndex = 0;
int c;
if( *target == 0)
return true; // return true if target is a null string
while( (c = timedRead()) > 0){
if(c != target[index])
index = 0; // reset index if any char does not match
if( c == target[index]){
//////Serial.print("found "); Serial.write(c); Serial.print("index now"); Serial.println(index+1);
if(++index >= targetLen){ // return true if all chars in the target match
return true;
}
}
if(termLen > 0 && c == terminator[termIndex]){
if(++termIndex >= termLen)
return false; // return false if terminate string found before target string
}
else
termIndex = 0;
}
return false;
}
// returns the first valid (long) integer value from the current position.
// initial characters that are not digits (or the minus sign) are skipped
// function is terminated by the first character that is not a digit.
long Stream::parseInt()
{
return parseInt(NO_SKIP_CHAR); // terminate on first non-digit character (or timeout)
}
// as above but a given skipChar is ignored
// this allows format characters (typically commas) in values to be ignored
long Stream::parseInt(char skipChar)
{
boolean isNegative = false;
long value = 0;
int c;
c = peekNextDigit();
// ignore non numeric leading characters
if(c < 0)
return 0; // zero returned if timeout
do{
if(c == skipChar)
; // ignore this charactor
else if(c == '-')
isNegative = true;
else if(c >= '0' && c <= '9') // is c a digit?
value = value * 10 + c - '0';
read(); // consume the character we got with peek
c = timedPeek();
}
while( (c >= '0' && c <= '9') || c == skipChar );
if(isNegative)
value = -value;
return value;
}
// as parseInt but returns a floating point value
float Stream::parseFloat()
{
return parseFloat(NO_SKIP_CHAR);
}
// as above but the given skipChar is ignored
// this allows format characters (typically commas) in values to be ignored
float Stream::parseFloat(char skipChar){
boolean isNegative = false;
boolean isFraction = false;
long value = 0;
char c;
float fraction = 1.0;
c = peekNextDigit();
// ignore non numeric leading characters
if(c < 0)
return 0; // zero returned if timeout
do{
if(c == skipChar)
; // ignore
else if(c == '-')
isNegative = true;
else if (c == '.')
isFraction = true;
else if(c >= '0' && c <= '9') { // is c a digit?
value = value * 10 + c - '0';
if(isFraction)
fraction *= 0.1;
}
read(); // consume the character we got with peek
c = timedPeek();
}
while( (c >= '0' && c <= '9') || c == '.' || c == skipChar );
if(isNegative)
value = -value;
if(isFraction)
return value * fraction;
else
return value;
}
// read characters from stream into buffer
// terminates if length characters have been read, or timeout (see setTimeout)
// returns the number of characters placed in the buffer
// the buffer is NOT null terminated.
//
size_t Stream::readBytes(char *buffer, size_t length)
{
size_t count = 0;
while (count < length) {
int c = timedRead();
if (c < 0) break;
*buffer++ = (char)c;
count++;
}
return count;
}
// as readBytes with terminator character
// terminates if length characters have been read, timeout, or if the terminator character detected
// returns the number of characters placed in the buffer (0 means no valid data found)
size_t Stream::readBytesUntil(char terminator, char *buffer, size_t length)
{
if (length < 1) return 0;
size_t index = 0;
while (index < length) {
int c = timedRead();
if (c < 0 || c == terminator) break;
*buffer++ = (char)c;
index++;
}
return index; // return number of characters, not including null terminator
}
String Stream::readString()
{
String ret;
int c = timedRead();
while (c >= 0)
{
ret += (char)c;
c = timedRead();
}
return ret;
}
String Stream::readStringUntil(char terminator)
{
String ret;
int c = timedRead();
while (c >= 0 && c != terminator)
{
ret += (char)c;
c = timedRead();
}
return ret;
}

View File

@@ -0,0 +1,96 @@
/*
Stream.h - base class for character-based streams.
Copyright (c) 2010 David A. Mellis. 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
parsing functions based on TextFinder library by Michael Margolis
*/
#ifndef Stream_h
#define Stream_h
#include <inttypes.h>
#include "Print.h"
// compatability macros for testing
/*
#define getInt() parseInt()
#define getInt(skipChar) parseInt(skipchar)
#define getFloat() parseFloat()
#define getFloat(skipChar) parseFloat(skipChar)
#define getString( pre_string, post_string, buffer, length)
readBytesBetween( pre_string, terminator, buffer, length)
*/
class Stream : public Print
{
protected:
unsigned long _timeout; // number of milliseconds to wait for the next char before aborting timed read
unsigned long _startMillis; // used for timeout measurement
int timedRead(); // private method to read stream with timeout
int timedPeek(); // private method to peek stream with timeout
int peekNextDigit(); // returns the next numeric digit in the stream or -1 if timeout
public:
virtual int available() = 0;
virtual int read() = 0;
virtual int peek() = 0;
virtual void flush() = 0;
Stream() {_timeout=1000;}
// parsing methods
void setTimeout(unsigned long timeout); // sets maximum milliseconds to wait for stream data, default is 1 second
bool find(char *target); // reads data from the stream until the target string is found
// returns true if target string is found, false if timed out (see setTimeout)
bool find(char *target, size_t length); // reads data from the stream until the target string of given length is found
// returns true if target string is found, false if timed out
bool findUntil(char *target, char *terminator); // as find but search ends if the terminator string is found
bool findUntil(char *target, size_t targetLen, char *terminate, size_t termLen); // as above but search ends if the terminate string is found
long parseInt(); // returns the first valid (long) integer value from the current position.
// initial characters that are not digits (or the minus sign) are skipped
// integer is terminated by the first character that is not a digit.
float parseFloat(); // float version of parseInt
size_t readBytes( char *buffer, size_t length); // read chars from stream into buffer
// terminates if length characters have been read or timeout (see setTimeout)
// returns the number of characters placed in the buffer (0 means no valid data found)
size_t readBytesUntil( char terminator, char *buffer, size_t length); // as readBytes with terminator character
// terminates if length characters have been read, timeout, or if the terminator character detected
// returns the number of characters placed in the buffer (0 means no valid data found)
// Arduino String functions to be added here
String readString();
String readStringUntil(char terminator);
protected:
long parseInt(char skipChar); // as above but the given skipChar is ignored
// as above but the given skipChar is ignored
// this allows format characters (typically commas) in values to be ignored
float parseFloat(char skipChar); // as above but the given skipChar is ignored
};
#endif

View File

@@ -0,0 +1,218 @@
/*
* Copyright (c) 2012 by Thomas Carpenter
* Software based SPI Master Library for Tiny core.
*
* This file is free software; you can redistribute it and/or modify
* it under the terms of either the GNU General Public License version 2
* or the GNU Lesser General Public License version 2.1, both as
* published by the Free Software Foundation.
*
* Currently, this runs at 125kHz on an 8MHz clock.
*/
#include "TinySoftwareSPI.h"
#include "Arduino.h"
SoftSPIClass::SoftSPIClass(){
_bitOrder = MSBFIRST;
_mode = SPI_MODE0;
_running = false;
transferType = &SoftSPIClass::noTransfer;
}
#if defined(SS) && defined(MOSI) && defined(MISO) && defined(SCK)
void SoftSPIClass::begin(){
begin(SCK,MOSI,MISO,SS);
}
#endif
void SoftSPIClass::writeSS(boolean state){
if (state) {
*_SS_PORT |= _SS_HIGH;
} else {
*_SS_PORT &= _SS_LOW;
}
}
void SoftSPIClass::begin(byte SCK_, byte MOSI_, byte MISO_, byte SS_){
_SS = SS_;
_SCK = SCK_;
_MISO = MISO_;
_MOSI = MOSI_;
byte MOSIport = digitalPinToPort(_MOSI);
byte SSport = digitalPinToPort(_SS);
byte SCKport = digitalPinToPort(_SCK);
byte MISOport = digitalPinToPort(_MISO);
if ((MOSIport == NOT_A_PIN) ||
( SSport == NOT_A_PIN) ||
( SCKport == NOT_A_PIN) ||
(MISOport == NOT_A_PIN) ){
end();
} else {
_running = true;
pinMode(_MOSI, OUTPUT);
pinMode(_MISO, INPUT);
pinMode(_SCK, OUTPUT);
pinMode(_SS, OUTPUT);
_MOSI_PORT = portOutputRegister(MOSIport);
_MOSI_HIGH = digitalPinToBitMask(_MOSI);
_MOSI_LOW = ~_MOSI_HIGH;
_SCK_PORT = portOutputRegister(SCKport);
_SCK_HIGH = digitalPinToBitMask(_SCK);
_SCK_LOW = ~_SCK_HIGH;
_SS_PORT = portOutputRegister(SSport);
_SS_HIGH = digitalPinToBitMask(_SS);
_SS_LOW = ~_SS_HIGH;
_MISO_PIN = portInputRegister(MISOport);
_MISO_MASK = digitalPinToBitMask(_MISO);
*_SS_PORT |= _SS_HIGH;
*_SCK_PORT &= _SCK_LOW;
*_MOSI_PORT &= _MOSI_LOW;
//Default to Mode0.
_mode = SPI_MODE0;
transferType = &SoftSPIClass::transferMode0;
}
}
byte SoftSPIClass::noTransfer(byte _data){
//This does nothing. If you call SPI.transfer() before calling begin() or after calling end(), the call will be redirected here to avoid crash.
return 0xFF;
}
byte SoftSPIClass::transferMode0(byte _data){
byte _newData = 0;
for (byte i = 0;i < 8; i++){
if(_data & 0x80){
*_MOSI_PORT |= _MOSI_HIGH;
} else {
*_MOSI_PORT &= _MOSI_LOW;
}
_data <<= 1;
*_SCK_PORT |= _SCK_HIGH;
_newData <<= 1;
_newData |= ((*_MISO_PIN & _MISO_MASK) ? 1 : 0);
*_SCK_PORT &= _SCK_LOW;
}
return _newData;
}
byte SoftSPIClass::transferMode1(byte _data){
byte _newData = 0;
for (byte i = 0;i < 8; i++){
*_SCK_PORT |= _SCK_HIGH;
if(_data & 0x80){
*_MOSI_PORT |= _MOSI_HIGH;
} else {
*_MOSI_PORT &= _MOSI_LOW;
}
_data <<= 1;
*_SCK_PORT &= _SCK_LOW;
_newData <<= 1;
_newData |= ((*_MISO_PIN & _MISO_MASK) ? 1 : 0);
}
return _newData;
}
byte SoftSPIClass::transferMode2(byte _data){
byte _newData = 0;
for (byte i = 0;i < 8; i++){
if(_data & 0x80){
*_MOSI_PORT |= _MOSI_HIGH;
} else {
*_MOSI_PORT &= _MOSI_LOW;
}
_data <<= 1;
*_SCK_PORT &= _SCK_LOW;
_newData <<= 1;
_newData |= ((*_MISO_PIN & _MISO_MASK) ? 1 : 0);
*_SCK_PORT |= _SCK_HIGH;
}
return _newData;
}
byte SoftSPIClass::transferMode3(byte _data){
byte _newData = 0;
for (byte i = 0;i < 8; i++){
*_SCK_PORT &= _SCK_LOW;
if(_data & 0x80){
*_MOSI_PORT |= _MOSI_HIGH;
} else {
*_MOSI_PORT &= _MOSI_LOW;
}
_data <<= 1;
*_SCK_PORT |= _SCK_HIGH;
_newData <<= 1;
_newData |= ((*_MISO_PIN & _MISO_MASK) ? 1 : 0);
}
return _newData;
}
byte SoftSPIClass::transfer(byte _data){
byte _newData = 0;
byte oldSREG = SREG;
cli();
if (_bitOrder == MSBFIRST){
//Send data
_newData = (*this.*transferType)(_data);
SREG = oldSREG;
return _newData;
} else {
//flip the data
for(byte i = 0; i < 8; i++){
_newData <<= 1;
_newData |= _data & 1;
_data >>= 1;
}
//SPI transfer
_newData = (*this.*transferType)(_newData);
SREG = oldSREG;
//flip data back.
_data = 0;
for(byte i = 0; i < 8; i++){
_data <<= 1;
_data |= _newData & 1;
_newData >>= 1;
}
return _data;
}
}
void SoftSPIClass::end(){
_running = false;
transferType = &SoftSPIClass::noTransfer;
}
void SoftSPIClass::setBitOrder(uint8_t bitOrder) {
_bitOrder = bitOrder;
}
void SoftSPIClass::setDataMode(uint8_t mode)
{
_mode = mode;
if(_mode == SPI_MODE0){
transferType = &SoftSPIClass::transferMode0;
} else if (_mode == SPI_MODE1){
transferType = &SoftSPIClass::transferMode1;
} else if (_mode == SPI_MODE2){
transferType = &SoftSPIClass::transferMode2;
} else if (_mode == SPI_MODE3){
transferType = &SoftSPIClass::transferMode3;
} else {
_mode = SPI_MODE0;
transferType = &SoftSPIClass::transferMode0;
}
if(_mode & 0x02){
*_SCK_PORT |= _SCK_HIGH;
} else {
*_SCK_PORT &= _SCK_LOW;
}
}
void SoftSPIClass::setClockDivider(uint8_t rate)
{
//does nothing as the speed cannot be changed - fixed at Fcpu/16
}
SoftSPIClass SPI;

View File

@@ -0,0 +1,83 @@
/*
* Copyright (c) 2012 by Thomas Carpenter
* Software based SPI Master Library for Tiny core.
*
* This file is free software; you can redistribute it and/or modify
* it under the terms of either the GNU General Public License version 2
* or the GNU Lesser General Public License version 2.1, both as
* published by the Free Software Foundation.
*/
#ifndef _SPI_H_INCLUDED
//Uses the same guard as the SPI class as the two cannot be used together
#define _SPI_H_INCLUDED
#include <stdio.h>
#include <Arduino.h>
#define SPI_MODE0 0
#define SPI_MODE1 1
#define SPI_MODE2 2
#define SPI_MODE3 3
#define SPI_CLOCK_DIV4 0x00
#define SPI_CLOCK_DIV16 0x01
#define SPI_CLOCK_DIV64 0x02
#define SPI_CLOCK_DIV128 0x03
#define SPI_CLOCK_DIV2 0x04
#define SPI_CLOCK_DIV8 0x05
#define SPI_CLOCK_DIV32 0x06
class SoftSPIClass;
typedef byte (SoftSPIClass::*TransferFunction)(byte _data);
class SoftSPIClass {
public:
SoftSPIClass();
private:
TransferFunction transferType;
byte noTransfer(byte _data);
byte transferMode0(byte _data);
byte transferMode1(byte _data);
byte transferMode2(byte _data);
byte transferMode3(byte _data);
public:
byte transfer(byte _data);
// SPI Configuration methods
#if defined(SS) && defined(MOSI) && defined(MISO) && defined(SCK)
void begin(); // Default to the preset SPI pins
#endif
void begin(byte SCK_, byte MOSI_, byte MISO_, byte SS_); //No SS specified, so require pin designation
void end();
void setBitOrder(uint8_t);
void setDataMode(uint8_t);
void setClockDivider(uint8_t);
void writeSS(boolean state);
private:
byte _rate;
byte _bitOrder;
byte _mode;
boolean _running;
byte _SS;
byte _SCK;
byte _MISO;
byte _MOSI;
volatile uint8_t* _MOSI_PORT;
volatile uint8_t* _SS_PORT;
volatile uint8_t* _SCK_PORT;
volatile uint8_t* _MISO_PIN;
byte _SS_HIGH;
byte _MOSI_HIGH;
byte _SCK_HIGH;
byte _SS_LOW;
byte _MOSI_LOW;
byte _SCK_LOW;
byte _MISO_MASK;
};
extern SoftSPIClass SPI;
#endif

View File

@@ -0,0 +1,266 @@
/*
TinySoftwareSerial.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
*/
#include <stdlib.h>
#include <stdio.h>
#include <string.h>
#include <inttypes.h>
#include "Arduino.h"
#include "wiring_private.h"
#if USE_SOFTWARE_SERIAL
#include "TinySoftwareSerial.h"
// Define constants and variables for buffering incoming serial data. We're
// using a ring buffer (I think), in which rx_buffer_head is the index of the
// location to which to write the next incoming character and rx_buffer_tail
// is the index of the location from which to read.
extern "C"{
uint8_t getch() {
uint8_t ch = 0;
__asm__ __volatile__ (
" rcall uartDelay\n" // Get to 0.25 of start bit (our baud is too fast, so give room to correct)
"1: rcall uartDelay\n" // Wait 0.25 bit period
" rcall uartDelay\n" // Wait 0.25 bit period
" rcall uartDelay\n" // Wait 0.25 bit period
" rcall uartDelay\n" // Wait 0.25 bit period
" clc\n"
" in r23,%[pin]\n"
" and r23, %[mask]\n"
" breq 2f\n"
" sec\n"
"2: ror %0\n"
" dec %[count]\n"
" breq 3f\n"
" rjmp 1b\n"
"3: rcall uartDelay\n" // Wait 0.25 bit period
" rcall uartDelay\n" // Wait 0.25 bit period
:
"=r" (ch)
:
"0" ((uint8_t)0),
[count] "r" ((uint8_t)8),
[pin] "I" (_SFR_IO_ADDR(ANALOG_COMP_PIN)),
[mask] "r" (Serial._rxmask)
:
"r23",
"r24",
"r25"
);
return ch;
}
void uartDelay() {
__asm__ __volatile__ (
"mov r25,%[count]\n"
"1:dec r25\n"
"brne 1b\n"
"ret\n"
::[count] "r" ((uint8_t)Serial._delayCount)
);
}
#if !defined (ANALOG_COMP_vect) && defined(ANA_COMP_vect)
//rename the vector so we can use it.
#define ANALOG_COMP_vect ANA_COMP_vect
#elif !defined (ANALOG_COMP_vect)
#error Tiny Software Serial cant find the Analog comparator interrupt vector!
#endif
ISR(ANALOG_COMP_vect){
char ch = getch(); //read in the character softwarily - I know its not a word, but it sounded cool, so you know what: #define softwarily 1
store_char(ch, Serial._rx_buffer);
sbi(ACSR,ACI); //clear the flag.
}
}
soft_ring_buffer rx_buffer = { { 0 }, 0, 0 };
// Constructor ////////////////////////////////////////////////////////////////
TinySoftwareSerial::TinySoftwareSerial(soft_ring_buffer *rx_buffer, uint8_t txBit, uint8_t rxBit)
{
_rx_buffer = rx_buffer;
_rxmask = _BV(rxBit);
_txmask = _BV(txBit);
_txunmask = ~_txmask;
_delayCount = 0;
}
// Public Methods //////////////////////////////////////////////////////////////
void TinySoftwareSerial::begin(long baud)
{
long tempDelay = (((F_CPU/baud)-39)/12);
if ((tempDelay > 255) || (tempDelay <= 0)){
end(); //Cannot start as it would screw up uartDelay().
}
_delayCount = (uint8_t)tempDelay;
cbi(ACSR,ACIE); //turn off the comparator interrupt to allow change of ACD
#ifdef ACBG
sbi(ACSR,ACBG); //enable the internal bandgap reference - used instead of AIN0 to allow it to be used for TX.
#endif
cbi(ACSR,ACD); //turn on the comparator for RX
#ifdef ACIC
cbi(ACSR,ACIC); //prevent the comparator from affecting timer1 - just to be safe.
#endif
sbi(ACSR,ACIS1); //interrupt on rising edge (this means RX has gone from Mark state to Start bit state).
sbi(ACSR,ACIS0);
//Setup the pins in case someone messed with them.
ANALOG_COMP_DDR &= ~_rxmask; //set RX to an input
ANALOG_COMP_PORT |= _rxmask; //enable pullup on RX pin - to prevent accidental interrupt triggers.
ANALOG_COMP_DDR |= _txmask; //set TX to an output.
ANALOG_COMP_PORT |= _txmask; //set TX pin high
sbi(ACSR,ACI); //clear the flag.
sbi(ACSR,ACIE); //turn on the comparator interrupt to allow us to use it for RX
#ifdef ACSRB
ACSRB = 0; //Use AIN0 as +, AIN1 as -, no hysteresis - just like ones without this register.
#endif
}
void TinySoftwareSerial::end()
{
sbi(ACSR,ACI); //clear the flag.
cbi(ACSR,ACIE); //turn off the comparator interrupt to allow change of ACD, and because it needs to be turned off now too!
#ifdef ACBG
cbi(ACSR,ACBG); //disable the bandgap reference
#endif
sbi(ACSR,ACD); //turn off the comparator to save power
_delayCount = 0;
_rx_buffer->head = _rx_buffer->tail;
}
int TinySoftwareSerial::available(void)
{
return (unsigned int)(SERIAL_BUFFER_SIZE + _rx_buffer->head - _rx_buffer->tail) % SERIAL_BUFFER_SIZE;
}
void store_char(unsigned char c, soft_ring_buffer *buffer)
{
int i = (unsigned int)(buffer->head + 1) % SERIAL_BUFFER_SIZE;
// if we should be storing the received character into the location
// just before the tail (meaning that the head would advance to the
// current location of the tail), we're about to overflow the buffer
// and so we don't write the character or advance the head.
if (i != buffer->tail) {
buffer->buffer[buffer->head] = c;
buffer->head = i;
}
}
int TinySoftwareSerial::peek(void)
{
if (_rx_buffer->head == _rx_buffer->tail) {
return -1;
} else {
return _rx_buffer->buffer[_rx_buffer->tail];
}
}
int TinySoftwareSerial::read(void)
{
// if the head isn't ahead of the tail, we don't have any characters
if (_rx_buffer->head == _rx_buffer->tail) {
return -1;
} else {
unsigned char c = _rx_buffer->buffer[_rx_buffer->tail];
_rx_buffer->tail = (unsigned int)(_rx_buffer->tail + 1) % SERIAL_BUFFER_SIZE;
return c;
}
}
size_t TinySoftwareSerial::write(uint8_t ch)
{
uint8_t oldSREG = SREG;
cli(); //Prevent interrupts from breaking the transmission. Note: TinySoftwareSerial is half duplex.
//it can either recieve or send, not both (because recieving requires an interrupt and would stall transmission
__asm__ __volatile__ (
" com %[ch]\n" // ones complement, carry set
" sec\n"
"1: brcc 2f\n"
" in r23,%[uartPort] \n"
" and r23,%[uartUnmask]\n"
" out %[uartPort],r23 \n"
" rjmp 3f\n"
"2: in r23,%[uartPort] \n"
" or r23,%[uartMask]\n"
" out %[uartPort],r23 \n"
" nop\n"
"3: rcall uartDelay\n"
" rcall uartDelay\n"
" rcall uartDelay\n"
" rcall uartDelay\n"
" lsr %[ch]\n"
" dec %[count]\n"
" brne 1b\n"
:
:
[ch] "r" (ch),
[count] "r" ((uint8_t)10),
[uartPort] "I" (_SFR_IO_ADDR(ANALOG_COMP_PORT)),
[uartMask] "r" (_txmask),
[uartUnmask] "r" (_txunmask)
: "r23",
"r24",
"r25"
);
SREG = oldSREG;
return 1;
}
void TinySoftwareSerial::flush()
{
}
TinySoftwareSerial::operator bool() {
return true;
}
// Preinstantiate Objects //////////////////////////////////////////////////////
#ifndef ANALOG_COMP_DDR
#error Please define ANALOG_COMP_DDR in the pins_arduino.h file!
#endif
#ifndef ANALOG_COMP_PORT
#error Please define ANALOG_COMP_PORT in the pins_arduino.h file!
#endif
#ifndef ANALOG_COMP_PIN
#error Please define ANALOG_COMP_PIN in the pins_arduino.h file!
#endif
#ifndef ANALOG_COMP_AIN0_BIT
#error Please define ANALOG_COMP_AIN0_BIT in the pins_arduino.h file!
#endif
#ifndef ANALOG_COMP_AIN1_BIT
#error Please define ANALOG_COMP_AIN1_BIT in the pins_arduino.h file!
#endif
TinySoftwareSerial Serial(&rx_buffer, ANALOG_COMP_AIN0_BIT, ANALOG_COMP_AIN1_BIT);
#endif // whole file

View File

@@ -0,0 +1,61 @@
#if USE_SOFTWARE_SERIAL
#ifndef TinySoftwareSerial_h
#define TinySoftwareSerial_h
#include <inttypes.h>
#include "Stream.h"
#if !defined(ACSR) && defined(ACSRA)
#define ACSR ACSRA
#endif
#if (RAMEND < 250)
#define SERIAL_BUFFER_SIZE 8
#elif (RAMEND < 500)
#define SERIAL_BUFFER_SIZE 16
#elif (RAMEND < 1000)
#define SERIAL_BUFFER_SIZE 32
#else
#define SERIAL_BUFFER_SIZE 128
#endif
struct soft_ring_buffer
{
unsigned char buffer[SERIAL_BUFFER_SIZE];
int head;
int tail;
};
extern "C"{
void uartDelay() __attribute__ ((naked));
uint8_t getch();
void store_char(unsigned char c, soft_ring_buffer *buffer);
}
class TinySoftwareSerial : public Stream
{
public: //should be private but needed by extern "C" {} functions.
uint8_t _rxmask;
uint8_t _txmask;
uint8_t _txunmask;
soft_ring_buffer *_rx_buffer;
uint8_t _delayCount;
public:
TinySoftwareSerial(soft_ring_buffer *rx_buffer, uint8_t txBit, uint8_t rxBit);
void begin(long);
void end();
virtual int available(void);
virtual int peek(void);
virtual int read(void);
virtual void flush(void);
virtual size_t write(uint8_t);
using Print::write; // pull in write(str) and write(buf, size) from Print
operator bool();
};
#if (!defined(UBRRH) && !defined(UBRR0H)) || USE_SOFTWARE_SERIAL
extern TinySoftwareSerial Serial;
#endif
//extern void putch(uint8_t);
#endif
#endif

View File

@@ -0,0 +1,546 @@
/* Tone.cpp
A Tone Generator Library
Written by Brett Hagman
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
Version Modified By Date Comments
------- ----------- -------- --------
0001 B Hagman 09/08/02 Initial coding
0002 B Hagman 09/08/18 Multiple pins
0003 B Hagman 09/08/18 Moved initialization from constructor to begin()
0004 B Hagman 09/09/26 Fixed problems with ATmega8
0005 B Hagman 09/11/23 Scanned prescalars for best fit on 8 bit timers
09/11/25 Changed pin toggle method to XOR
09/11/25 Fixed timer0 from being excluded
0006 D Mellis 09/12/29 Replaced objects with functions
0007 B Cook 10/05/03 Rewritten to only work with Timer1 and support direct hardware output
0008 B Cook 10/05/03 Rewritten so the timer can be selected at compile time
0009 T Carpenter 12/08/06 Rewritten to remove requirement for all the wierd timer name creation macros.
*************************************************/
#include <avr/interrupt.h>
#include "Arduino.h"
#include "wiring_private.h"
#include "pins_arduino.h"
// timerx_toggle_count:
// > 0 - duration specified
// = 0 - stopped
// < 0 - infinitely (until stop() method called, or new play() called)
static volatile long tone_timer_toggle_count;
static volatile uint8_t *tone_timer_pin_register;
static volatile uint8_t tone_timer_pin_mask;
static uint8_t tone_pin = 255;
void tone( uint8_t _pin, unsigned int frequency, unsigned long duration )
{
if ( tone_pin == 255 )
{
/* Set the timer to power-up conditions so we start from a known state */
// Ensure the timer is in the same state as power-up
#if (TIMER_TO_USE_FOR_TONE == 0)
TCCR0B = (0<<FOC0A) | (0<<FOC0B) | (0<<WGM02) | (0<<CS02) | (0<<CS01) | (0<<CS00);
TCCR0A = (0<<COM0A1) | (0<<COM0A0) | (0<<COM0B1) | (0<<COM0B0) | (0<<WGM01) | (0<<WGM00);
// Reset the count to zero
TCNT0 = 0;
// Set the output compare registers to zero
OCR0A = 0;
OCR0B = 0;
#if defined(TIMSK)
// Disable all Timer0 interrupts
TIMSK &= ~((1<<OCIE0B) | (1<<OCIE0A) | (1<<TOIE0));
// Clear the Timer0 interrupt flags
TIFR |= ((1<<OCF0B) | (1<<OCF0A) | (1<<TOV0));
#elif defined(TIMSK1)
// Disable all Timer0 interrupts
TIMSK0 &= ~((1<<OCIE0B) | (1<<OCIE0A) | (1<<TOIE0));
// Clear the Timer0 interrupt flags
TIFR0 |= ((1<<OCF0B) | (1<<OCF0A) | (1<<TOV0));
#endif
#elif (TIMER_TO_USE_FOR_TONE == 1) && defined(TCCR1)
// Turn off Clear on Compare Match, turn off PWM A, disconnect the timer from the output pin, stop the clock
TCCR1 = (0<<CTC1) | (0<<PWM1A) | (0<<COM1A1) | (0<<COM1A0) | (0<<CS13) | (0<<CS12) | (0<<CS11) | (0<<CS10);
// Turn off PWM A, disconnect the timer from the output pin, no Force Output Compare Match, no Prescaler Reset
GTCCR &= ~((1<<PWM1B) | (1<<COM1B1) | (1<<COM1B0) | (1<<FOC1B) | (1<<FOC1A) | (1<<PSR1));
// Reset the count to zero
TCNT1 = 0;
// Set the output compare registers to zero
OCR1A = 0;
OCR1B = 0;
OCR1C = 0;
// Disable all Timer1 interrupts
TIMSK &= ~((1<<OCIE1A) | (1<<OCIE1B) | (1<<TOIE1));
// Clear the Timer1 interrupt flags
TIFR |= ((1<<OCF1A) | (1<<OCF1B) | (1<<TOV1));
#elif (TIMER_TO_USE_FOR_TONE == 1) && defined(TCCR1E)
TCCR1A = 0;
TCCR1B = 0;
TCCR1C = 0;
TCCR1D = 0;
TCCR1E = 0;
// Reset the count to zero
TCNT1 = 0;
// Set the output compare registers to zero
OCR1A = 0;
OCR1B = 0;
// Disable all Timer1 interrupts
TIMSK &= ~((1<<TOIE1) | (1<<OCIE1A) | (1<<OCIE1B) | (1<<OCIE1D));
// Clear the Timer1 interrupt flags
TIFR |= ((1<<TOV1) | (1<<OCF1A) | (1<<OCF1B) | (1<<OCF1D));
#elif (TIMER_TO_USE_FOR_TONE == 1)
// Turn off Input Capture Noise Canceler, Input Capture Edge Select on Falling, stop the clock
TCCR1B = (0<<ICNC1) | (0<<ICES1) | (0<<WGM13) | (0<<WGM12) | (0<<CS12) | (0<<CS11) | (0<<CS10);
// Disconnect the timer from the output pins, Set Waveform Generation Mode to Normal
TCCR1A = (0<<COM1A1) | (0<<COM1A0) | (0<<COM1B1) | (0<<COM1B0) | (0<<WGM11) | (0<<WGM10);
// Reset the count to zero
TCNT1 = 0;
// Set the output compare registers to zero
OCR1A = 0;
OCR1B = 0;
// Disable all Timer1 interrupts
#if defined(TIMSK)
TIMSK &= ~((1<<TOIE1) | (1<<OCIE1A) | (1<<OCIE1B) | (1<<ICIE1));
// Clear the Timer1 interrupt flags
TIFR |= ((1<<TOV1) | (1<<OCF1A) | (1<<OCF1B) | (1<<ICF1));
#elif defined(TIMSK1)
// Disable all Timer1 interrupts
TIMSK1 &= ~((1<<TOIE1) | (1<<OCIE1A) | (1<<OCIE1B) | (1<<ICIE1));
// Clear the Timer1 interrupt flags
TIFR1 |= ((1<<TOV1) | (1<<OCF1A) | (1<<OCF1B) | (1<<ICF1));
#endif
#endif
/*
Compare Output Mode = Normal port operation, OCxA/OCxB disconnected.
Waveform Generation Mode = 4; 0100; CTC; (Clear Timer on Compare); OCR1A; Immediate; MAX
Clock Select = No clock source (Timer/Counter stopped).
Note: Turn off the clock first to avoid ticks and scratches.
*/
#if TIMER_TO_USE_FOR_TONE == 1
#if defined(TCCR1)
sbi(TCCR1,CTC1);
cbi(TCCR1,PWM1A);
cbi(GTCCR,PWM1B);
#elif !defined(TCCR1E)
cbi(TCCR1A,WGM10);
cbi(TCCR1A,WGM11);
sbi(TCCR1B,WGM12);
cbi(TCCR1B,WGM13);
#endif
#elif TIMER_TO_USE_FOR_TONE == 0
cbi(TCCR0A,WGM00);
sbi(TCCR0A,WGM01);
cbi(TCCR0B,WGM02);
#endif
/* If the tone pin can be driven directly from the timer */
#if (TIMER_TO_USE_FOR_TONE == 1) && defined(TCCR1E)
if ( (digitalPinToTimer(_pin) == TIMER1A) || (digitalPinToTimer(_pin) == TIMER1B) || (digitalPinToTimer(_pin) == TIMER1D) )
{
#elif (TIMER_TO_USE_FOR_TONE == 1)
if ( (digitalPinToTimer(_pin) == TIMER1A) || (digitalPinToTimer(_pin) == TIMER1B) )
{
#elif (TIMER_TO_USE_FOR_TONE == 0)
if ( (digitalPinToTimer(_pin) == TIMER0A) || (digitalPinToTimer(_pin) == TIMER0B) )
{
#else
if (0)
{ //unsupported, so only use software.
#endif
/* Pin toggling is handled by the hardware */
tone_timer_pin_register = NULL;
tone_timer_pin_mask = 0;
uint8_t timer = digitalPinToTimer(_pin);
#if defined(COM0A1)
//Just in case there are now pwm pins on timer0 (ATTiny861)
if (timer == TIMER0A)
{
/* Compare Output Mode = Toggle OC0A on Compare Match. */
cbi(TCCR0A,COM0A1);
sbi(TCCR0A,COM0A0);
}
else
#endif
if (timer == TIMER1A)
{
/* Compare Output Mode = Toggle OC1A on Compare Match. */
#if defined(TCCR1)
cbi(TCCR1,COM1A1);
sbi(TCCR1,COM1A0);
#elif defined(TCCR1E)
cbi(TCCR1C,COM1A1S);
sbi(TCCR1C,COM1A0S);
#else
cbi(TCCR1A,COM1A1);
sbi(TCCR1A,COM1A0);
#endif
}
#if defined(COM0B1)
//Just in case there are <2 pwm pins on timer0 (ATTiny861)
else if (timer == TIMER0B)
{
/* Compare Output Mode = Toggle OC0B on Compare Match. */
cbi(TCCR0A,COM0B1);
sbi(TCCR0A,COM0B0);
}
#endif
#if defined(COM1D1)
//in case there is a OCRD. (ATtiny861)
else if (timer == TIMER1D){
/* Compare Output Mode = Toggle OC1D on Compare Match. */
#if defined(TCCR1)
cbi(TCCR1,COM1D1);
sbi(TCCR1,COM1D0);
#elif defined(TCCR1E)
cbi(TCCR1C,COM1D1);
sbi(TCCR1C,COM1D0);
#else
cbi(TCCR1A,COM1D1);
sbi(TCCR1A,COM1D0);
#endif
}
#endif
else
{
/* Compare Output Mode = Toggle OC1B on Compare Match. */
#if defined(TCCR1)
cbi(GTCCR,COM1B1);
sbi(GTCCR,COM1B0);
#elif defined(TCCR1E)
cbi(TCCR1C,COM1B1S);
sbi(TCCR1C,COM1B0S);
#else
cbi(TCCR1A,COM1B1);
sbi(TCCR1A,COM1B0);
#endif
}
}
else
{
/* Save information needed by the interrupt service routine */
tone_timer_pin_register = portOutputRegister( digitalPinToPort( _pin ) );
tone_timer_pin_mask = digitalPinToBitMask( _pin );
/* Compare Output Mode = Normal port operation, OCxA disconnected. */
#if (TIMER_TO_USE_FOR_TONE == 0)
TCCR0A &= ~((1<<COM0A1)|(1<<COM0A0)|(1<<COM0B1)|(1<<COM0B0));
#elif (TIMER_TO_USE_FOR_TONE == 1) & defined(TCCR1)
TCCR1 &= ~((1<<COM1A1)|(1<<COM1A0));
GTCCR &= ~((1<<COM1B1)|(1<<COM1B0));
#elif (TIMER_TO_USE_FOR_TONE == 1) && defined(TCCR1E)
TCCR1C &= ~((1<<COM1A1S)|(1<<COM1A0S)|(1<<COM1B1S)|(1<<COM1B0S)|(1<<COM1D1)|(1<<COM1D0));
#elif (TIMER_TO_USE_FOR_TONE == 1)
TCCR1A &= ~((1<<COM1A1)|(1<<COM1A0)|(1<<COM1B1)|(1<<COM1B0));
#endif
}
/* Ensure the pin is configured for output */
pinMode( _pin, OUTPUT );
tone_pin = _pin;
}
if ( tone_pin == _pin )
{
/* Stop the clock while we make changes, then set the counter to zero to reduce ticks and scratches. */
// Millis timer is always processor clock divided by MillisTimer_Prescale_Value (64)
#if (TIMER_TO_USE_FOR_TONE == 0)
TCCR0B &= ~((1<<CS02)|(1<<CS01)|(1<<CS00));
TCNT0 = 0;
#elif (TIMER_TO_USE_FOR_TONE == 1) && defined(TCCR1)
TCCR1 &= ~((1<<CS13)|(1<<CS12)|(1<<CS11)|(1<<CS10));
TCNT1 = 0;
#elif (TIMER_TO_USE_FOR_TONE == 1) && defined(TCCR1E)
TCCR1B &= ~((1<<CS13)|(1<<CS12)|(1<<CS11)|(1<<CS10));
TCNT1 = 0;
#elif (TIMER_TO_USE_FOR_TONE == 1)
TCCR1B &= ~((1<<CS12)|(1<<CS11)|(1<<CS10));
TCNT1 = 0;
#endif
if ( frequency > 0 )
{
/* Determine which prescaler to use */
/* Set the Output Compare Register (rounding up) */
#if TIMER_TO_USE_FOR_TONE == 1
uint16_t ocr = F_CPU / frequency / 2;
#if defined(TCCR1E)
uint8_t prescalarbits = 0b0001;
if (ocr > 256)
{
ocr >>= 3; //divide by 8
prescalarbits = 0b0100; // ck/8
if (ocr > 256)
{
ocr >>= 3; //divide by a further 8
prescalarbits = 0b0111; //ck/64
if (ocr > 256)
{
ocr >>= 2; //divide by a further 4
prescalarbits = 0b1001; //ck/256
if (ocr > 256)
{
// can't do any better than /1024
ocr >>= 2; //divide by a further 4
prescalarbits = 0b1011; //ck/1024
}
}
}
}
#else
#if defined(TCCR1)
uint8_t prescalarbits = 0b0001;
#else
uint8_t prescalarbits = 0b001;
#endif
if (ocr > 0xffff)
{
ocr /= 64;
#if defined(TCCR1)
prescalarbits = 0b0111;
#else
prescalarbits = 0b011;
#endif
}
#endif
ocr -= 1; //Note we are doing the subtraction of 1 here to save repeatedly calculating ocr from just the frequency in the if tree above
OCR1A = ocr;
#elif TIMER_TO_USE_FOR_TONE == 0
uint16_t ocr = F_CPU / frequency / 2;
uint8_t prescalarbits = 0b001; // ck/1
if (ocr > 256)
{
ocr >>= 3; //divide by 8
prescalarbits = 0b010; // ck/8
if (ocr > 256)
{
ocr >>= 3; //divide by a further 8
prescalarbits = 0b011; //ck/64
if (ocr > 256)
{
ocr >>= 2; //divide by a further 4
prescalarbits = 0b100; //ck/256
if (ocr > 256)
{
// can't do any better than /1024
ocr >>= 2; //divide by a further 4
prescalarbits = 0b101; //ck/1024
}
}
}
}
ocr -= 1; //Note we are doing the subtraction of 1 here to save repeatedly calculating ocr from just the frequency in the if tree above
OCR0A = ocr;
#endif
/* Does the caller want a specific duration? */
if ( duration > 0 )
{
/* Determine how many times the value toggles */
tone_timer_toggle_count = (2 * frequency * duration) / 1000;
/* Output Compare A Match Interrupt Enable */
#if (TIMER_TO_USE_FOR_TONE == 1)
#if defined (TIMSK)
TIMSK |= (1<<OCIE1A);
#else
TIMSK1 |= (1<<OCIE1A);
#endif
#elif (TIMER_TO_USE_FOR_TONE == 0)
#if defined (TIMSK)
TIMSK |= (1<<OCIE0A);
#else
TIMSK0 |= (1<<OCIE0A);
#endif
#endif
}
else
{
/* Indicate to the interrupt service routine that we'll be running until further notice */
tone_timer_toggle_count = -1;
/* All pins but the OCxA / OCxB pins have to be driven by software */
#if (TIMER_TO_USE_FOR_TONE == 1)
#if defined(TCCR1E)
if ( (digitalPinToTimer(_pin) != TIMER1A) && (digitalPinToTimer(_pin) != TIMER1B) && (digitalPinToTimer(_pin) != TIMER1D) )
#else
if ( (digitalPinToTimer(_pin) != TIMER1A) && (digitalPinToTimer(_pin) != TIMER1B) )
#endif
{
/* Output Compare A Match Interrupt Enable (software control)*/
#if defined (TIMSK)
TIMSK |= (1<<OCIE1A);
#else
TIMSK1 |= (1<<OCIE1A);
#endif
}
#elif (TIMER_TO_USE_FOR_TONE == 0)
if ( (digitalPinToTimer(_pin) != TIMER0A) && (digitalPinToTimer(_pin) != TIMER0B) )
{
/* Output Compare A Match Interrupt Enable (software control)*/
#if defined (TIMSK)
TIMSK |= (1<<OCIE0A);
#else
TIMSK0 |= (1<<OCIE0A);
#endif
}
#endif
}
//Clock is always stopped before this point, which means all of CS[0..2] are already 0, so can just use a bitwise OR to set required bits
#if (TIMER_TO_USE_FOR_TONE == 0)
TCCR0B |= (prescalarbits << CS00);
#elif (TIMER_TO_USE_FOR_TONE == 1) && defined(TCCR1)
TCCR1 |= (prescalarbits << CS10);
#elif (TIMER_TO_USE_FOR_TONE == 1)
TCCR1B |= (prescalarbits << CS10);
#endif
}
else
{
/* To be on the safe side, turn off all interrupts */
#if (TIMER_TO_USE_FOR_TONE == 1)
#if defined (TIMSK)
TIMSK |= (1<<OCIE1A);
TIMSK &= ~((1<<TOIE1) | (1<<OCIE1A) | (1<<OCIE1B));
#if defined(ICIE1)
TIMSK &= ~(1<<ICIE1);
#endif
#if defined(OCIE1D)
TIMSK &= ~(1<<OCIE1D);
#endif
#else
TIMSK1 |= (1<<OCIE1A);
TIMSK1 &= ~((1<<ICIE1) | (1<<OCIE1B) | (1<<OCIE1A) | (1<<TOIE1));
#endif
#elif (TIMER_TO_USE_FOR_TONE == 0)
#if defined (TIMSK)
TIMSK |= (1<<OCIE0A);
TIMSK &= ~((1<<OCIE0B) | (1<<OCIE0A) | (1<<TOIE0));
#else
TIMSK0 |= (1<<OCIE0A);
TIMSK0 &= ~((1<<OCIE0B) | (1<<OCIE0A) | (1<<TOIE0));
#endif
#endif
/* Clock is stopped. Counter is zero. The only thing left to do is turn off the output. */
digitalWrite( _pin, 0 );
}
}
}
void noTone( uint8_t _pin )
{
if ( (tone_pin != 255)
&& ((tone_pin == _pin) || (_pin == 255)) )
{
// Turn off all interrupts
#if (TIMER_TO_USE_FOR_TONE == 1)
#if defined (TIMSK)
TIMSK &= ~((1<<TOIE1) | (1<<OCIE1A) | (1<<OCIE1B));
#if defined(ICIE1)
TIMSK &= ~(1<<ICIE1);
#endif
#if defined(OCIE1D)
TIMSK &= ~(1<<OCIE1D);
#endif
#else
TIMSK1 &= ~((1<<ICIE1) | (1<<OCIE1B) | (1<<OCIE1A) | (1<<TOIE1));
#endif
#elif (TIMER_TO_USE_FOR_TONE == 0)
#if defined (TIMSK)
TIMSK &= ~((1<<OCIE0B) | (1<<OCIE0A) | (1<<TOIE0));
#else
TIMSK0 &= ~((1<<OCIE0B) | (1<<OCIE0A) | (1<<TOIE0));
#endif
#endif
// This just disables the tone. It doesn't reinitialise the PWM modules.
#if (TIMER_TO_USE_FOR_TONE == 0)
TCCR0B &= ~((1<<CS02) | (1<<CS01) | (1<<CS00)); //stop the clock
#elif (TIMER_TO_USE_FOR_TONE == 1) && defined(TCCR1)
TCCR1 &= ~((1<<CS13) | (1<<CS12) | (1<<CS11) | (1<<CS10)); //stop the clock
#elif (TIMER_TO_USE_FOR_TONE == 1) && defined(TCCR1E)
TCCR1B &= ~((1<<CS13) | (1<<CS12) | (1<<CS11) | (1<<CS10)); //stop the clock
#elif (TIMER_TO_USE_FOR_TONE == 1)
TCCR1B &= ~((1<<CS12) | (1<<CS11) | (1<<CS10)); //stop the clock
#endif
// Set the output low
if ( tone_timer_pin_register != NULL )
{
*tone_timer_pin_register &= ~(tone_timer_pin_mask);
}
else
{
digitalWrite( tone_pin, LOW );
}
tone_pin = 255;
}
}
#if (TIMER_TO_USE_FOR_TONE == 0)
ISR(TIMER0_COMPA_vect)
#elif (TIMER_TO_USE_FOR_TONE == 1)
ISR(TIMER1_COMPA_vect)
#else
#error Tone timer Overflow vector not defined!
#endif
{
if ( tone_timer_toggle_count != 0 )
{
if ( tone_timer_toggle_count > 0 )
{
--tone_timer_toggle_count;
if ( tone_timer_toggle_count == 0 )
{
// Shutdown the hardware
noTone( 255 );
// Skip the rest. We're finished.
return;
}
}
*tone_timer_pin_register ^= tone_timer_pin_mask;
}
else
{
// Shutdown the hardware
noTone( 255 );
}
}

View File

@@ -0,0 +1,168 @@
/*
WCharacter.h - Character utility functions for Wiring & Arduino
Copyright (c) 2010 Hernando Barragan. 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 Character_h
#define Character_h
#include <ctype.h>
// WCharacter.h prototypes
inline boolean isAlphaNumeric(int c) __attribute__((always_inline));
inline boolean isAlpha(int c) __attribute__((always_inline));
inline boolean isAscii(int c) __attribute__((always_inline));
inline boolean isWhitespace(int c) __attribute__((always_inline));
inline boolean isControl(int c) __attribute__((always_inline));
inline boolean isDigit(int c) __attribute__((always_inline));
inline boolean isGraph(int c) __attribute__((always_inline));
inline boolean isLowerCase(int c) __attribute__((always_inline));
inline boolean isPrintable(int c) __attribute__((always_inline));
inline boolean isPunct(int c) __attribute__((always_inline));
inline boolean isSpace(int c) __attribute__((always_inline));
inline boolean isUpperCase(int c) __attribute__((always_inline));
inline boolean isHexadecimalDigit(int c) __attribute__((always_inline));
inline int toAscii(int c) __attribute__((always_inline));
inline int toLowerCase(int c) __attribute__((always_inline));
inline int toUpperCase(int c)__attribute__((always_inline));
// Checks for an alphanumeric character.
// It is equivalent to (isalpha(c) || isdigit(c)).
inline boolean isAlphaNumeric(int c)
{
return ( isalnum(c) == 0 ? false : true);
}
// Checks for an alphabetic character.
// It is equivalent to (isupper(c) || islower(c)).
inline boolean isAlpha(int c)
{
return ( isalpha(c) == 0 ? false : true);
}
// Checks whether c is a 7-bit unsigned char value
// that fits into the ASCII character set.
inline boolean isAscii(int c)
{
return ( isascii (c) == 0 ? false : true);
}
// Checks for a blank character, that is, a space or a tab.
inline boolean isWhitespace(int c)
{
return ( isblank (c) == 0 ? false : true);
}
// Checks for a control character.
inline boolean isControl(int c)
{
return ( iscntrl (c) == 0 ? false : true);
}
// Checks for a digit (0 through 9).
inline boolean isDigit(int c)
{
return ( isdigit (c) == 0 ? false : true);
}
// Checks for any printable character except space.
inline boolean isGraph(int c)
{
return ( isgraph (c) == 0 ? false : true);
}
// Checks for a lower-case character.
inline boolean isLowerCase(int c)
{
return (islower (c) == 0 ? false : true);
}
// Checks for any printable character including space.
inline boolean isPrintable(int c)
{
return ( isprint (c) == 0 ? false : true);
}
// Checks for any printable character which is not a space
// or an alphanumeric character.
inline boolean isPunct(int c)
{
return ( ispunct (c) == 0 ? false : true);
}
// Checks for white-space characters. For the avr-libc library,
// these are: space, formfeed ('\f'), newline ('\n'), carriage
// return ('\r'), horizontal tab ('\t'), and vertical tab ('\v').
inline boolean isSpace(int c)
{
return ( isspace (c) == 0 ? false : true);
}
// Checks for an uppercase letter.
inline boolean isUpperCase(int c)
{
return ( isupper (c) == 0 ? false : true);
}
// Checks for a hexadecimal digits, i.e. one of 0 1 2 3 4 5 6 7
// 8 9 a b c d e f A B C D E F.
inline boolean isHexadecimalDigit(int c)
{
return ( isxdigit (c) == 0 ? false : true);
}
// Converts c to a 7-bit unsigned char value that fits into the
// ASCII character set, by clearing the high-order bits.
inline int toAscii(int c)
{
return toascii (c);
}
// Warning:
// Many people will be unhappy if you use this function.
// This function will convert accented letters into random
// characters.
// Converts the letter c to lower case, if possible.
inline int toLowerCase(int c)
{
return tolower (c);
}
// Converts the letter c to upper case, if possible.
inline int toUpperCase(int c)
{
return toupper (c);
}
#endif

View File

@@ -0,0 +1,155 @@
/* -*- 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 28-08-2009 for attiny84 R.Wiersma
Modified 09-10-2009 for attiny45 A.Saporetti
Modified 20-11-2010 - B.Cook - Correct a minor bug in attachInterrupt
*/
#include <inttypes.h>
#include <avr/io.h>
#include <avr/interrupt.h>
#include <avr/pgmspace.h>
#include <stdio.h>
#include "wiring_private.h"
volatile static voidFuncPtr intFunc[NUMBER_EXTERNAL_INTERRUPTS];
#if defined( MCUCR ) && ! defined( EICRA )
#define EICRA MCUCR
#endif
#if defined( GIMSK ) && ! defined( EIMSK )
#define EIMSK GIMSK
#endif
void attachInterrupt(uint8_t interruptNum, void (*userFunc)(void), int mode)
{
if ( interruptNum < NUMBER_EXTERNAL_INTERRUPTS )
{
/*
If attachInterrupt is called in succession for the same
interruptNum but a different userFunc then the following line
is not safe. Changing intFunc is not atomic.
intFunc[interruptNum] = userFunc;
*/
{
// save interrupt flag
uint8_t SaveSREG = SREG;
// disable interrupts
cli();
// access the shared data
intFunc[interruptNum] = userFunc;
// restore the interrupt flag
SREG = SaveSREG;
}
// 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 NUMBER_EXTERNAL_INTERRUPTS >= 1
case EXTERNAL_INTERRUPT_0:
EICRA = (EICRA & ~((1 << ISC00) | (1 << ISC01))) | (mode << ISC00);
EIMSK |= (1 << INT0);
break;
#endif
#if NUMBER_EXTERNAL_INTERRUPTS >= 2 && !defined(ISC11)
//For ATtiny861, but interrupts share the same vector.
case EXTERNAL_INTERRUPT_1:
EICRA = (EICRA & ~((1 << ISC00) | (1 << ISC01))) | (mode << ISC00);
EIMSK |= (1 << INT1);
break;
#endif
#if NUMBER_EXTERNAL_INTERRUPTS >= 2 && defined(ISC11)
case EXTERNAL_INTERRUPT_1:
EICRA = (EICRA & ~((1 << ISC10) | (1 << ISC11))) | (mode << ISC10);
EIMSK |= (1 << INT1);
break;
#endif
#if NUMBER_EXTERNAL_INTERRUPTS > 2
#error Add handlers for the additional interrupts.
#endif
}
}
}
void detachInterrupt(uint8_t interruptNum)
{
if ( interruptNum < NUMBER_EXTERNAL_INTERRUPTS )
{
// Disable the interrupt. (We can't assume that interruptNum is equal
// to the number of the EIMSK bit to clear, as this isn't true on the
// ATmega8. There, INT0 is 6 and INT1 is 7.)
switch (interruptNum)
{
#if NUMBER_EXTERNAL_INTERRUPTS >= 1
case EXTERNAL_INTERRUPT_0:
EIMSK &= ~(1 << INT0);
break;;
#endif
#if NUMBER_EXTERNAL_INTERRUPTS >= 2
case EXTERNAL_INTERRUPT_1:
EIMSK &= ~(1 << INT1);
break;;
#endif
#if NUMBER_EXTERNAL_INTERRUPTS > 2
#error Add handlers for the additional interrupts.
#endif
}
intFunc[interruptNum] = 0;
}
}
#if NUMBER_EXTERNAL_INTERRUPTS >= 1
ISR(EXTERNAL_INTERRUPT_0_vect)
{
if(intFunc[EXTERNAL_INTERRUPT_0])
intFunc[EXTERNAL_INTERRUPT_0]();
}
#endif
#if NUMBER_EXTERNAL_INTERRUPTS >= 2
ISR(EXTERNAL_INTERRUPT_1_vect)
{
if(intFunc[EXTERNAL_INTERRUPT_1])
intFunc[EXTERNAL_INTERRUPT_1]();
}
#endif
#if NUMBER_EXTERNAL_INTERRUPTS > 2
#error Add handlers for the additional interrupts.
#endif

View File

@@ -0,0 +1,60 @@
/* -*- mode: jde; c-basic-offset: 2; indent-tabs-mode: nil -*- */
/*
Part of the Wiring project - http://wiring.org.co
Copyright (c) 2004-06 Hernando Barragan
Modified 13 August 2006, David A. Mellis for Arduino - http://www.arduino.cc/
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
$Id$
*/
extern "C" {
#include "stdlib.h"
}
void randomSeed(unsigned int seed)
{
if (seed != 0) {
srandom(seed);
}
}
long random(long howbig)
{
if (howbig == 0) {
return 0;
}
return random() % howbig;
}
long random(long howsmall, long howbig)
{
if (howsmall >= howbig) {
return howsmall;
}
long diff = howbig - howsmall;
return random(diff) + howsmall;
}
long map(long x, long in_min, long in_max, long out_min, long out_max)
{
return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
}
unsigned int makeWord(unsigned int w) { return w; }
unsigned int makeWord(unsigned char h, unsigned char l) { return (h << 8) | l; }

View File

@@ -0,0 +1,2 @@
//For compatibility with older programs
#include "Arduino.h"

View File

@@ -0,0 +1,744 @@
/*
WString.cpp - String library for Wiring & Arduino
...mostly rewritten by Paul Stoffregen...
Copyright (c) 2009-10 Hernando Barragan. All rights reserved.
Copyright 2011, Paul Stoffregen, paul@pjrc.com
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 "WString.h"
/*********************************************/
/* Constructors */
/*********************************************/
String::String(const char *cstr)
{
init();
if (cstr) copy(cstr, strlen(cstr));
}
String::String(const String &value)
{
init();
*this = value;
}
String::String(const __FlashStringHelper *pstr)
{
init();
*this = pstr;
}
#ifdef __GXX_EXPERIMENTAL_CXX0X__
String::String(String &&rval)
{
init();
move(rval);
}
String::String(StringSumHelper &&rval)
{
init();
move(rval);
}
#endif
String::String(char c)
{
init();
char buf[2];
buf[0] = c;
buf[1] = 0;
*this = buf;
}
String::String(unsigned char value, unsigned char base)
{
init();
char buf[1 + 8 * sizeof(unsigned char)];
utoa(value, buf, base);
*this = buf;
}
String::String(int value, unsigned char base)
{
init();
char buf[2 + 8 * sizeof(int)];
itoa(value, buf, base);
*this = buf;
}
String::String(unsigned int value, unsigned char base)
{
init();
char buf[1 + 8 * sizeof(unsigned int)];
utoa(value, buf, base);
*this = buf;
}
String::String(long value, unsigned char base)
{
init();
char buf[2 + 8 * sizeof(long)];
ltoa(value, buf, base);
*this = buf;
}
String::String(unsigned long value, unsigned char base)
{
init();
char buf[1 + 8 * sizeof(unsigned long)];
ultoa(value, buf, base);
*this = buf;
}
String::String(float value, unsigned char decimalPlaces)
{
init();
char buf[33];
*this = dtostrf(value, (decimalPlaces + 2), decimalPlaces, buf);
}
String::String(double value, unsigned char decimalPlaces)
{
init();
char buf[33];
*this = dtostrf(value, (decimalPlaces + 2), decimalPlaces, buf);
}
String::~String()
{
free(buffer);
}
/*********************************************/
/* Memory Management */
/*********************************************/
inline void String::init(void)
{
buffer = NULL;
capacity = 0;
len = 0;
}
void String::invalidate(void)
{
if (buffer) free(buffer);
buffer = NULL;
capacity = len = 0;
}
unsigned char String::reserve(unsigned int size)
{
if (buffer && capacity >= size) return 1;
if (changeBuffer(size)) {
if (len == 0) buffer[0] = 0;
return 1;
}
return 0;
}
unsigned char String::changeBuffer(unsigned int maxStrLen)
{
char *newbuffer = (char *)realloc(buffer, maxStrLen + 1);
if (newbuffer) {
buffer = newbuffer;
capacity = maxStrLen;
return 1;
}
return 0;
}
/*********************************************/
/* Copy and Move */
/*********************************************/
String & String::copy(const char *cstr, unsigned int length)
{
if (!reserve(length)) {
invalidate();
return *this;
}
len = length;
strcpy(buffer, cstr);
return *this;
}
String & String::copy(const __FlashStringHelper *pstr, unsigned int length)
{
if (!reserve(length)) {
invalidate();
return *this;
}
len = length;
strcpy_P(buffer, (PGM_P)pstr);
return *this;
}
#ifdef __GXX_EXPERIMENTAL_CXX0X__
void String::move(String &rhs)
{
if (buffer) {
if (capacity >= rhs.len) {
strcpy(buffer, rhs.buffer);
len = rhs.len;
rhs.len = 0;
return;
} else {
free(buffer);
}
}
buffer = rhs.buffer;
capacity = rhs.capacity;
len = rhs.len;
rhs.buffer = NULL;
rhs.capacity = 0;
rhs.len = 0;
}
#endif
String & String::operator = (const String &rhs)
{
if (this == &rhs) return *this;
if (rhs.buffer) copy(rhs.buffer, rhs.len);
else invalidate();
return *this;
}
#ifdef __GXX_EXPERIMENTAL_CXX0X__
String & String::operator = (String &&rval)
{
if (this != &rval) move(rval);
return *this;
}
String & String::operator = (StringSumHelper &&rval)
{
if (this != &rval) move(rval);
return *this;
}
#endif
String & String::operator = (const char *cstr)
{
if (cstr) copy(cstr, strlen(cstr));
else invalidate();
return *this;
}
String & String::operator = (const __FlashStringHelper *pstr)
{
if (pstr) copy(pstr, strlen_P((PGM_P)pstr));
else invalidate();
return *this;
}
/*********************************************/
/* concat */
/*********************************************/
unsigned char String::concat(const String &s)
{
return concat(s.buffer, s.len);
}
unsigned char String::concat(const char *cstr, unsigned int length)
{
unsigned int newlen = len + length;
if (!cstr) return 0;
if (length == 0) return 1;
if (!reserve(newlen)) return 0;
strcpy(buffer + len, cstr);
len = newlen;
return 1;
}
unsigned char String::concat(const char *cstr)
{
if (!cstr) return 0;
return concat(cstr, strlen(cstr));
}
unsigned char String::concat(char c)
{
char buf[2];
buf[0] = c;
buf[1] = 0;
return concat(buf, 1);
}
unsigned char String::concat(unsigned char num)
{
char buf[1 + 3 * sizeof(unsigned char)];
itoa(num, buf, 10);
return concat(buf, strlen(buf));
}
unsigned char String::concat(int num)
{
char buf[2 + 3 * sizeof(int)];
itoa(num, buf, 10);
return concat(buf, strlen(buf));
}
unsigned char String::concat(unsigned int num)
{
char buf[1 + 3 * sizeof(unsigned int)];
utoa(num, buf, 10);
return concat(buf, strlen(buf));
}
unsigned char String::concat(long num)
{
char buf[2 + 3 * sizeof(long)];
ltoa(num, buf, 10);
return concat(buf, strlen(buf));
}
unsigned char String::concat(unsigned long num)
{
char buf[1 + 3 * sizeof(unsigned long)];
ultoa(num, buf, 10);
return concat(buf, strlen(buf));
}
unsigned char String::concat(float num)
{
char buf[20];
char* string = dtostrf(num, 4, 2, buf);
return concat(string, strlen(string));
}
unsigned char String::concat(double num)
{
char buf[20];
char* string = dtostrf(num, 4, 2, buf);
return concat(string, strlen(string));
}
unsigned char String::concat(const __FlashStringHelper * str)
{
if (!str) return 0;
int length = strlen_P((const char *) str);
if (length == 0) return 1;
unsigned int newlen = len + length;
if (!reserve(newlen)) return 0;
strcpy_P(buffer + len, (const char *) str);
len = newlen;
return 1;
}
/*********************************************/
/* Concatenate */
/*********************************************/
StringSumHelper & operator + (const StringSumHelper &lhs, const String &rhs)
{
StringSumHelper &a = const_cast<StringSumHelper&>(lhs);
if (!a.concat(rhs.buffer, rhs.len)) a.invalidate();
return a;
}
StringSumHelper & operator + (const StringSumHelper &lhs, const char *cstr)
{
StringSumHelper &a = const_cast<StringSumHelper&>(lhs);
if (!cstr || !a.concat(cstr, strlen(cstr))) a.invalidate();
return a;
}
StringSumHelper & operator + (const StringSumHelper &lhs, char c)
{
StringSumHelper &a = const_cast<StringSumHelper&>(lhs);
if (!a.concat(c)) a.invalidate();
return a;
}
StringSumHelper & operator + (const StringSumHelper &lhs, unsigned char num)
{
StringSumHelper &a = const_cast<StringSumHelper&>(lhs);
if (!a.concat(num)) a.invalidate();
return a;
}
StringSumHelper & operator + (const StringSumHelper &lhs, int num)
{
StringSumHelper &a = const_cast<StringSumHelper&>(lhs);
if (!a.concat(num)) a.invalidate();
return a;
}
StringSumHelper & operator + (const StringSumHelper &lhs, unsigned int num)
{
StringSumHelper &a = const_cast<StringSumHelper&>(lhs);
if (!a.concat(num)) a.invalidate();
return a;
}
StringSumHelper & operator + (const StringSumHelper &lhs, long num)
{
StringSumHelper &a = const_cast<StringSumHelper&>(lhs);
if (!a.concat(num)) a.invalidate();
return a;
}
StringSumHelper & operator + (const StringSumHelper &lhs, unsigned long num)
{
StringSumHelper &a = const_cast<StringSumHelper&>(lhs);
if (!a.concat(num)) a.invalidate();
return a;
}
StringSumHelper & operator + (const StringSumHelper &lhs, float num)
{
StringSumHelper &a = const_cast<StringSumHelper&>(lhs);
if (!a.concat(num)) a.invalidate();
return a;
}
StringSumHelper & operator + (const StringSumHelper &lhs, double num)
{
StringSumHelper &a = const_cast<StringSumHelper&>(lhs);
if (!a.concat(num)) a.invalidate();
return a;
}
StringSumHelper & operator + (const StringSumHelper &lhs, const __FlashStringHelper *rhs)
{
StringSumHelper &a = const_cast<StringSumHelper&>(lhs);
if (!a.concat(rhs)) a.invalidate();
return a;
}
/*********************************************/
/* Comparison */
/*********************************************/
int String::compareTo(const String &s) const
{
if (!buffer || !s.buffer) {
if (s.buffer && s.len > 0) return 0 - *(unsigned char *)s.buffer;
if (buffer && len > 0) return *(unsigned char *)buffer;
return 0;
}
return strcmp(buffer, s.buffer);
}
unsigned char String::equals(const String &s2) const
{
return (len == s2.len && compareTo(s2) == 0);
}
unsigned char String::equals(const char *cstr) const
{
if (len == 0) return (cstr == NULL || *cstr == 0);
if (cstr == NULL) return buffer[0] == 0;
return strcmp(buffer, cstr) == 0;
}
unsigned char String::operator<(const String &rhs) const
{
return compareTo(rhs) < 0;
}
unsigned char String::operator>(const String &rhs) const
{
return compareTo(rhs) > 0;
}
unsigned char String::operator<=(const String &rhs) const
{
return compareTo(rhs) <= 0;
}
unsigned char String::operator>=(const String &rhs) const
{
return compareTo(rhs) >= 0;
}
unsigned char String::equalsIgnoreCase( const String &s2 ) const
{
if (this == &s2) return 1;
if (len != s2.len) return 0;
if (len == 0) return 1;
const char *p1 = buffer;
const char *p2 = s2.buffer;
while (*p1) {
if (tolower(*p1++) != tolower(*p2++)) return 0;
}
return 1;
}
unsigned char String::startsWith( const String &s2 ) const
{
if (len < s2.len) return 0;
return startsWith(s2, 0);
}
unsigned char String::startsWith( const String &s2, unsigned int offset ) const
{
if (offset > len - s2.len || !buffer || !s2.buffer) return 0;
return strncmp( &buffer[offset], s2.buffer, s2.len ) == 0;
}
unsigned char String::endsWith( const String &s2 ) const
{
if ( len < s2.len || !buffer || !s2.buffer) return 0;
return strcmp(&buffer[len - s2.len], s2.buffer) == 0;
}
/*********************************************/
/* Character Access */
/*********************************************/
char String::charAt(unsigned int loc) const
{
return operator[](loc);
}
void String::setCharAt(unsigned int loc, char c)
{
if (loc < len) buffer[loc] = c;
}
char & String::operator[](unsigned int index)
{
static char dummy_writable_char;
if (index >= len || !buffer) {
dummy_writable_char = 0;
return dummy_writable_char;
}
return buffer[index];
}
char String::operator[]( unsigned int index ) const
{
if (index >= len || !buffer) return 0;
return buffer[index];
}
void String::getBytes(unsigned char *buf, unsigned int bufsize, unsigned int index) const
{
if (!bufsize || !buf) return;
if (index >= len) {
buf[0] = 0;
return;
}
unsigned int n = bufsize - 1;
if (n > len - index) n = len - index;
strncpy((char *)buf, buffer + index, n);
buf[n] = 0;
}
/*********************************************/
/* Search */
/*********************************************/
int String::indexOf(char c) const
{
return indexOf(c, 0);
}
int String::indexOf( char ch, unsigned int fromIndex ) const
{
if (fromIndex >= len) return -1;
const char* temp = strchr(buffer + fromIndex, ch);
if (temp == NULL) return -1;
return temp - buffer;
}
int String::indexOf(const String &s2) const
{
return indexOf(s2, 0);
}
int String::indexOf(const String &s2, unsigned int fromIndex) const
{
if (fromIndex >= len) return -1;
const char *found = strstr(buffer + fromIndex, s2.buffer);
if (found == NULL) return -1;
return found - buffer;
}
int String::lastIndexOf( char theChar ) const
{
return lastIndexOf(theChar, len - 1);
}
int String::lastIndexOf(char ch, unsigned int fromIndex) const
{
if (fromIndex >= len) return -1;
char tempchar = buffer[fromIndex + 1];
buffer[fromIndex + 1] = '\0';
char* temp = strrchr( buffer, ch );
buffer[fromIndex + 1] = tempchar;
if (temp == NULL) return -1;
return temp - buffer;
}
int String::lastIndexOf(const String &s2) const
{
return lastIndexOf(s2, len - s2.len);
}
int String::lastIndexOf(const String &s2, unsigned int fromIndex) const
{
if (s2.len == 0 || len == 0 || s2.len > len) return -1;
if (fromIndex >= len) fromIndex = len - 1;
int found = -1;
for (char *p = buffer; p <= buffer + fromIndex; p++) {
p = strstr(p, s2.buffer);
if (!p) break;
if ((unsigned int)(p - buffer) <= fromIndex) found = p - buffer;
}
return found;
}
String String::substring(unsigned int left, unsigned int right) const
{
if (left > right) {
unsigned int temp = right;
right = left;
left = temp;
}
String out;
if (left > len) return out;
if (right > len) right = len;
char temp = buffer[right]; // save the replaced character
buffer[right] = '\0';
out = buffer + left; // pointer arithmetic
buffer[right] = temp; //restore character
return out;
}
/*********************************************/
/* Modification */
/*********************************************/
void String::replace(char find, char replace)
{
if (!buffer) return;
for (char *p = buffer; *p; p++) {
if (*p == find) *p = replace;
}
}
void String::replace(const String& find, const String& replace)
{
if (len == 0 || find.len == 0) return;
int diff = replace.len - find.len;
char *readFrom = buffer;
char *foundAt;
if (diff == 0) {
while ((foundAt = strstr(readFrom, find.buffer)) != NULL) {
memcpy(foundAt, replace.buffer, replace.len);
readFrom = foundAt + replace.len;
}
} else if (diff < 0) {
char *writeTo = buffer;
while ((foundAt = strstr(readFrom, find.buffer)) != NULL) {
unsigned int n = foundAt - readFrom;
memcpy(writeTo, readFrom, n);
writeTo += n;
memcpy(writeTo, replace.buffer, replace.len);
writeTo += replace.len;
readFrom = foundAt + find.len;
len += diff;
}
strcpy(writeTo, readFrom);
} else {
unsigned int size = len; // compute size needed for result
while ((foundAt = strstr(readFrom, find.buffer)) != NULL) {
readFrom = foundAt + find.len;
size += diff;
}
if (size == len) return;
if (size > capacity && !changeBuffer(size)) return; // XXX: tell user!
int index = len - 1;
while (index >= 0 && (index = lastIndexOf(find, index)) >= 0) {
readFrom = buffer + index + find.len;
memmove(readFrom + diff, readFrom, len - (readFrom - buffer));
len += diff;
buffer[len] = 0;
memcpy(buffer + index, replace.buffer, replace.len);
index--;
}
}
}
void String::remove(unsigned int index){
if (index >= len) { return; }
int count = len - index;
remove(index, count);
}
void String::remove(unsigned int index, unsigned int count){
if (index >= len) { return; }
if (count <= 0) { return; }
if (index + count > len) { count = len - index; }
char *writeTo = buffer + index;
len = len - count;
strncpy(writeTo, buffer + index + count,len - index);
buffer[len] = 0;
}
void String::toLowerCase(void)
{
if (!buffer) return;
for (char *p = buffer; *p; p++) {
*p = tolower(*p);
}
}
void String::toUpperCase(void)
{
if (!buffer) return;
for (char *p = buffer; *p; p++) {
*p = toupper(*p);
}
}
void String::trim(void)
{
if (!buffer || len == 0) return;
char *begin = buffer;
while (isspace(*begin)) begin++;
char *end = buffer + len - 1;
while (isspace(*end) && end >= begin) end--;
len = end + 1 - begin;
if (begin > buffer) memcpy(buffer, begin, len);
buffer[len] = 0;
}
/*********************************************/
/* Parsing / Conversion */
/*********************************************/
long String::toInt(void) const
{
if (buffer) return atol(buffer);
return 0;
}
float String::toFloat(void) const
{
if (buffer) return float(atof(buffer));
return 0;
}

View File

@@ -0,0 +1,224 @@
/*
WString.h - String library for Wiring & Arduino
...mostly rewritten by Paul Stoffregen...
Copyright (c) 2009-10 Hernando Barragan. All right reserved.
Copyright 2011, Paul Stoffregen, paul@pjrc.com
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 String_class_h
#define String_class_h
#ifdef __cplusplus
#include <stdlib.h>
#include <string.h>
#include <ctype.h>
#include <avr/pgmspace.h>
// When compiling programs with this class, the following gcc parameters
// dramatically increase performance and memory (RAM) efficiency, typically
// with little or no increase in code size.
// -felide-constructors
// -std=c++0x
class __FlashStringHelper;
#define F(string_literal) (reinterpret_cast<const __FlashStringHelper *>(PSTR(string_literal)))
// An inherited class for holding the result of a concatenation. These
// result objects are assumed to be writable by subsequent concatenations.
class StringSumHelper;
// The string class
class String
{
// use a function pointer to allow for "if (s)" without the
// complications of an operator bool(). for more information, see:
// http://www.artima.com/cppsource/safebool.html
typedef void (String::*StringIfHelperType)() const;
void StringIfHelper() const {}
public:
// constructors
// creates a copy of the initial value.
// if the initial value is null or invalid, or if memory allocation
// fails, the string will be marked as invalid (i.e. "if (s)" will
// be false).
String(const char *cstr = "");
String(const String &str);
String(const __FlashStringHelper *str);
#ifdef __GXX_EXPERIMENTAL_CXX0X__
String(String &&rval);
String(StringSumHelper &&rval);
#endif
explicit String(char c);
explicit String(unsigned char, unsigned char base=10);
explicit String(int, unsigned char base=10);
explicit String(unsigned int, unsigned char base=10);
explicit String(long, unsigned char base=10);
explicit String(unsigned long, unsigned char base=10);
explicit String(float, unsigned char decimalPlaces=2);
explicit String(double, unsigned char decimalPlaces=2);
~String(void);
// memory management
// return true on success, false on failure (in which case, the string
// is left unchanged). reserve(0), if successful, will validate an
// invalid string (i.e., "if (s)" will be true afterwards)
unsigned char reserve(unsigned int size);
inline unsigned int length(void) const {return len;}
// creates a copy of the assigned value. if the value is null or
// invalid, or if the memory allocation fails, the string will be
// marked as invalid ("if (s)" will be false).
String & operator = (const String &rhs);
String & operator = (const char *cstr);
String & operator = (const __FlashStringHelper *str);
#ifdef __GXX_EXPERIMENTAL_CXX0X__
String & operator = (String &&rval);
String & operator = (StringSumHelper &&rval);
#endif
// concatenate (works w/ built-in types)
// returns true on success, false on failure (in which case, the string
// is left unchanged). if the argument is null or invalid, the
// concatenation is considered unsucessful.
unsigned char concat(const String &str);
unsigned char concat(const char *cstr);
unsigned char concat(char c);
unsigned char concat(unsigned char c);
unsigned char concat(int num);
unsigned char concat(unsigned int num);
unsigned char concat(long num);
unsigned char concat(unsigned long num);
unsigned char concat(float num);
unsigned char concat(double num);
unsigned char concat(const __FlashStringHelper * str);
// if there's not enough memory for the concatenated value, the string
// will be left unchanged (but this isn't signalled in any way)
String & operator += (const String &rhs) {concat(rhs); return (*this);}
String & operator += (const char *cstr) {concat(cstr); return (*this);}
String & operator += (char c) {concat(c); return (*this);}
String & operator += (unsigned char num) {concat(num); return (*this);}
String & operator += (int num) {concat(num); return (*this);}
String & operator += (unsigned int num) {concat(num); return (*this);}
String & operator += (long num) {concat(num); return (*this);}
String & operator += (unsigned long num) {concat(num); return (*this);}
String & operator += (float num) {concat(num); return (*this);}
String & operator += (double num) {concat(num); return (*this);}
String & operator += (const __FlashStringHelper *str){concat(str); return (*this);}
friend StringSumHelper & operator + (const StringSumHelper &lhs, const String &rhs);
friend StringSumHelper & operator + (const StringSumHelper &lhs, const char *cstr);
friend StringSumHelper & operator + (const StringSumHelper &lhs, char c);
friend StringSumHelper & operator + (const StringSumHelper &lhs, unsigned char num);
friend StringSumHelper & operator + (const StringSumHelper &lhs, int num);
friend StringSumHelper & operator + (const StringSumHelper &lhs, unsigned int num);
friend StringSumHelper & operator + (const StringSumHelper &lhs, long num);
friend StringSumHelper & operator + (const StringSumHelper &lhs, unsigned long num);
friend StringSumHelper & operator + (const StringSumHelper &lhs, float num);
friend StringSumHelper & operator + (const StringSumHelper &lhs, double num);
friend StringSumHelper & operator + (const StringSumHelper &lhs, const __FlashStringHelper *rhs);
// comparison (only works w/ Strings and "strings")
operator StringIfHelperType() const { return buffer ? &String::StringIfHelper : 0; }
int compareTo(const String &s) const;
unsigned char equals(const String &s) const;
unsigned char equals(const char *cstr) const;
unsigned char operator == (const String &rhs) const {return equals(rhs);}
unsigned char operator == (const char *cstr) const {return equals(cstr);}
unsigned char operator != (const String &rhs) const {return !equals(rhs);}
unsigned char operator != (const char *cstr) const {return !equals(cstr);}
unsigned char operator < (const String &rhs) const;
unsigned char operator > (const String &rhs) const;
unsigned char operator <= (const String &rhs) const;
unsigned char operator >= (const String &rhs) const;
unsigned char equalsIgnoreCase(const String &s) const;
unsigned char startsWith( const String &prefix) const;
unsigned char startsWith(const String &prefix, unsigned int offset) const;
unsigned char endsWith(const String &suffix) const;
// character acccess
char charAt(unsigned int index) const;
void setCharAt(unsigned int index, char c);
char operator [] (unsigned int index) const;
char& operator [] (unsigned int index);
void getBytes(unsigned char *buf, unsigned int bufsize, unsigned int index=0) const;
void toCharArray(char *buf, unsigned int bufsize, unsigned int index=0) const
{getBytes((unsigned char *)buf, bufsize, index);}
const char * c_str() const { return buffer; }
// search
int indexOf( char ch ) const;
int indexOf( char ch, unsigned int fromIndex ) const;
int indexOf( const String &str ) const;
int indexOf( const String &str, unsigned int fromIndex ) const;
int lastIndexOf( char ch ) const;
int lastIndexOf( char ch, unsigned int fromIndex ) const;
int lastIndexOf( const String &str ) const;
int lastIndexOf( const String &str, unsigned int fromIndex ) const;
String substring( unsigned int beginIndex ) const { return substring(beginIndex, len); };
String substring( unsigned int beginIndex, unsigned int endIndex ) const;
// modification
void replace(char find, char replace);
void replace(const String& find, const String& replace);
void remove(unsigned int index);
void remove(unsigned int index, unsigned int count);
void toLowerCase(void);
void toUpperCase(void);
void trim(void);
// parsing/conversion
long toInt(void) const;
float toFloat(void) const;
protected:
char *buffer; // the actual char array
unsigned int capacity; // the array length minus one (for the '\0')
unsigned int len; // the String length (not counting the '\0')
protected:
void init(void);
void invalidate(void);
unsigned char changeBuffer(unsigned int maxStrLen);
unsigned char concat(const char *cstr, unsigned int length);
// copy and move
String & copy(const char *cstr, unsigned int length);
String & copy(const __FlashStringHelper *pstr, unsigned int length);
#ifdef __GXX_EXPERIMENTAL_CXX0X__
void move(String &rhs);
#endif
};
class StringSumHelper : public String
{
public:
StringSumHelper(const String &s) : String(s) {}
StringSumHelper(const char *p) : String(p) {}
StringSumHelper(char c) : String(c) {}
StringSumHelper(unsigned char num) : String(num) {}
StringSumHelper(int num) : String(num) {}
StringSumHelper(unsigned int num) : String(num) {}
StringSumHelper(long num) : String(num) {}
StringSumHelper(unsigned long num) : String(num) {}
StringSumHelper(float num) : String(num) {}
StringSumHelper(double num) : String(num) {}
};
#endif // __cplusplus
#endif // String_class_h

View File

@@ -0,0 +1,515 @@
#ifndef Binary_h
#define Binary_h
#define B0 0
#define B00 0
#define B000 0
#define B0000 0
#define B00000 0
#define B000000 0
#define B0000000 0
#define B00000000 0
#define B1 1
#define B01 1
#define B001 1
#define B0001 1
#define B00001 1
#define B000001 1
#define B0000001 1
#define B00000001 1
#define B10 2
#define B010 2
#define B0010 2
#define B00010 2
#define B000010 2
#define B0000010 2
#define B00000010 2
#define B11 3
#define B011 3
#define B0011 3
#define B00011 3
#define B000011 3
#define B0000011 3
#define B00000011 3
#define B100 4
#define B0100 4
#define B00100 4
#define B000100 4
#define B0000100 4
#define B00000100 4
#define B101 5
#define B0101 5
#define B00101 5
#define B000101 5
#define B0000101 5
#define B00000101 5
#define B110 6
#define B0110 6
#define B00110 6
#define B000110 6
#define B0000110 6
#define B00000110 6
#define B111 7
#define B0111 7
#define B00111 7
#define B000111 7
#define B0000111 7
#define B00000111 7
#define B1000 8
#define B01000 8
#define B001000 8
#define B0001000 8
#define B00001000 8
#define B1001 9
#define B01001 9
#define B001001 9
#define B0001001 9
#define B00001001 9
#define B1010 10
#define B01010 10
#define B001010 10
#define B0001010 10
#define B00001010 10
#define B1011 11
#define B01011 11
#define B001011 11
#define B0001011 11
#define B00001011 11
#define B1100 12
#define B01100 12
#define B001100 12
#define B0001100 12
#define B00001100 12
#define B1101 13
#define B01101 13
#define B001101 13
#define B0001101 13
#define B00001101 13
#define B1110 14
#define B01110 14
#define B001110 14
#define B0001110 14
#define B00001110 14
#define B1111 15
#define B01111 15
#define B001111 15
#define B0001111 15
#define B00001111 15
#define B10000 16
#define B010000 16
#define B0010000 16
#define B00010000 16
#define B10001 17
#define B010001 17
#define B0010001 17
#define B00010001 17
#define B10010 18
#define B010010 18
#define B0010010 18
#define B00010010 18
#define B10011 19
#define B010011 19
#define B0010011 19
#define B00010011 19
#define B10100 20
#define B010100 20
#define B0010100 20
#define B00010100 20
#define B10101 21
#define B010101 21
#define B0010101 21
#define B00010101 21
#define B10110 22
#define B010110 22
#define B0010110 22
#define B00010110 22
#define B10111 23
#define B010111 23
#define B0010111 23
#define B00010111 23
#define B11000 24
#define B011000 24
#define B0011000 24
#define B00011000 24
#define B11001 25
#define B011001 25
#define B0011001 25
#define B00011001 25
#define B11010 26
#define B011010 26
#define B0011010 26
#define B00011010 26
#define B11011 27
#define B011011 27
#define B0011011 27
#define B00011011 27
#define B11100 28
#define B011100 28
#define B0011100 28
#define B00011100 28
#define B11101 29
#define B011101 29
#define B0011101 29
#define B00011101 29
#define B11110 30
#define B011110 30
#define B0011110 30
#define B00011110 30
#define B11111 31
#define B011111 31
#define B0011111 31
#define B00011111 31
#define B100000 32
#define B0100000 32
#define B00100000 32
#define B100001 33
#define B0100001 33
#define B00100001 33
#define B100010 34
#define B0100010 34
#define B00100010 34
#define B100011 35
#define B0100011 35
#define B00100011 35
#define B100100 36
#define B0100100 36
#define B00100100 36
#define B100101 37
#define B0100101 37
#define B00100101 37
#define B100110 38
#define B0100110 38
#define B00100110 38
#define B100111 39
#define B0100111 39
#define B00100111 39
#define B101000 40
#define B0101000 40
#define B00101000 40
#define B101001 41
#define B0101001 41
#define B00101001 41
#define B101010 42
#define B0101010 42
#define B00101010 42
#define B101011 43
#define B0101011 43
#define B00101011 43
#define B101100 44
#define B0101100 44
#define B00101100 44
#define B101101 45
#define B0101101 45
#define B00101101 45
#define B101110 46
#define B0101110 46
#define B00101110 46
#define B101111 47
#define B0101111 47
#define B00101111 47
#define B110000 48
#define B0110000 48
#define B00110000 48
#define B110001 49
#define B0110001 49
#define B00110001 49
#define B110010 50
#define B0110010 50
#define B00110010 50
#define B110011 51
#define B0110011 51
#define B00110011 51
#define B110100 52
#define B0110100 52
#define B00110100 52
#define B110101 53
#define B0110101 53
#define B00110101 53
#define B110110 54
#define B0110110 54
#define B00110110 54
#define B110111 55
#define B0110111 55
#define B00110111 55
#define B111000 56
#define B0111000 56
#define B00111000 56
#define B111001 57
#define B0111001 57
#define B00111001 57
#define B111010 58
#define B0111010 58
#define B00111010 58
#define B111011 59
#define B0111011 59
#define B00111011 59
#define B111100 60
#define B0111100 60
#define B00111100 60
#define B111101 61
#define B0111101 61
#define B00111101 61
#define B111110 62
#define B0111110 62
#define B00111110 62
#define B111111 63
#define B0111111 63
#define B00111111 63
#define B1000000 64
#define B01000000 64
#define B1000001 65
#define B01000001 65
#define B1000010 66
#define B01000010 66
#define B1000011 67
#define B01000011 67
#define B1000100 68
#define B01000100 68
#define B1000101 69
#define B01000101 69
#define B1000110 70
#define B01000110 70
#define B1000111 71
#define B01000111 71
#define B1001000 72
#define B01001000 72
#define B1001001 73
#define B01001001 73
#define B1001010 74
#define B01001010 74
#define B1001011 75
#define B01001011 75
#define B1001100 76
#define B01001100 76
#define B1001101 77
#define B01001101 77
#define B1001110 78
#define B01001110 78
#define B1001111 79
#define B01001111 79
#define B1010000 80
#define B01010000 80
#define B1010001 81
#define B01010001 81
#define B1010010 82
#define B01010010 82
#define B1010011 83
#define B01010011 83
#define B1010100 84
#define B01010100 84
#define B1010101 85
#define B01010101 85
#define B1010110 86
#define B01010110 86
#define B1010111 87
#define B01010111 87
#define B1011000 88
#define B01011000 88
#define B1011001 89
#define B01011001 89
#define B1011010 90
#define B01011010 90
#define B1011011 91
#define B01011011 91
#define B1011100 92
#define B01011100 92
#define B1011101 93
#define B01011101 93
#define B1011110 94
#define B01011110 94
#define B1011111 95
#define B01011111 95
#define B1100000 96
#define B01100000 96
#define B1100001 97
#define B01100001 97
#define B1100010 98
#define B01100010 98
#define B1100011 99
#define B01100011 99
#define B1100100 100
#define B01100100 100
#define B1100101 101
#define B01100101 101
#define B1100110 102
#define B01100110 102
#define B1100111 103
#define B01100111 103
#define B1101000 104
#define B01101000 104
#define B1101001 105
#define B01101001 105
#define B1101010 106
#define B01101010 106
#define B1101011 107
#define B01101011 107
#define B1101100 108
#define B01101100 108
#define B1101101 109
#define B01101101 109
#define B1101110 110
#define B01101110 110
#define B1101111 111
#define B01101111 111
#define B1110000 112
#define B01110000 112
#define B1110001 113
#define B01110001 113
#define B1110010 114
#define B01110010 114
#define B1110011 115
#define B01110011 115
#define B1110100 116
#define B01110100 116
#define B1110101 117
#define B01110101 117
#define B1110110 118
#define B01110110 118
#define B1110111 119
#define B01110111 119
#define B1111000 120
#define B01111000 120
#define B1111001 121
#define B01111001 121
#define B1111010 122
#define B01111010 122
#define B1111011 123
#define B01111011 123
#define B1111100 124
#define B01111100 124
#define B1111101 125
#define B01111101 125
#define B1111110 126
#define B01111110 126
#define B1111111 127
#define B01111111 127
#define B10000000 128
#define B10000001 129
#define B10000010 130
#define B10000011 131
#define B10000100 132
#define B10000101 133
#define B10000110 134
#define B10000111 135
#define B10001000 136
#define B10001001 137
#define B10001010 138
#define B10001011 139
#define B10001100 140
#define B10001101 141
#define B10001110 142
#define B10001111 143
#define B10010000 144
#define B10010001 145
#define B10010010 146
#define B10010011 147
#define B10010100 148
#define B10010101 149
#define B10010110 150
#define B10010111 151
#define B10011000 152
#define B10011001 153
#define B10011010 154
#define B10011011 155
#define B10011100 156
#define B10011101 157
#define B10011110 158
#define B10011111 159
#define B10100000 160
#define B10100001 161
#define B10100010 162
#define B10100011 163
#define B10100100 164
#define B10100101 165
#define B10100110 166
#define B10100111 167
#define B10101000 168
#define B10101001 169
#define B10101010 170
#define B10101011 171
#define B10101100 172
#define B10101101 173
#define B10101110 174
#define B10101111 175
#define B10110000 176
#define B10110001 177
#define B10110010 178
#define B10110011 179
#define B10110100 180
#define B10110101 181
#define B10110110 182
#define B10110111 183
#define B10111000 184
#define B10111001 185
#define B10111010 186
#define B10111011 187
#define B10111100 188
#define B10111101 189
#define B10111110 190
#define B10111111 191
#define B11000000 192
#define B11000001 193
#define B11000010 194
#define B11000011 195
#define B11000100 196
#define B11000101 197
#define B11000110 198
#define B11000111 199
#define B11001000 200
#define B11001001 201
#define B11001010 202
#define B11001011 203
#define B11001100 204
#define B11001101 205
#define B11001110 206
#define B11001111 207
#define B11010000 208
#define B11010001 209
#define B11010010 210
#define B11010011 211
#define B11010100 212
#define B11010101 213
#define B11010110 214
#define B11010111 215
#define B11011000 216
#define B11011001 217
#define B11011010 218
#define B11011011 219
#define B11011100 220
#define B11011101 221
#define B11011110 222
#define B11011111 223
#define B11100000 224
#define B11100001 225
#define B11100010 226
#define B11100011 227
#define B11100100 228
#define B11100101 229
#define B11100110 230
#define B11100111 231
#define B11101000 232
#define B11101001 233
#define B11101010 234
#define B11101011 235
#define B11101100 236
#define B11101101 237
#define B11101110 238
#define B11101111 239
#define B11110000 240
#define B11110001 241
#define B11110010 242
#define B11110011 243
#define B11110100 244
#define B11110101 245
#define B11110110 246
#define B11110111 247
#define B11111000 248
#define B11111001 249
#define B11111010 250
#define B11111011 251
#define B11111100 252
#define B11111101 253
#define B11111110 254
#define B11111111 255
#endif

View File

@@ -0,0 +1,15 @@
#include <Arduino.h>
int main(void)
{
//OSCCAL = TUNED_OSCCAL_VALUE; //set the oscillator calibration value based on the pins_arduino.h file. If this is not set, it will be optimised away - it would boil down to 1 = 1;
init();
setup();
for (;;)
loop();
return 0;
}

View File

@@ -0,0 +1,18 @@
#include <new.h>
void * operator new(size_t size)
{
return malloc(size);
}
void operator delete(void * ptr)
{
free(ptr);
}
int __cxa_guard_acquire(__guard *g) {return !*(char *)(g);};
void __cxa_guard_release (__guard *g) {*(char *)g = 1;};
void __cxa_guard_abort (__guard *) {};
void __cxa_pure_virtual(void) {};

View File

@@ -0,0 +1,22 @@
/* Header to define new/delete operators as they aren't provided by avr-gcc by default
Taken from http://www.avrfreaks.net/index.php?name=PNphpBB2&file=viewtopic&t=59453
*/
#ifndef NEW_H
#define NEW_H
#include <stdlib.h>
void * operator new(size_t size);
void operator delete(void * ptr);
__extension__ typedef int __guard __attribute__((mode (__DI__)));
extern "C" int __cxa_guard_acquire(__guard *);
extern "C" void __cxa_guard_release (__guard *);
extern "C" void __cxa_guard_abort (__guard *);
extern "C" void __cxa_pure_virtual(void);
#endif

View File

@@ -0,0 +1,692 @@
/*
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
$Id: wiring.c 970 2010-05-25 20:16:15Z dmellis $
Modified 28-08-2009 for attiny84 R.Wiersma
Modified 14-10-2009 for attiny45 Saposoft
Modified 20-11-2010 - B.Cook - Rewritten to use the various Veneers.
*/
#include "wiring_private.h"
#if F_CPU >= 3000000L
#if !defined(__AVR_ATtiny167__) && !defined(__AVR_ATtiny87__)
#define timer0Prescaler 0b011
#else
#define timer0Prescaler 0b100
#endif
//Timers with TCCR1 are slightly different.
#if defined(TCCR1) && (TIMER_TO_USE_FOR_MILLIS == 1)
#define MillisTimer_Prescale_Index (0b0111)
#define ToneTimer_Prescale_Index (timer0Prescaler)
#elif defined(TCCR1) && (TIMER_TO_USE_FOR_MILLIS == 0)
#define MillisTimer_Prescale_Index (timer0Prescaler)
#define ToneTimer_Prescale_Index (0b0111)
#elif defined(TCCR1E) && (TIMER_TO_USE_FOR_MILLIS == 1)
#define MillisTimer_Prescale_Index (0b0111)
#define ToneTimer_Prescale_Index (timer0Prescaler)
#elif defined(TCCR1E) && (TIMER_TO_USE_FOR_MILLIS == 0)
#define MillisTimer_Prescale_Index (timer0Prescaler)
#define ToneTimer_Prescale_Index (0b0111)
#elif (TIMER_TO_USE_FOR_MILLIS == 1)
#define MillisTimer_Prescale_Index (0b011)
#define ToneTimer_Prescale_Index (timer0Prescaler)
#else
#define MillisTimer_Prescale_Index (timer0Prescaler)
#define ToneTimer_Prescale_Index (0b011)
#endif
#define MillisTimer_Prescale_Value (64)
#define ToneTimer_Prescale_Value (64)
#else
#if defined(TCCR1) && (TIMER_TO_USE_FOR_MILLIS == 1)
#define MillisTimer_Prescale_Index (0b0100)
#define ToneTimer_Prescale_Index (0b010)
#elif defined(TCCR1) && (TIMER_TO_USE_FOR_MILLIS == 0)
#define MillisTimer_Prescale_Index (0b010)
#define ToneTimer_Prescale_Index (0b0100)
#elif defined(TCCR1E) && (TIMER_TO_USE_FOR_MILLIS == 1)
#define MillisTimer_Prescale_Index (0b0100)
#define ToneTimer_Prescale_Index (0b010)
#elif defined(TCCR1E) && (TIMER_TO_USE_FOR_MILLIS == 0)
#define MillisTimer_Prescale_Index (0b010)
#define ToneTimer_Prescale_Index (0b0100)
#else
#define MillisTimer_Prescale_Index (0b010)
#define ToneTimer_Prescale_Index (0b010)
#endif
#define MillisTimer_Prescale_Value (8)
#define ToneTimer_Prescale_Value (8)
#endif
// the prescaler is set so that the millis timer ticks every MillisTimer_Prescale_Value (64) clock cycles, and the
// the overflow handler is called every 256 ticks.
#define MICROSECONDS_PER_MILLIS_OVERFLOW (clockCyclesToMicroseconds(MillisTimer_Prescale_Value * 256))
// the whole number of milliseconds per millis timer overflow
#define MILLIS_INC (MICROSECONDS_PER_MILLIS_OVERFLOW / 1000)
// the fractional number of milliseconds per millis timer 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_MILLIS_OVERFLOW % 1000) >> 3)
#define FRACT_MAX (1000 >> 3)
volatile unsigned long millis_timer_overflow_count = 0;
volatile unsigned long millis_timer_millis = 0;
static unsigned char millis_timer_fract = 0;
#if (TIMER_TO_USE_FOR_MILLIS == 0)
#if defined(TIMER0_OVF_vect)
SIGNAL(TIMER0_OVF_vect)
#elif defined(TIM0_OVF_vect)
SIGNAL(TIM0_OVF_vect)
#else
#error cannot find Millis() timer overflow vector
#endif
#elif (TIMER_TO_USE_FOR_MILLIS == 1)
#if defined(TIMER1_OVF_vect)
SIGNAL(TIMER1_OVF_vect)
#elif defined(TIM1_OVF_vect)
SIGNAL(TIM1_OVF_vect)
#else
#error cannot find Millis() timer overflow vector
#endif
#else
#error Millis() timer not defined!
#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 = millis_timer_millis;
unsigned char f = millis_timer_fract;
/* rmv: The code below generates considerably less code (emtpy Sketch is 326 versus 304)...
m += MILLIS_INC;
f += FRACT_INC;
if (f >= FRACT_MAX) {
f -= FRACT_MAX;
m += 1;
}
...rmv */
f += FRACT_INC;
if (f >= FRACT_MAX)
{
f -= FRACT_MAX;
m += 1;
m += MILLIS_INC;
}
else
{
m += MILLIS_INC;
}
millis_timer_fract = f;
millis_timer_millis = m;
millis_timer_overflow_count++;
//MICROSECONDS_PER_MILLIS_OVERFLOW=2048
//MILLIS_INC=2
//FRACT_INC=6
//FRACT_MAX=125
}
unsigned long millis()
{
unsigned long m;
uint8_t oldSREG = SREG;
// disable interrupts while we read millis_timer_millis or we might get an
// inconsistent value (e.g. in the middle of a write to millis_timer_millis)
cli();
m = millis_timer_millis;
SREG = oldSREG;
return m;
}
unsigned long micros()
{
unsigned long m;
uint8_t oldSREG = SREG, t;
cli();
m = millis_timer_overflow_count;
#if defined(TCNT0) && (TIMER_TO_USE_FOR_MILLIS == 0) && !defined(TCW0)
t = TCNT0;
#elif defined(TCNT0L) && (TIMER_TO_USE_FOR_MILLIS == 0)
t = TCNT0L;
#elif defined(TCNT1) && (TIMER_TO_USE_FOR_MILLIS == 1)
t = TCNT1;
#elif defined(TCNT1L) && (TIMER_TO_USE_FOR_MILLIS == 1)
t = TCNT1L;
#else
#error Millis()/Micros() timer not defined
#endif
#if defined(TIFR0) && (TIMER_TO_USE_FOR_MILLIS == 0)
if ((TIFR0 & _BV(TOV0)) && (t < 255))
m++;
#elif defined(TIFR) && (TIMER_TO_USE_FOR_MILLIS == 0)
if ((TIFR & _BV(TOV0)) && (t < 255))
m++;
#elif defined(TIFR1) && (TIMER_TO_USE_FOR_MILLIS == 1)
if ((TIFR1 & _BV(TOV1)) && (t < 255))
m++;
#elif defined(TIFR) && (TIMER_TO_USE_FOR_MILLIS == 1)
if ((TIFR & _BV(TOV1)) && (t < 255))
m++;
#endif
SREG = oldSREG;
return ((m << 8) + t) * (MillisTimer_Prescale_Value / clockCyclesPerMicrosecond());
}
void delay(unsigned long ms)
{
uint16_t start = (uint16_t)micros();
while (ms > 0) {
if (((uint16_t)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 AVR 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
}
#if INITIALIZE_SECONDARY_TIMERS
static void initToneTimerInternal(void)
{
// Timer is processor clock divided by ToneTimer_Prescale_Index
#if (TIMER_TO_USE_FOR_TONE == 0)
TCCR0B &= ~((1<<CS02) | (1<<CS01) | (1<<CS00)); //stop the clock to configure
// Use the Tone Timer for phase correct PWM
sbi(TCCR0A, WGM00);
cbi(TCCR0A, WGM01);
cbi(TCCR0B, WGM02);
TCCR0B |= (ToneTimer_Prescale_Index << CS00);
#elif (TIMER_TO_USE_FOR_TONE == 1) && defined(TCCR1)
TCCR1 &= ~((1<<CS13) | (1<<CS12) | (1<<CS11) | (1<<CS10)); //stop the clock to configure
// Use the Tone Timer for fast PWM as phase correct not supported by this timer
sbi(TCCR1, CTC1);
#if !defined(__AVR_ATtiny85__)
sbi(TCCR1, PWM1A); //for the tiny 85, Timer0 is used instead.
#endif
sbi(GTCCR, PWM1B);
OCR1C = 0xFF; //Use 255 as the top to match with the others as this module doesn't have a 8bit PWM mode.
TCCR1 |= (ToneTimer_Prescale_Index << CS10);
#elif (TIMER_TO_USE_FOR_TONE == 1) && defined(TCCR1E)
TCCR1B &= ~((1<<CS13) | (1<<CS12) | (1<<CS11) | (1<<CS10)); //stop the clock to configure
// Use the Tone Timer for phase correct PWM
sbi(TCCR1A, PWM1A);
sbi(TCCR1A, PWM1B);
sbi(TCCR1C, PWM1D);
cbi(TCCR1D, WGM11);
sbi(TCCR1D, WGM10);
TCCR1B |= (ToneTimer_Prescale_Index << CS10);
#elif (TIMER_TO_USE_FOR_TONE == 1)
TCCR1B &= ~((1<<CS12) | (1<<CS11) | (1<<CS10)); //stop the clock to configure
// Use the Tone Timer for phase correct PWM
sbi(TCCR1A, WGM10);
cbi(TCCR1A, WGM11);
cbi(TCCR1B, WGM12);
cbi(TCCR1B, WGM13);
TCCR1B |= (ToneTimer_Prescale_Index << CS10); //set the clock
#endif
}
#endif
void initToneTimer(void)
{
// Ensure the timer is in the same state as power-up
#if (TIMER_TO_USE_FOR_TONE == 0)
TCCR0B = (0<<FOC0A) | (0<<FOC0B) | (0<<WGM02) | (0<<CS02) | (0<<CS01) | (0<<CS00);
TCCR0A = (0<<COM0A1) | (0<<COM0A0) | (0<<COM0B1) | (0<<COM0B0) | (0<<WGM01) | (0<<WGM00);
// Reset the count to zero
TCNT0 = 0;
// Set the output compare registers to zero
OCR0A = 0;
OCR0B = 0;
#if defined(TIMSK)
// Disable all Timer0 interrupts
TIMSK &= ~((1<<OCIE0B) | (1<<OCIE0A) | (1<<TOIE0));
// Clear the Timer0 interrupt flags
TIFR |= ((1<<OCF0B) | (1<<OCF0A) | (1<<TOV0));
#elif defined(TIMSK1)
// Disable all Timer0 interrupts
TIMSK0 &= ~((1<<OCIE0B) | (1<<OCIE0A) | (1<<TOIE0));
// Clear the Timer0 interrupt flags
TIFR0 |= ((1<<OCF0B) | (1<<OCF0A) | (1<<TOV0));
#endif
#elif (TIMER_TO_USE_FOR_TONE == 1) && defined(TCCR1)
// Turn off Clear on Compare Match, turn off PWM A, disconnect the timer from the output pin, stop the clock
TCCR1 = (0<<CTC1) | (0<<PWM1A) | (0<<COM1A1) | (0<<COM1A0) | (0<<CS13) | (0<<CS12) | (0<<CS11) | (0<<CS10);
// Turn off PWM A, disconnect the timer from the output pin, no Force Output Compare Match, no Prescaler Reset
GTCCR &= ~((1<<PWM1B) | (1<<COM1B1) | (1<<COM1B0) | (1<<FOC1B) | (1<<FOC1A) | (1<<PSR1));
// Reset the count to zero
TCNT1 = 0;
// Set the output compare registers to zero
OCR1A = 0;
OCR1B = 0;
OCR1C = 0;
// Disable all Timer1 interrupts
TIMSK &= ~((1<<OCIE1A) | (1<<OCIE1B) | (1<<TOIE1));
// Clear the Timer1 interrupt flags
TIFR |= ((1<<OCF1A) | (1<<OCF1B) | (1<<TOV1));
#elif (TIMER_TO_USE_FOR_TONE == 1) && defined(TCCR1E)
TCCR1A = 0;
TCCR1B = 0;
TCCR1C = 0;
TCCR1D = 0;
TCCR1E = 0;
// Reset the count to zero
TCNT1 = 0;
// Set the output compare registers to zero
OCR1A = 0;
OCR1B = 0;
OCR1C = 0;
OCR1D = 0;
// Disable all Timer1 interrupts
TIMSK &= ~((1<<TOIE1) | (1<<OCIE1A) | (1<<OCIE1B) | (1<<OCIE1D));
// Clear the Timer1 interrupt flags
TIFR |= ((1<<TOV1) | (1<<OCF1A) | (1<<OCF1B) | (1<<OCF1D));
#elif (TIMER_TO_USE_FOR_TONE == 1)
// Turn off Input Capture Noise Canceler, Input Capture Edge Select on Falling, stop the clock
TCCR1B = (0<<ICNC1) | (0<<ICES1) | (0<<WGM13) | (0<<WGM12) | (0<<CS12) | (0<<CS11) | (0<<CS10);
// Disconnect the timer from the output pins, Set Waveform Generation Mode to Normal
TCCR1A = (0<<COM1A1) | (0<<COM1A0) | (0<<COM1B1) | (0<<COM1B0) | (0<<WGM11) | (0<<WGM10);
// Reset the count to zero
TCNT1 = 0;
// Set the output compare registers to zero
OCR1A = 0;
OCR1B = 0;
// Disable all Timer1 interrupts
#if defined(TIMSK)
TIMSK &= ~((1<<TOIE1) | (1<<OCIE1A) | (1<<OCIE1B) | (1<<ICIE1));
// Clear the Timer1 interrupt flags
TIFR |= ((1<<TOV1) | (1<<OCF1A) | (1<<OCF1B) | (1<<ICF1));
#elif defined(TIMSK1)
// Disable all Timer1 interrupts
TIMSK1 &= ~((1<<TOIE1) | (1<<OCIE1A) | (1<<OCIE1B) | (1<<ICIE1));
// Clear the Timer1 interrupt flags
TIFR1 |= ((1<<TOV1) | (1<<OCF1A) | (1<<OCF1B) | (1<<ICF1));
#endif
#endif
#if INITIALIZE_SECONDARY_TIMERS
// Prepare the timer for PWM
initToneTimerInternal();
#endif
}
#if F_CPU == 20000000
// 20 MHz / 128 ~= 125 KHz
#define ADC_ARDUINO_PRESCALER B111
#elif F_CPU == 18432000
// 18.432 MHz / 128 ~= 125 KHz
#define ADC_ARDUINO_PRESCALER B111
#elif F_CPU == 16000000
// 16 MHz / 128 = 125 KHz
#define ADC_ARDUINO_PRESCALER B111
#elif F_CPU == 12000000
// 12 MHz / 64 ~= 125 KHz
#define ADC_ARDUINO_PRESCALER B110
#elif F_CPU == 8000000
// 8 MHz / 64 = 125 KHz
#define ADC_ARDUINO_PRESCALER B110
#elif F_CPU == 1000000
// 1 MHz / 8 = 125 KHz
#define ADC_ARDUINO_PRESCALER B011
#elif F_CPU == 128000
// 128 kHz / 2 = 64 KHz -> This is the closest you can get, the prescaler is 2
#define ADC_ARDUINO_PRESCALER B000
#else
#error Add an entry for the selected processor speed.
#endif
void init(void)
{
// In case the bootloader left our millis timer in a bad way
#if defined( HAVE_BOOTLOADER ) && HAVE_BOOTLOADER
// Ensure the timer is in the same state as power-up
#if (TIMER_TO_USE_FOR_MILLIS == 0) && defined(WGM01)
TCCR0B = 0;
TCCR0A = 0;
// Reset the count to zero
TCNT0 = 0;
// Set the output compare registers to zero
OCR0A = 0;
#ifdef OCR0B
OCR0B = 0;
#endif
#if defined(TIMSK)
// Disable all Timer0 interrupts
TIMSK &= ~((1<<OCIE0B) | (1<<OCIE0A) | (1<<TOIE0));
// Clear the Timer0 interrupt flags
TIFR |= ((1<<OCF0B) | (1<<OCF0A) | (1<<TOV0));
#elif defined(TIMSK1)
#ifdef OCIE0B
// Disable all Timer0 interrupts
TIMSK0 &= ~((1<<OCIE0B) | (1<<OCIE0A) | (1<<TOIE0));
// Clear the Timer0 interrupt flags
TIFR0 |= ((1<<OCF0B) | (1<<OCF0A) | (1<<TOV0));
#else
// Disable all Timer0 interrupts
TIMSK0 &= ~((1<<OCIE0A) | (1<<TOIE0));
// Clear the Timer0 interrupt flags
TIFR0 |= ((1<<OCF0A) | (1<<TOV0));
#endif
#endif
#elif (TIMER_TO_USE_FOR_MILLIS == 0) && defined(TCW0)
TCCR0A = 0;
TCCR0B = 0;
// Reset the count to zero
TCNT0 = 0;
#if defined(TIMSK)
// Disable all Timer0 interrupts
TIMSK &= ~((1<<OCIE0B) | (1<<OCIE0A) | (1<<TOIE0));
// Clear the Timer0 interrupt flags
TIFR |= ((1<<OCF0B) | (1<<OCF0A) | (1<<TOV0));
#if defined(TICIE0)
cbi(TIMSK,TICIE0);
sbi(TIFR0,ICF0);
#endif
#elif defined(TIMSK1)
// Disable all Timer0 interrupts
TIMSK0 &= ~((1<<OCIE0B) | (1<<OCIE0A) | (1<<TOIE0));
// Clear the Timer0 interrupt flags
TIFR0 |= ((1<<OCF0B) | (1<<OCF0A) | (1<<TOV0));
#if defined(TICIE0)
cbi(TIMSK0,TICIE0);
sbi(TIFR0,ICF0);
#endif
#endif
#elif (TIMER_TO_USE_FOR_MILLIS == 1) && defined(TCCR1)
// Turn off Clear on Compare Match, turn off PWM A, disconnect the timer from the output pin, stop the clock
TCCR1 = (0<<CTC1) | (0<<PWM1A) | (0<<COM1A1) | (0<<COM1A0) | (0<<CS13) | (0<<CS12) | (0<<CS11) | (0<<CS10);
// Turn off PWM A, disconnect the timer from the output pin, no Force Output Compare Match, no Prescaler Reset
GTCCR &= ~((1<<PWM1B) | (1<<COM1B1) | (1<<COM1B0) | (1<<FOC1B) | (1<<FOC1A) | (1<<PSR1));
// Reset the count to zero
TCNT1 = 0;
// Set the output compare registers to zero
OCR1A = 0;
OCR1B = 0;
OCR1C = 0;
// Disable all Timer1 interrupts
TIMSK = 0;
// Clear the Timer1 interrupt flags
TIFR |= ((1<<OCF1A) | (1<<OCF1B) | (1<<TOV1));
#elif (TIMER_TO_USE_FOR_MILLIS == 1) && defined(TCCR1E)
TCCR1A = 0;
TCCR1B = 0;
TCCR1C = 0;
TCCR1D = 0;
TCCR1E = 0;
// Reset the count to zero
TCNT1 = 0;
// Set the output compare registers to zero
OCR1A = 0;
OCR1B = 0;
// Disable all Timer1 interrupts
TIMSK &= ~((1<<TOIE1) | (1<<OCIE1A) | (1<<OCIE1B) | (1<<OCIE1D));
// Clear the Timer1 interrupt flags
TIFR |= ((1<<TOV1) | (1<<OCF1A) | (1<<OCF1B) | (1<<OCF1D));
#elif (TIMER_TO_USE_FOR_MILLIS == 1)
// Turn off Input Capture Noise Canceler, Input Capture Edge Select on Falling, stop the clock
TCCR1B = (0<<ICNC1) | (0<<ICES1) | (0<<WGM13) | (0<<WGM12) | (0<<CS12) | (0<<CS11) | (0<<CS10);
// Disconnect the timer from the output pins, Set Waveform Generation Mode to Normal
TCCR1A = (0<<COM1A1) | (0<<COM1A0) | (0<<COM1B1) | (0<<COM1B0) | (0<<WGM11) | (0<<WGM10);
// Reset the count to zero
TCNT1 = 0;
// Set the output compare registers to zero
OCR1A = 0;
OCR1B = 0;
// Disable all Timer1 interrupts
#if defined(TIMSK)
TIMSK &= ~((1<<TOIE1) | (1<<OCIE1A) | (1<<OCIE1B) | (1<<ICIE1));
// Clear the Timer1 interrupt flags
TIFR |= ((1<<TOV1) | (1<<OCF1A) | (1<<OCF1B) | (1<<ICF1));
#elif defined(TIMSK1)
// Disable all Timer1 interrupts
TIMSK1 &= ~((1<<TOIE1) | (1<<OCIE1A) | (1<<OCIE1B) | (1<<ICIE1));
// Clear the Timer1 interrupt flags
TIFR1 |= ((1<<TOV1) | (1<<OCF1A) | (1<<OCF1B) | (1<<ICF1));
#endif
#endif
#endif
// Use the Millis Timer for fast PWM (unless it doesn't have an output).
#if (TIMER_TO_USE_FOR_MILLIS == 0) && defined(WGM01)
sbi(TCCR0A, WGM01);
sbi(TCCR0A, WGM00);
#elif (TIMER_TO_USE_FOR_MILLIS == 1) && defined(TCCR1)
sbi(TCCR1, CTC1);
//#if !defined(__AVR_ATtiny85__)
// sbi(TCCR1, PWM1A); //for the tiny 85, Timer0 is used instead.
//#endif
//sbi(GTCCR, PWM1B);
OCR1C = 0xFF; //Use 255 as the top to match with the others as this module doesn't have a 8bit PWM mode.
#elif (TIMER_TO_USE_FOR_MILLIS == 1) && defined(TCCR1E)
sbi(TCCR1C, PWM1D);
sbi(TCCR1A, PWM1A);
sbi(TCCR1A, PWM1B);
cbi(TCCR1E, WGM10); //fast pwm mode
cbi(TCCR1E, WGM11);
OCR1C = 0xFF; //Use 255 as the top to match with the others as this module doesn't have a 8bit PWM mode.
#elif (TIMER_TO_USE_FOR_MILLIS == 1)
sbi(TCCR1A, WGM10);
sbi(TCCR1B, WGM12);
#endif
// Millis timer is always processor clock divided by MillisTimer_Prescale_Value (64)
#if (TIMER_TO_USE_FOR_MILLIS == 0)
TCCR0B = (TCCR0B & ~((1<<CS02)|(1<<CS01)|(1<<CS00))) | (MillisTimer_Prescale_Index << CS00);
#elif (TIMER_TO_USE_FOR_MILLIS == 1) && defined(TCCR1)
TCCR1 = (TCCR1 & ~((1<<CS13)|(1<<CS12)|(1<<CS11)|(1<<CS10))) | (MillisTimer_Prescale_Index << CS10);
#elif (TIMER_TO_USE_FOR_MILLIS == 1) && defined(TCCR1E)
TCCR1B = (TCCR1B & ~((1<<CS13)|(1<<CS12)|(1<<CS11)|(1<<CS10))) | (MillisTimer_Prescale_Index << CS10);
#elif (TIMER_TO_USE_FOR_MILLIS == 1)
TCCR1B = (TCCR1B & ~((1<<CS12)|(1<<CS11)|(1<<CS10))) | (MillisTimer_Prescale_Index << CS10);
#endif
// this needs to be called before setup() or some functions won't work there
sei();
// Enable the overlow interrupt (this is the basic system tic-toc for millis)
#if defined(TIMSK) && defined(TOIE0) && (TIMER_TO_USE_FOR_MILLIS == 0)
sbi(TIMSK, TOIE0);
#elif defined(TIMSK0) && defined(TOIE0) && (TIMER_TO_USE_FOR_MILLIS == 0)
sbi(TIMSK0, TOIE0);
#elif defined(TIMSK) && defined(TOIE1) && (TIMER_TO_USE_FOR_MILLIS == 1)
sbi(TIMSK, TOIE1);
#elif defined(TIMSK1) && defined(TOIE1) && (TIMER_TO_USE_FOR_MILLIS == 1)
sbi(TIMSK1, TOIE1);
#else
#error Millis() Timer overflow interrupt not set correctly
#endif
// Initialize the timer used for Tone
#if INITIALIZE_SECONDARY_TIMERS
initToneTimerInternal();
#endif
// Initialize the ADC
#if defined( INITIALIZE_ANALOG_TO_DIGITAL_CONVERTER ) && INITIALIZE_ANALOG_TO_DIGITAL_CONVERTER
#if defined(ADCSRA)
// set a2d prescale factor
ADCSRA = (ADCSRA & ~((1<<ADPS2)|(1<<ADPS1)|(1<<ADPS0))) | (ADC_ARDUINO_PRESCALER << ADPS0) | (1<<ADEN);
// enable a2d conversions
sbi(ADCSRA, ADEN);
#endif
#endif
}

View File

@@ -0,0 +1,261 @@
/*
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
$Id: wiring.c 248 2007-02-03 15:36:30Z mellis $
Modified 28-08-2009 for attiny84 R.Wiersma
Modified 14-10-2009 for attiny45 Saposoft
Corrected 17-05-2010 for ATtiny84 B.Cook
*/
#include "wiring_private.h"
#include "pins_arduino.h"
#ifndef DEFAULT
//For those with no ADC, need to define default.
#define DEFAULT (0)
#endif
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.
// fix? Validate the mode?
analog_reference = mode;
}
int analogRead(uint8_t pin)
{
#if defined( NUM_DIGITAL_PINS )
if ( pin >= NUM_DIGITAL_PINS ) pin -= NUM_DIGITAL_PINS; // allow for channel or pin numbers
#endif
// fix? Validate pin?
if(pin >= NUM_ANALOG_INPUTS) return 0; //Not a valid pin.
//if(pin < 4) return 9; //Not a valid pin.
#ifndef ADCSRA
return digitalRead(analogInputToDigitalPin(pin)) ? 1023 : 0; //No ADC, so read as a digital pin instead.
#endif
#if defined(ADMUX)
#if defined(MUX4)
ADMUX = ((analog_reference & 0x03) << REFS0) | ((pin & 0x1F) << MUX0); //select the channel and reference
#elif defined(MUX3)
ADMUX = ((analog_reference & 0x03) << REFS0) | ((pin & 0x0F) << MUX0); //select the channel and reference
#else
ADMUX = ((analog_reference & 0x03) << REFS0) | ((pin & 0x07) << MUX0); //select the channel and reference
#endif
#endif
#if defined(REFS2)
ADMUX |= (((analog_reference & 0x04) >> 2) << REFS2); //some have an extra reference bit in a weird position.
#endif
#if defined(HAVE_ADC) && HAVE_ADC
sbi(ADCSRA, ADSC); //Start conversion
while(ADCSRA & (1<<ADSC)); //Wait for conversion to complete.
uint8_t low = ADCL;
uint8_t high = ADCH;
return (high << 8) | low;
#else
return LOW;
#endif
}
void pwmReset()
{
cbi(TCCR1D, OC1AV);
cbi(TCCR1D, OC1AU);
cbi(TCCR1D, OC1AW);
cbi(TCCR1D, OC1AX);
cbi(TCCR1D, OC1BV);
cbi(TCCR1D, OC1BU);
cbi(TCCR1D, OC1BW);
cbi(TCCR1D, OC1BX);
}
void pwmWrite(uint8_t channel, int val)
{
if( channel == TIMER1A){
// connect pwm to pin on timer 1, channel A
sbi(TCCR1A, COM1A1);
sbi(TCCR1A, WGM10);
cbi(TCCR1A, COM1A0);
sbi(TCCR1B, WGM10);
sbi(TCCR1B, CS11);
//sbi(TCCR1B, CS10);
OCR1A = val; // set pwm duty
} else if( channel == TIMER1B){
// connect pwm to pin on timer 1, channel B
sbi(TCCR1A, COM1B1);
sbi(TCCR1A, WGM10);
cbi(TCCR1A, COM1B0);
sbi(TCCR1B, WGM10);
sbi(TCCR1B, CS11);
//sbi(TCCR1B, CS10);
OCR1B = val; // set pwm duty
}
}
void pwmConnect(uint8_t pin)
{
pinMode(pin,OUTPUT);
if(pin == 2)
sbi(TCCR1D, OC1AV);
else if(pin == 0)
sbi(TCCR1D, OC1AU);
// cbi(TCCR1D, OC1AW);//used by crystal
else if(pin == 3)
sbi(TCCR1D, OC1AX);
else if(pin == 4)
sbi(TCCR1D, OC1BV);
else if(pin == 1)
sbi(TCCR1D, OC1BU);
// cbi(TCCR1D, OC1BW);//used by crystal
// sbi(TCCR1D, OC1BX);//reset pin
}
void pwmDisconnect(uint8_t pin)
{
pinMode(pin,OUTPUT);
if(pin == 2)
cbi(TCCR1D, OC1AV);
else if(pin == 0)
cbi(TCCR1D, OC1AU);
// cbi(TCCR1D, OC1AW);//used by crystal
else if(pin == 3)
cbi(TCCR1D, OC1AX);
else if(pin == 4)
cbi(TCCR1D, OC1BV);
else if(pin == 1)
cbi(TCCR1D, OC1BU);
// cbi(TCCR1D, OC1BW);//used by crystal
// cbi(TCCR1D, OC1BX);//reset pin
}
// 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
{
uint8_t timer = digitalPinToTimer(pin);
if( timer == TIMER0A){
// connect pwm to pin 8 on timer 0, channel A
sbi(TCCR0A, COM0A1);
cbi(TCCR0A, COM0A0);
sbi(TCCR0A, WGM01);
sbi(TCCR0A, WGM00);
OCR0A = val; // set pwm duty
} else
if( timer == TIMER1A){
// connect pwm to pin on timer 1, channel A
sbi(TCCR1A, COM1A1);
sbi(TCCR1A, WGM10);
cbi(TCCR1A, COM1A0);
sbi(TCCR1B, WGM10);
sbi(TCCR1B, CS11);
//sbi(TCCR1B, CS10);
cbi(TCCR1D, OC1AV);
cbi(TCCR1D, OC1AU);
cbi(TCCR1D, OC1AW);
cbi(TCCR1D, OC1AX);
if(pin == 2)
sbi(TCCR1D, OC1AV);
else if(pin == 0)
sbi(TCCR1D, OC1AU);
else if(pin == 3)
sbi(TCCR1D, OC1AX);
OCR1A = val; // set pwm duty
} else
if( timer == TIMER1B){
// connect pwm to pin on timer 1, channel B
sbi(TCCR1A, COM1B1);
sbi(TCCR1A, WGM10);
cbi(TCCR1A, COM1B0);
sbi(TCCR1B, WGM10);
sbi(TCCR1B, CS11);
//sbi(TCCR1B, CS10);
cbi(TCCR1D, OC1BV);
cbi(TCCR1D, OC1BU);
cbi(TCCR1D, OC1BW);
cbi(TCCR1D, OC1BX);
if(pin == 4)
sbi(TCCR1D, OC1BV);
else if(pin == 1)
sbi(TCCR1D, OC1BU);
OCR1B = val; // set pwm duty
} else
{
if (val < 128)
{
digitalWrite(pin, LOW);
}
else
{
digitalWrite(pin, HIGH);
}
}
}
}

View File

@@ -0,0 +1,160 @@
/*
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
$Id: wiring.c 248 2007-02-03 15:36:30Z mellis $
Modified 28-08-2009 for attiny84 R.Wiersma
Modified 14-10-2009 for attiny45 Saposoft
*/
#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;
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;
}
}
static void turnOffPWM(uint8_t timer)
{
#if defined(TCCR0A) && defined(COM0A1)
if( timer == TIMER0A){
cbi(TCCR0A, COM0A1);
cbi(TCCR0A, COM0A0);
} else
#endif
#if defined(TCCR0A) && defined(COM0B1)
if( timer == TIMER0B){
cbi(TCCR0A, COM0B1);
cbi(TCCR0A, COM0B0);
} else
#endif
#if defined(TCCR1A) && defined(COM1A1)
if( timer == TIMER1A){
cbi(TCCR1A, COM1A1);
cbi(TCCR1A, COM1A0);
} else
#endif
#if defined(TCCR1) && defined(COM1A1)
if(timer == TIMER1A){
cbi(TCCR1, COM1A1);
cbi(TCCR1, COM1A0);
#ifdef OC1AX
cbi(TCCR1D, OC1AX);
#endif
} else
#endif
#if defined(TCCR1A) && defined(COM1B1)
if( timer == TIMER1B){
cbi(TCCR1A, COM1B1);
cbi(TCCR1A, COM1B0);
#ifdef OC1BV
cbi(TCCR1D, OC1BV);
#endif
} else
#endif
#if defined(TCCR1) && defined(COM1B1)
if( timer == TIMER1B){
cbi(GTCCR, COM1B1);
cbi(GTCCR, COM1B0);
} else
#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);
if (val == LOW) {
uint8_t oldSREG = SREG;
cli();
*out &= ~bit;
SREG = oldSREG;
} else {
uint8_t oldSREG = SREG;
cli();
*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;
}

View File

@@ -0,0 +1,178 @@
/*
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
$Id: wiring.h 239 2007-01-12 17:58:39Z mellis $
Modified 28-08-2009 for attiny84 R.Wiersma
*/
#ifndef WiringPrivate_h
#define WiringPrivate_h
#include <avr/io.h>
#include <avr/interrupt.h>
#include <stdio.h>
#include <stdarg.h>
#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
#if defined( EXT_INT0_vect )
#define EXTERNAL_INTERRUPT_0_vect EXT_INT0_vect
#elif defined( INT0_vect )
#define EXTERNAL_INTERRUPT_0_vect INT0_vect
#endif
#if defined( EXT_INT1_vect )
#define EXTERNAL_INTERRUPT_1_vect EXT_INT1_vect
#elif defined( INT1_vect )
#define EXTERNAL_INTERRUPT_1_vect INT1_vect
#endif
#if defined( EXT_INT2_vect )
#define EXTERNAL_INTERRUPT_2_vect EXT_INT2_vect
#elif defined( INT2_vect )
#define EXTERNAL_INTERRUPT_2_vect INT2_vect
#endif
#if defined( EXT_INT3_vect )
#define EXTERNAL_INTERRUPT_3_vect EXT_INT3_vect
#elif defined( INT3_vect )
#define EXTERNAL_INTERRUPT_3_vect INT3_vect
#endif
#if defined( EXT_INT4_vect )
#define EXTERNAL_INTERRUPT_4_vect EXT_INT4_vect
#elif defined( INT4_vect )
#define EXTERNAL_INTERRUPT_4_vect INT4_vect
#endif
#if defined( EXT_INT5_vect )
#define EXTERNAL_INTERRUPT_5_vect EXT_INT5_vect
#elif defined( INT5_vect )
#define EXTERNAL_INTERRUPT_5_vect INT5_vect
#endif
#if defined( EXT_INT6_vect )
#define EXTERNAL_INTERRUPT_6_vect EXT_INT6_vect
#elif defined( INT6_vect )
#define EXTERNAL_INTERRUPT_6_vect INT6_vect
#endif
#if defined( EXT_INT7_vect )
#define EXTERNAL_INTERRUPT_7_vect EXT_INT7_vect
#elif defined( INT7_vect )
#define EXTERNAL_INTERRUPT_7_vect INT7_vect
#endif
#if defined( EXT_INT8_vect )
#define EXTERNAL_INTERRUPT_8_vect EXT_INT8_vect
#elif defined( INT8_vect )
#define EXTERNAL_INTERRUPT_8_vect INT8_vect
#endif
#if defined( EXT_INT9_vect )
#define EXTERNAL_INTERRUPT_9_vect EXT_INT9_vect
#elif defined( INT9_vect )
#define EXTERNAL_INTERRUPT_9_vect INT9_vect
#endif
#if defined( EXTERNAL_INTERRUPT_9_vect )
#define NUMBER_EXTERNAL_INTERRUPTS (10)
#elif defined( EXTERNAL_INTERRUPT_8_vect )
#define NUMBER_EXTERNAL_INTERRUPTS (9)
#elif defined( EXTERNAL_INTERRUPT_7_vect )
#define NUMBER_EXTERNAL_INTERRUPTS (8)
#elif defined( EXTERNAL_INTERRUPT_6_vect )
#define NUMBER_EXTERNAL_INTERRUPTS (7)
#elif defined( EXTERNAL_INTERRUPT_5_vect )
#define NUMBER_EXTERNAL_INTERRUPTS (6)
#elif defined( EXTERNAL_INTERRUPT_4_vect )
#define NUMBER_EXTERNAL_INTERRUPTS (5)
#elif defined( EXTERNAL_INTERRUPT_3_vect )
#define NUMBER_EXTERNAL_INTERRUPTS (4)
#elif defined( EXTERNAL_INTERRUPT_2_vect )
#define NUMBER_EXTERNAL_INTERRUPTS (3)
#elif defined( EXTERNAL_INTERRUPT_1_vect )
#define NUMBER_EXTERNAL_INTERRUPTS (2)
#elif defined( EXTERNAL_INTERRUPT_0_vect )
#define NUMBER_EXTERNAL_INTERRUPTS (1)
#else
#define NUMBER_EXTERNAL_INTERRUPTS (0)
#endif
#if NUMBER_EXTERNAL_INTERRUPTS >= 1
#define EXTERNAL_INTERRUPT_0 (0)
#endif
#if NUMBER_EXTERNAL_INTERRUPTS >= 2
#define EXTERNAL_INTERRUPT_1 (1)
#endif
#if NUMBER_EXTERNAL_INTERRUPTS >= 3
#define EXTERNAL_INTERRUPT_2 (2)
#endif
#if NUMBER_EXTERNAL_INTERRUPTS >= 4
#define EXTERNAL_INTERRUPT_3 (3)
#endif
#if NUMBER_EXTERNAL_INTERRUPTS >= 5
#define EXTERNAL_INTERRUPT_4 (4)
#endif
#if NUMBER_EXTERNAL_INTERRUPTS >= 6
#define EXTERNAL_INTERRUPT_5 (5)
#endif
#if NUMBER_EXTERNAL_INTERRUPTS >= 7
#define EXTERNAL_INTERRUPT_6 (6)
#endif
#if NUMBER_EXTERNAL_INTERRUPTS >= 8
#define EXTERNAL_INTERRUPT_7 (7)
#endif
#if NUMBER_EXTERNAL_INTERRUPTS >= 9
#define EXTERNAL_INTERRUPT_8 (8)
#endif
#if NUMBER_EXTERNAL_INTERRUPTS >= 10
#define EXTERNAL_INTERRUPT_9 (9)
#endif
typedef void (*voidFuncPtr)(void);
#ifdef __cplusplus
} // extern "C"
#endif
#endif

View File

@@ -0,0 +1,69 @@
/*
wiring_pulse.c - pulseIn() function
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
$Id: wiring.c 248 2007-02-03 15:36:30Z mellis $
*/
#include "wiring_private.h"
#include "pins_arduino.h"
/* 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
* to 3 minutes in length, but must be called at least a few dozen microseconds
* before the start of the pulse. */
unsigned long pulseIn(uint8_t pin, uint8_t state, unsigned long timeout)
{
// cache the port and bit of the pin in order to speed up the
// pulse width measuring loop and achieve finer resolution. calling
// digitalRead() instead yields much coarser resolution.
uint8_t bit = digitalPinToBitMask(pin);
uint8_t port = digitalPinToPort(pin);
uint8_t stateMask = (state ? bit : 0);
unsigned long width = 0; // keep initialization out of time critical area
// convert the timeout from microseconds to a number of times through
// the initial loop; it takes 16 clock cycles per iteration.
unsigned long numloops = 0;
unsigned long maxloops = microsecondsToClockCycles(timeout) / 16;
// wait for any previous pulse to end
while ((*portInputRegister(port) & bit) == stateMask)
if (numloops++ == maxloops)
return 0;
// wait for the pulse to start
while ((*portInputRegister(port) & bit) != stateMask)
if (numloops++ == maxloops)
return 0;
// wait for the pulse to stop
while ((*portInputRegister(port) & bit) == stateMask) {
if (numloops++ == maxloops)
return 0;
width++;
}
// convert the reading to microseconds. The loop has been determined
// to be 20 clock cycles long and have about 16 clocks between the edge
// and the start of the loop. There will be some error introduced by
// the interrupt handlers.
return clockCyclesToMicroseconds(width * 21 + 16);
}

View File

@@ -0,0 +1,55 @@
/*
wiring_shift.c - shiftOut() function
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
$Id: wiring.c 248 2007-02-03 15:36:30Z mellis $
*/
#include "wiring_private.h"
uint8_t shiftIn(uint8_t dataPin, uint8_t clockPin, uint8_t bitOrder) {
uint8_t value = 0;
uint8_t i;
for (i = 0; i < 8; ++i) {
digitalWrite(clockPin, HIGH);
if (bitOrder == LSBFIRST)
value |= digitalRead(dataPin) << i;
else
value |= digitalRead(dataPin) << (7 - i);
digitalWrite(clockPin, LOW);
}
return value;
}
void shiftOut(uint8_t dataPin, uint8_t clockPin, uint8_t bitOrder, uint8_t val)
{
uint8_t i;
for (i = 0; i < 8; i++) {
if (bitOrder == LSBFIRST)
digitalWrite(dataPin, !!(val & (1 << i)));
else
digitalWrite(dataPin, !!(val & (1 << (7 - i))));
digitalWrite(clockPin, HIGH);
digitalWrite(clockPin, LOW);
}
}