mirror of
https://github.com/arduino/Arduino.git
synced 2025-02-18 12:54:25 +01:00
Cleaning up the core (modified version of a patch by Jim Studt): moving pin definitions to program space to save RAM, changing core function arguments (e.g. pinMode(), digitalWrite()) to uint8_t, restoring old SREG after delayMicroseconds() instead of always enabling interrupts, etc.
This commit is contained in:
parent
440033c814
commit
d277488310
@ -64,7 +64,7 @@ void HardwareSerial::print(char c)
|
||||
printByte(c);
|
||||
}
|
||||
|
||||
void HardwareSerial::print(char c[])
|
||||
void HardwareSerial::print(const char c[])
|
||||
{
|
||||
printString(c);
|
||||
}
|
||||
@ -120,7 +120,7 @@ void HardwareSerial::println(char c)
|
||||
println();
|
||||
}
|
||||
|
||||
void HardwareSerial::println(char c[])
|
||||
void HardwareSerial::println(const char c[])
|
||||
{
|
||||
print(c);
|
||||
println();
|
||||
|
@ -40,7 +40,7 @@ class HardwareSerial
|
||||
int read(void);
|
||||
void flush(void);
|
||||
void print(char);
|
||||
void print(char[]);
|
||||
void print(const char[]);
|
||||
void print(uint8_t);
|
||||
void print(int);
|
||||
void print(unsigned int);
|
||||
@ -49,7 +49,7 @@ class HardwareSerial
|
||||
void print(long, int);
|
||||
void println(void);
|
||||
void println(char);
|
||||
void println(char[]);
|
||||
void println(const char[]);
|
||||
void println(uint8_t);
|
||||
void println(int);
|
||||
void println(long);
|
||||
|
@ -13,4 +13,4 @@
|
||||
long random(long);
|
||||
long random(long, long);
|
||||
void randomSeed(unsigned int);
|
||||
#endif
|
||||
#endif
|
||||
|
@ -24,39 +24,33 @@
|
||||
|
||||
#include <avr/io.h>
|
||||
#include "wiring_private.h"
|
||||
#include "pins_arduino.h"
|
||||
|
||||
// On the Arduino board, digital pins are also used
|
||||
// for the analog output (software PWM). Analog input
|
||||
// pins are a separate set.
|
||||
|
||||
// ATMEL ATMEGA8 / ARDUINO
|
||||
// ATMEL ATMEGA8 & 168 / ARDUINO
|
||||
//
|
||||
// +-\/-+
|
||||
// PC6 1| |28 PC5 (AI 5)
|
||||
// (D 0) PD0 2| |27 PC4 (AI 4)
|
||||
// (D 1) PD1 3| |26 PC3 (AI 3)
|
||||
// (D 2) PD2 4| |25 PC2 (AI 2)
|
||||
// (D 3) PD3 5| |24 PC1 (AI 1)
|
||||
// (D 4) PD4 6| |23 PC0 (AI 0)
|
||||
// VCC 7| |22 GND
|
||||
// GND 8| |21 AREF
|
||||
// PB6 9| |20 AVCC
|
||||
// PB7 10| |19 PB5 (D 13)
|
||||
// (D 5) PD5 11| |18 PB4 (D 12)
|
||||
// (D 6) PD6 12| |17 PB3 (D 11) PWM
|
||||
// (D 7) PD7 13| |16 PB2 (D 10) PWM
|
||||
// (D 8) PB0 14| |15 PB1 (D 9) PWM
|
||||
// +----+
|
||||
// +-\/-+
|
||||
// PC6 1| |28 PC5 (AI 5)
|
||||
// (D 0) PD0 2| |27 PC4 (AI 4)
|
||||
// (D 1) PD1 3| |26 PC3 (AI 3)
|
||||
// (D 2) PD2 4| |25 PC2 (AI 2)
|
||||
// PWM+ (D 3) PD3 5| |24 PC1 (AI 1)
|
||||
// (D 4) PD4 6| |23 PC0 (AI 0)
|
||||
// VCC 7| |22 GND
|
||||
// GND 8| |21 AREF
|
||||
// PB6 9| |20 AVCC
|
||||
// PB7 10| |19 PB5 (D 13)
|
||||
// PWM+ (D 5) PD5 11| |18 PB4 (D 12)
|
||||
// PWM+ (D 6) PD6 12| |17 PB3 (D 11) PWM
|
||||
// (D 7) PD7 13| |16 PB2 (D 10) PWM
|
||||
// (D 8) PB0 14| |15 PB1 (D 9) PWM
|
||||
// +----+
|
||||
//
|
||||
// (PWM+ indicates the additional PWM pins on the ATmega168.)
|
||||
|
||||
#define NUM_DIGITAL_PINS 14
|
||||
#define NUM_ANALOG_OUT_PINS 11
|
||||
#if defined(__AVR_ATmega168__)
|
||||
#define NUM_ANALOG_IN_PINS 8
|
||||
#else
|
||||
#define NUM_ANALOG_IN_PINS 6
|
||||
#endif
|
||||
|
||||
#define NUM_PORTS 4
|
||||
|
||||
#define PB 2
|
||||
#define PC 3
|
||||
@ -65,53 +59,78 @@
|
||||
// these arrays map port names (e.g. port B) to the
|
||||
// appropriate addresses for various functions (e.g. reading
|
||||
// and writing)
|
||||
int port_to_mode[NUM_PORTS + 1] = {
|
||||
const uint8_t PROGMEM port_to_mode_PGM[] = {
|
||||
NOT_A_PORT,
|
||||
NOT_A_PORT,
|
||||
_SFR_IO_ADDR(DDRB),
|
||||
_SFR_IO_ADDR(DDRC),
|
||||
_SFR_IO_ADDR(DDRD),
|
||||
&DDRB,
|
||||
&DDRC,
|
||||
&DDRD,
|
||||
};
|
||||
|
||||
int port_to_output[NUM_PORTS + 1] = {
|
||||
const uint8_t PROGMEM port_to_output_PGM[] = {
|
||||
NOT_A_PORT,
|
||||
NOT_A_PORT,
|
||||
_SFR_IO_ADDR(PORTB),
|
||||
_SFR_IO_ADDR(PORTC),
|
||||
_SFR_IO_ADDR(PORTD),
|
||||
&PORTB,
|
||||
&PORTC,
|
||||
&PORTD,
|
||||
};
|
||||
|
||||
int port_to_input[NUM_PORTS + 1] = {
|
||||
const uint8_t PROGMEM port_to_input_PGM[] = {
|
||||
NOT_A_PORT,
|
||||
NOT_A_PORT,
|
||||
_SFR_IO_ADDR(PINB),
|
||||
_SFR_IO_ADDR(PINC),
|
||||
_SFR_IO_ADDR(PIND),
|
||||
&PINB,
|
||||
&PINC,
|
||||
&PIND,
|
||||
};
|
||||
|
||||
// these arrays map the pin numbers on the arduino
|
||||
// board to the atmega8 port and pin numbers
|
||||
pin_t digital_pin_to_port_array[NUM_DIGITAL_PINS] = {
|
||||
{ PD, 0 },
|
||||
{ PD, 1 },
|
||||
{ PD, 2 },
|
||||
{ PD, 3 },
|
||||
{ PD, 4 },
|
||||
{ PD, 5 },
|
||||
{ PD, 6 },
|
||||
{ PD, 7 },
|
||||
{ PB, 0 },
|
||||
{ PB, 1 },
|
||||
{ PB, 2 },
|
||||
{ PB, 3 },
|
||||
{ PB, 4 },
|
||||
{ PB, 5 },
|
||||
const uint8_t PROGMEM digital_pin_to_port_PGM[] = {
|
||||
PD, /* 0 */
|
||||
PD,
|
||||
PD,
|
||||
PD,
|
||||
PD,
|
||||
PD,
|
||||
PD,
|
||||
PD,
|
||||
PB, /* 8 */
|
||||
PB,
|
||||
PB,
|
||||
PB,
|
||||
PB,
|
||||
PB,
|
||||
PC, /* 14 */
|
||||
PC,
|
||||
PC,
|
||||
PC,
|
||||
PC,
|
||||
PC,
|
||||
};
|
||||
|
||||
pin_t *digital_pin_to_port = digital_pin_to_port_array;
|
||||
const uint8_t PROGMEM digital_pin_to_bit_mask_PGM[] = {
|
||||
_BV(0), /* 0, port D */
|
||||
_BV(1),
|
||||
_BV(2),
|
||||
_BV(3),
|
||||
_BV(4),
|
||||
_BV(5),
|
||||
_BV(6),
|
||||
_BV(7),
|
||||
_BV(0), /* 8, port B */
|
||||
_BV(1),
|
||||
_BV(2),
|
||||
_BV(3),
|
||||
_BV(4),
|
||||
_BV(5),
|
||||
_BV(0), /* 14, port C */
|
||||
_BV(1),
|
||||
_BV(2),
|
||||
_BV(3),
|
||||
_BV(4),
|
||||
_BV(5),
|
||||
};
|
||||
|
||||
int analog_out_pin_to_timer_array[NUM_DIGITAL_PINS] = {
|
||||
NOT_ON_TIMER,
|
||||
const uint8_t PROGMEM digital_pin_to_timer_PGM[] = {
|
||||
NOT_ON_TIMER, /* 0 - port D */
|
||||
NOT_ON_TIMER,
|
||||
NOT_ON_TIMER,
|
||||
// on the ATmega168, digital pin 3 has hardware pwm
|
||||
@ -130,7 +149,7 @@ int analog_out_pin_to_timer_array[NUM_DIGITAL_PINS] = {
|
||||
NOT_ON_TIMER,
|
||||
#endif
|
||||
NOT_ON_TIMER,
|
||||
NOT_ON_TIMER,
|
||||
NOT_ON_TIMER, /* 8 - port B */
|
||||
TIMER1A,
|
||||
TIMER1B,
|
||||
#if defined(__AVR_ATmega168__)
|
||||
@ -140,42 +159,11 @@ int analog_out_pin_to_timer_array[NUM_DIGITAL_PINS] = {
|
||||
#endif
|
||||
NOT_ON_TIMER,
|
||||
NOT_ON_TIMER,
|
||||
NOT_ON_TIMER,
|
||||
NOT_ON_TIMER, /* 14 - port C */
|
||||
NOT_ON_TIMER,
|
||||
NOT_ON_TIMER,
|
||||
NOT_ON_TIMER,
|
||||
NOT_ON_TIMER,
|
||||
};
|
||||
|
||||
int *analog_out_pin_to_timer = analog_out_pin_to_timer_array;
|
||||
|
||||
/*
|
||||
// Some of the digital pins also support hardware PWM (analog output).
|
||||
pin_t analog_out_pin_to_port_array[NUM_DIGITAL_PINS] = {
|
||||
{ NOT_A_PIN, NOT_A_PIN },
|
||||
{ NOT_A_PIN, NOT_A_PIN },
|
||||
{ NOT_A_PIN, NOT_A_PIN },
|
||||
{ NOT_A_PIN, NOT_A_PIN },
|
||||
{ NOT_A_PIN, NOT_A_PIN },
|
||||
{ NOT_A_PIN, NOT_A_PIN },
|
||||
{ NOT_A_PIN, NOT_A_PIN },
|
||||
{ NOT_A_PIN, NOT_A_PIN },
|
||||
{ NOT_A_PIN, NOT_A_PIN },
|
||||
{ PB, 1 },
|
||||
{ PB, 2 },
|
||||
{ PB, 3 },
|
||||
{ NOT_A_PIN, NOT_A_PIN },
|
||||
{ NOT_A_PIN, NOT_A_PIN },
|
||||
};
|
||||
|
||||
pin_t *analog_out_pin_to_port = analog_out_pin_to_port_array;
|
||||
*/
|
||||
pin_t analog_in_pin_to_port_array[NUM_ANALOG_IN_PINS] = {
|
||||
{ PC, 0 },
|
||||
{ PC, 1 },
|
||||
{ PC, 2 },
|
||||
{ PC, 3 },
|
||||
{ PC, 4 },
|
||||
{ PC, 5 },
|
||||
#if defined(__AVR_ATmega168__)
|
||||
{ NOT_A_PIN, 6 },
|
||||
{ NOT_A_PIN, 7 },
|
||||
#endif
|
||||
};
|
||||
|
||||
pin_t *analog_in_pin_to_port = analog_in_pin_to_port_array;
|
||||
|
65
targets/arduino/pins_arduino.h
Normal file
65
targets/arduino/pins_arduino.h
Normal file
@ -0,0 +1,65 @@
|
||||
/*
|
||||
pins_arduino.h - Pin definition functions for Arduino
|
||||
Part of Arduino - http://www.arduino.cc/
|
||||
|
||||
Copyright (c) 2007 David A. Mellis
|
||||
|
||||
This library is free software; you can redistribute it and/or
|
||||
modify it under the terms of the GNU Lesser General Public
|
||||
License as published by the Free Software Foundation; either
|
||||
version 2.1 of the License, or (at your option) any later version.
|
||||
|
||||
This library is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
|
||||
Lesser General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU Lesser General
|
||||
Public License along with this library; if not, write to the
|
||||
Free Software Foundation, Inc., 59 Temple Place, Suite 330,
|
||||
Boston, MA 02111-1307 USA
|
||||
|
||||
$Id: wiring.h 249 2007-02-03 16:52:51Z mellis $
|
||||
*/
|
||||
|
||||
#ifndef Pins_Arduino_h
|
||||
#define Pins_Arduino_h
|
||||
|
||||
#include <avr/pgmspace.h>
|
||||
|
||||
#define NOT_A_PIN 0
|
||||
#define NOT_A_PORT 0
|
||||
|
||||
#define NOT_ON_TIMER 0
|
||||
#define TIMER0A 1
|
||||
#define TIMER0B 2
|
||||
#define TIMER1A 3
|
||||
#define TIMER1B 4
|
||||
#define TIMER2 5
|
||||
#define TIMER2A 6
|
||||
#define TIMER2B 7
|
||||
|
||||
extern const uint8_t PROGMEM port_to_mode_PGM[];
|
||||
extern const uint8_t PROGMEM port_to_input_PGM[];
|
||||
extern const uint8_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_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_byte( port_to_output_PGM + (P))) )
|
||||
#define portInputRegister(P) ( (volatile uint8_t *)( pgm_read_byte( port_to_input_PGM + (P))) )
|
||||
#define portModeRegister(P) ( (volatile uint8_t *)( pgm_read_byte( port_to_mode_PGM + (P))) )
|
||||
|
||||
#endif
|
@ -59,6 +59,8 @@ void delay(unsigned long ms)
|
||||
* too frequently. */
|
||||
void delayMicroseconds(unsigned int us)
|
||||
{
|
||||
uint8_t oldSREG;
|
||||
|
||||
// calling avrlib's delay_us() function with low values (e.g. 1 or
|
||||
// 2 microseconds) gives delays longer than desired.
|
||||
//delay_us(us);
|
||||
@ -78,6 +80,7 @@ void delayMicroseconds(unsigned int us)
|
||||
|
||||
// disable interrupts, otherwise the timer 0 overflow interrupt that
|
||||
// tracks milliseconds will make us delay longer than we want.
|
||||
oldSREG = SREG;
|
||||
cli();
|
||||
|
||||
// busy wait
|
||||
@ -87,71 +90,7 @@ void delayMicroseconds(unsigned int us)
|
||||
);
|
||||
|
||||
// reenable interrupts.
|
||||
sei();
|
||||
}
|
||||
|
||||
/*
|
||||
unsigned long pulseIn(int pin, int state)
|
||||
{
|
||||
unsigned long width = 0;
|
||||
|
||||
while (digitalRead(pin) == !state)
|
||||
;
|
||||
|
||||
while (digitalRead(pin) != !state)
|
||||
width++;
|
||||
|
||||
return width * 17 / 2; // convert to microseconds
|
||||
}
|
||||
*/
|
||||
|
||||
/* 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 10 microseconds
|
||||
* to 3 minutes in length, but must be called at least N microseconds before
|
||||
* the start of the pulse. */
|
||||
unsigned long pulseIn(int pin, int state)
|
||||
{
|
||||
// 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.
|
||||
int r = port_to_input[digitalPinToPort(pin)];
|
||||
int bit = digitalPinToBit(pin);
|
||||
int mask = 1 << bit;
|
||||
unsigned long width = 0;
|
||||
|
||||
// compute the desired bit pattern for the port reading (e.g. set or
|
||||
// clear the bit corresponding to the pin being read). the !!state
|
||||
// ensures that the function treats any non-zero value of state as HIGH.
|
||||
state = (!!state) << bit;
|
||||
|
||||
// wait for the pulse to start
|
||||
while ((_SFR_IO8(r) & mask) != state)
|
||||
;
|
||||
|
||||
// wait for the pulse to stop
|
||||
while ((_SFR_IO8(r) & mask) == state)
|
||||
width++;
|
||||
|
||||
// convert the reading to microseconds. the slower the CPU speed, the
|
||||
// proportionally fewer iterations of the loop will occur (e.g. a
|
||||
// 4 MHz clock will yield a width that is one-fourth of that read with
|
||||
// a 16 MHz clock). each loop was empirically determined to take
|
||||
// approximately 23/20 of a microsecond with a 16 MHz clock.
|
||||
return width * (16000000UL / F_CPU) * 20 / 23;
|
||||
}
|
||||
|
||||
void shiftOut(int dataPin, int clockPin, int bitOrder, byte val) {
|
||||
int 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);
|
||||
}
|
||||
SREG = oldSREG;
|
||||
}
|
||||
|
||||
void init()
|
||||
|
@ -63,16 +63,19 @@ extern "C"{
|
||||
#define degrees(rad) ((rad)*RAD_TO_DEG)
|
||||
#define sq(x) ((x)*(x))
|
||||
|
||||
#define clockCyclesPerMicrosecond() ( F_CPU / 1000000L )
|
||||
#define clockCyclesToMicroseconds(a) ( (a) / clockCyclesPerMicrosecond() )
|
||||
|
||||
typedef uint8_t boolean;
|
||||
typedef uint8_t byte;
|
||||
|
||||
void init(void);
|
||||
|
||||
void pinMode(int, int);
|
||||
void digitalWrite(int, int);
|
||||
int digitalRead(int);
|
||||
int analogRead(int);
|
||||
void analogWrite(int, int);
|
||||
void pinMode(uint8_t, uint8_t);
|
||||
void digitalWrite(uint8_t, uint8_t);
|
||||
int digitalRead(uint8_t);
|
||||
int analogRead(uint8_t);
|
||||
void analogWrite(uint8_t, int);
|
||||
|
||||
void beginSerial(long);
|
||||
void serialWrite(unsigned char);
|
||||
@ -81,8 +84,8 @@ int serialRead(void);
|
||||
void serialFlush(void);
|
||||
void printMode(int);
|
||||
void printByte(unsigned char c);
|
||||
void printNewline();
|
||||
void printString(char *s);
|
||||
void printNewline(void);
|
||||
void printString(const char *s);
|
||||
void printInteger(long n);
|
||||
void printHex(unsigned long n);
|
||||
void printOctal(unsigned long n);
|
||||
@ -92,9 +95,9 @@ void printIntegerInBase(unsigned long n, unsigned long base);
|
||||
unsigned long millis(void);
|
||||
void delay(unsigned long);
|
||||
void delayMicroseconds(unsigned int us);
|
||||
unsigned long pulseIn(int pin, int state);
|
||||
unsigned long pulseIn(uint8_t pin, uint8_t state);
|
||||
|
||||
void shiftOut(int dataPin, int clockPin, int endianness, byte val);
|
||||
void shiftOut(uint8_t dataPin, uint8_t clockPin, uint8_t bitOrder, byte val);
|
||||
|
||||
void attachInterrupt(uint8_t, void (*)(void), int mode);
|
||||
void detachInterrupt(uint8_t);
|
||||
|
@ -23,10 +23,11 @@
|
||||
*/
|
||||
|
||||
#include "wiring_private.h"
|
||||
#include "pins_arduino.h"
|
||||
|
||||
int analogRead(int pin)
|
||||
int analogRead(uint8_t pin)
|
||||
{
|
||||
unsigned int low, high, ch = analogInPinToBit(pin);
|
||||
uint8_t low, high, ch = analogInPinToBit(pin);
|
||||
|
||||
// the low 4 bits of ADMUX select the ADC channel
|
||||
ADMUX = (ADMUX & (unsigned int) 0xf0) | (ch & (unsigned int) 0x0f);
|
||||
@ -55,7 +56,7 @@ int analogRead(int pin)
|
||||
// hardware support. These are defined in the appropriate
|
||||
// pins_*.c file. For the rest of the pins, we default
|
||||
// to digital output.
|
||||
void analogWrite(int pin, int val)
|
||||
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
|
||||
@ -64,39 +65,39 @@ void analogWrite(int pin, int val)
|
||||
// call for the analog output pins.
|
||||
pinMode(pin, OUTPUT);
|
||||
|
||||
if (analogOutPinToTimer(pin) == TIMER1A) {
|
||||
if (digitalPinToTimer(pin) == TIMER1A) {
|
||||
// connect pwm to pin on timer 1, channel A
|
||||
sbi(TCCR1A, COM1A1);
|
||||
// set pwm duty
|
||||
OCR1A = val;
|
||||
} else if (analogOutPinToTimer(pin) == TIMER1B) {
|
||||
} else if (digitalPinToTimer(pin) == TIMER1B) {
|
||||
// connect pwm to pin on timer 1, channel B
|
||||
sbi(TCCR1A, COM1B1);
|
||||
// set pwm duty
|
||||
OCR1B = val;
|
||||
#if defined(__AVR_ATmega168__)
|
||||
} else if (analogOutPinToTimer(pin) == TIMER0A) {
|
||||
} else if (digitalPinToTimer(pin) == TIMER0A) {
|
||||
// connect pwm to pin on timer 0, channel A
|
||||
sbi(TCCR0A, COM0A1);
|
||||
// set pwm duty
|
||||
OCR0A = val;
|
||||
} else if (analogOutPinToTimer(pin) == TIMER0B) {
|
||||
} else if (digitalPinToTimer(pin) == TIMER0B) {
|
||||
// connect pwm to pin on timer 0, channel B
|
||||
sbi(TCCR0A, COM0B1);
|
||||
// set pwm duty
|
||||
OCR0B = val;
|
||||
} else if (analogOutPinToTimer(pin) == TIMER2A) {
|
||||
} else if (digitalPinToTimer(pin) == TIMER2A) {
|
||||
// connect pwm to pin on timer 2, channel A
|
||||
sbi(TCCR2A, COM2A1);
|
||||
// set pwm duty
|
||||
OCR2A = val;
|
||||
} else if (analogOutPinToTimer(pin) == TIMER2B) {
|
||||
} else if (digitalPinToTimer(pin) == TIMER2B) {
|
||||
// connect pwm to pin on timer 2, channel B
|
||||
sbi(TCCR2A, COM2B1);
|
||||
// set pwm duty
|
||||
OCR2B = val;
|
||||
#else
|
||||
} else if (analogOutPinToTimer(pin) == TIMER2) {
|
||||
} else if (digitalPinToTimer(pin) == TIMER2) {
|
||||
// connect pwm to pin on timer 2, channel B
|
||||
sbi(TCCR2, COM21);
|
||||
// set pwm duty
|
||||
|
@ -23,113 +23,77 @@
|
||||
*/
|
||||
|
||||
#include "wiring_private.h"
|
||||
#include "pins_arduino.h"
|
||||
|
||||
// Get the hardware port of the given virtual pin number. This comes from
|
||||
// the pins_*.c file for the active board configuration.
|
||||
int digitalPinToPort(int pin)
|
||||
void pinMode(uint8_t pin, uint8_t mode)
|
||||
{
|
||||
return digital_pin_to_port[pin].port;
|
||||
uint8_t bit = digitalPinToBitMask(pin);
|
||||
uint8_t port = digitalPinToPort(pin);
|
||||
volatile uint8_t *reg;
|
||||
|
||||
if (port == NOT_A_PIN) return;
|
||||
|
||||
// JWS: can I let the optimizer do this?
|
||||
reg = portModeRegister(port);
|
||||
|
||||
if (mode == INPUT) *reg &= ~bit;
|
||||
else *reg |= bit;
|
||||
}
|
||||
|
||||
// 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.
|
||||
int digitalPinToBit(int pin)
|
||||
// Forcing this inline keeps the callers from having to push their own stuff
|
||||
// on the stack. It is a good performance win and only takes 1 more byte per
|
||||
// user than calling. (It will take more bytes on the 168.)
|
||||
//
|
||||
// But shouldn't this be moved into pinMode? Seems silly to check and do on
|
||||
// each digitalread or write.
|
||||
//
|
||||
static inline void turnOffPWM(uint8_t timer) __attribute__ ((always_inline));
|
||||
static inline void turnOffPWM(uint8_t timer)
|
||||
{
|
||||
return digital_pin_to_port[pin].bit;
|
||||
}
|
||||
if (timer == TIMER1A) cbi(TCCR1A, COM1A1);
|
||||
if (timer == TIMER1B) cbi(TCCR1A, COM1B1);
|
||||
|
||||
int analogOutPinToTimer(int pin)
|
||||
{
|
||||
return analog_out_pin_to_timer[pin];
|
||||
}
|
||||
|
||||
int analogInPinToBit(int pin)
|
||||
{
|
||||
return analog_in_pin_to_port[pin].bit;
|
||||
}
|
||||
|
||||
void pinMode(int pin, int mode)
|
||||
{
|
||||
if (digitalPinToPort(pin) != NOT_A_PIN) {
|
||||
if (mode == INPUT)
|
||||
cbi(_SFR_IO8(port_to_mode[digitalPinToPort(pin)]),
|
||||
digitalPinToBit(pin));
|
||||
else
|
||||
sbi(_SFR_IO8(port_to_mode[digitalPinToPort(pin)]),
|
||||
digitalPinToBit(pin));
|
||||
}
|
||||
}
|
||||
|
||||
void digitalWrite(int pin, int val)
|
||||
{
|
||||
if (digitalPinToPort(pin) != NOT_A_PIN) {
|
||||
// If the pin that support PWM output, we need to turn it off
|
||||
// before doing a digital write.
|
||||
|
||||
if (analogOutPinToTimer(pin) == TIMER1A)
|
||||
cbi(TCCR1A, COM1A1);
|
||||
|
||||
if (analogOutPinToTimer(pin) == TIMER1B)
|
||||
cbi(TCCR1A, COM1B1);
|
||||
|
||||
#if defined(__AVR_ATmega168__)
|
||||
if (analogOutPinToTimer(pin) == TIMER0A)
|
||||
cbi(TCCR0A, COM0A1);
|
||||
|
||||
if (analogOutPinToTimer(pin) == TIMER0B)
|
||||
cbi(TCCR0A, COM0B1);
|
||||
|
||||
if (analogOutPinToTimer(pin) == TIMER2A)
|
||||
cbi(TCCR2A, COM2A1);
|
||||
|
||||
if (analogOutPinToTimer(pin) == TIMER2B)
|
||||
cbi(TCCR2A, COM2B1);
|
||||
if (timer == TIMER0A) cbi(TCCR0A, COM0A1);
|
||||
if (timer == TIMER0B) cbi(TCCR0A, COM0B1);
|
||||
if (timer == TIMER2A) cbi(TCCR2A, COM2A1);
|
||||
if (timer == TIMER2B) cbi(TCCR2A, COM2B1);
|
||||
#else
|
||||
if (analogOutPinToTimer(pin) == TIMER2)
|
||||
cbi(TCCR2, COM21);
|
||||
if (timer == TIMER2) cbi(TCCR2, COM21);
|
||||
#endif
|
||||
|
||||
if (val == LOW)
|
||||
cbi(_SFR_IO8(port_to_output[digitalPinToPort(pin)]),
|
||||
digitalPinToBit(pin));
|
||||
else
|
||||
sbi(_SFR_IO8(port_to_output[digitalPinToPort(pin)]),
|
||||
digitalPinToBit(pin));
|
||||
}
|
||||
}
|
||||
|
||||
int digitalRead(int pin)
|
||||
void digitalWrite(uint8_t pin, uint8_t val)
|
||||
{
|
||||
if (digitalPinToPort(pin) != NOT_A_PIN) {
|
||||
// If the pin that support PWM output, we need to turn it off
|
||||
// before getting a digital reading.
|
||||
uint8_t timer = digitalPinToTimer(pin);
|
||||
uint8_t bit = digitalPinToBitMask(pin);
|
||||
uint8_t port = digitalPinToPort(pin);
|
||||
volatile uint8_t *out;
|
||||
|
||||
if (analogOutPinToTimer(pin) == TIMER1A)
|
||||
cbi(TCCR1A, COM1A1);
|
||||
if (port == NOT_A_PIN) return;
|
||||
|
||||
if (analogOutPinToTimer(pin) == TIMER1B)
|
||||
cbi(TCCR1A, COM1B1);
|
||||
|
||||
#if defined(__AVR_ATmega168__)
|
||||
if (analogOutPinToTimer(pin) == TIMER0A)
|
||||
cbi(TCCR0A, COM0A1);
|
||||
|
||||
if (analogOutPinToTimer(pin) == TIMER0B)
|
||||
cbi(TCCR0A, COM0B1);
|
||||
// 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);
|
||||
|
||||
if (analogOutPinToTimer(pin) == TIMER2A)
|
||||
cbi(TCCR2A, COM2A1);
|
||||
|
||||
if (analogOutPinToTimer(pin) == TIMER2B)
|
||||
cbi(TCCR2A, COM2B1);
|
||||
#else
|
||||
if (analogOutPinToTimer(pin) == TIMER2)
|
||||
cbi(TCCR2, COM21);
|
||||
#endif
|
||||
out = portOutputRegister(port);
|
||||
|
||||
return (_SFR_IO8(port_to_input[digitalPinToPort(pin)]) >>
|
||||
digitalPinToBit(pin)) & 0x01;
|
||||
}
|
||||
|
||||
if (val == LOW) *out &= ~bit;
|
||||
else *out |= bit;
|
||||
}
|
||||
|
||||
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;
|
||||
}
|
||||
|
@ -45,29 +45,8 @@ extern "C"{
|
||||
#define sbi(sfr, bit) (_SFR_BYTE(sfr) |= _BV(bit))
|
||||
#endif
|
||||
|
||||
#define NOT_A_PIN 0
|
||||
#define NOT_A_PORT -1
|
||||
|
||||
#define NOT_ON_TIMER -1
|
||||
#define TIMER0A 0
|
||||
#define TIMER0B 1
|
||||
#define TIMER1A 2
|
||||
#define TIMER1B 3
|
||||
#define TIMER2 4
|
||||
#define TIMER2A 5
|
||||
#define TIMER2B 6
|
||||
|
||||
typedef struct {
|
||||
int port;
|
||||
int bit;
|
||||
} pin_t;
|
||||
|
||||
extern int port_to_mode[];
|
||||
extern int port_to_input[];
|
||||
extern int port_to_output[];
|
||||
extern pin_t *digital_pin_to_port;
|
||||
extern pin_t *analog_in_pin_to_port;
|
||||
extern int *analog_out_pin_to_timer;
|
||||
#define clockCyclesPerMicrosecond() ( F_CPU / 1000000L )
|
||||
#define clockCyclesToMicroseconds(a) ( (a) / clockCyclesPerMicrosecond() )
|
||||
|
||||
#define EXTERNAL_INT_0 0
|
||||
#define EXTERNAL_INT_1 1
|
||||
|
@ -23,53 +23,33 @@
|
||||
*/
|
||||
|
||||
#include "wiring_private.h"
|
||||
|
||||
/*
|
||||
unsigned long pulseIn(int pin, int state)
|
||||
{
|
||||
unsigned long width = 0;
|
||||
|
||||
while (digitalRead(pin) == !state)
|
||||
;
|
||||
|
||||
while (digitalRead(pin) != !state)
|
||||
width++;
|
||||
|
||||
return width * 17 / 2; // convert to microseconds
|
||||
}
|
||||
*/
|
||||
#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 10 microseconds
|
||||
* to 3 minutes in length, but must be called at least N microseconds before
|
||||
* the start of the pulse. */
|
||||
unsigned long pulseIn(int pin, int state)
|
||||
unsigned long pulseIn(uint8_t pin, uint8_t state)
|
||||
{
|
||||
// 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.
|
||||
int r = port_to_input[digitalPinToPort(pin)];
|
||||
int bit = digitalPinToBit(pin);
|
||||
int mask = 1 << bit;
|
||||
unsigned long width = 0;
|
||||
|
||||
// compute the desired bit pattern for the port reading (e.g. set or
|
||||
// clear the bit corresponding to the pin being read). the !!state
|
||||
// ensures that the function treats any non-zero value of state as HIGH.
|
||||
state = (!!state) << bit;
|
||||
|
||||
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
|
||||
|
||||
// wait for the pulse to start
|
||||
while ((_SFR_IO8(r) & mask) != state)
|
||||
while ((*portInputRegister(port) & bit) != stateMask)
|
||||
;
|
||||
|
||||
// wait for the pulse to stop
|
||||
while ((_SFR_IO8(r) & mask) == state)
|
||||
while ((*portInputRegister(port) & bit) == stateMask)
|
||||
width++;
|
||||
|
||||
// convert the reading to microseconds. the slower the CPU speed, the
|
||||
// proportionally fewer iterations of the loop will occur (e.g. a
|
||||
// 4 MHz clock will yield a width that is one-fourth of that read with
|
||||
// a 16 MHz clock). each loop was empirically determined to take
|
||||
// approximately 23/20 of a microsecond with a 16 MHz clock.
|
||||
return width * (16000000UL / F_CPU) * 20 / 23;
|
||||
|
||||
// convert the reading to microseconds. The loop has been determined
|
||||
// to be 10 clock cycles long and have about 12 clocks between the edge
|
||||
// and the start of the loop. There will be some error introduced by
|
||||
// the interrupt handlers.
|
||||
return clockCyclesToMicroseconds(width * 10 + 12);
|
||||
}
|
||||
|
@ -143,7 +143,7 @@ void printNewline()
|
||||
printByte('\n');
|
||||
}
|
||||
|
||||
void printString(char *s)
|
||||
void printString(const char *s)
|
||||
{
|
||||
while (*s)
|
||||
printByte(*s++);
|
||||
|
@ -24,7 +24,8 @@
|
||||
|
||||
#include "wiring_private.h"
|
||||
|
||||
void shiftOut(int dataPin, int clockPin, int bitOrder, byte val) {
|
||||
void shiftOut(uint8_t dataPin, uint8_t clockPin, uint8_t bitOrder, byte val)
|
||||
{
|
||||
int i;
|
||||
|
||||
for (i = 0; i < 8; i++) {
|
||||
|
Loading…
x
Reference in New Issue
Block a user