From e6e9334e4c45d6e2e390b09e7b3e6cd1a3258e14 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Oct 2011 09:16:30 +1100 Subject: [PATCH 01/15] memcheck: allow memcheck to build on desktop systems --- libraries/memcheck/memcheck.cpp | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/libraries/memcheck/memcheck.cpp b/libraries/memcheck/memcheck.cpp index 91493bfddc..c1820762d9 100644 --- a/libraries/memcheck/memcheck.cpp +++ b/libraries/memcheck/memcheck.cpp @@ -29,7 +29,7 @@ static __attribute__((noinline)) const uint32_t *current_stackptr(void) void memcheck_update_stackptr(void) { if (current_stackptr() < stack_low) { - unsigned s = (unsigned)(current_stackptr() - STACK_OFFSET); + unsigned s = (uintptr_t)(current_stackptr() - STACK_OFFSET); stack_low = (uint32_t *)(s & ~3); } } @@ -39,6 +39,7 @@ void memcheck_update_stackptr(void) */ void memcheck_init(void) { +#ifndef DESKTOP_BUILD uint32_t *p; free(malloc(1)); // ensure heap is initialised stack_low = current_stackptr(); @@ -46,6 +47,7 @@ void memcheck_init(void) for (p=(uint32_t *)(stack_low-1); p>(uint32_t *)__brkval; p--) { *p = SENTINEL; } +#endif } /* @@ -54,9 +56,13 @@ void memcheck_init(void) */ unsigned memcheck_available_memory(void) { +#ifdef DESKTOP_BUILD + return 0x1000; +#else memcheck_update_stackptr(); while (*stack_low != SENTINEL && stack_low > (const uint32_t *)__brkval) { stack_low--; } - return (unsigned)(stack_low) - __brkval; + return (uintptr_t)(stack_low) - __brkval; +#endif } From e1778001168c59b3fca7df4d1acb0dd650bad4af Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Oct 2011 09:16:52 +1100 Subject: [PATCH 02/15] fixed PROGMEM declaration for desktop build --- libraries/AP_Common/AP_Common.h | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/libraries/AP_Common/AP_Common.h b/libraries/AP_Common/AP_Common.h index 0c585f4c7a..fe0a3c9e99 100644 --- a/libraries/AP_Common/AP_Common.h +++ b/libraries/AP_Common/AP_Common.h @@ -77,8 +77,14 @@ typedef struct { // has an equivalent effect but avoids the warnings, which otherwise // make finding real issues difficult. // +#if DESKTOP_BUILD +# undef PROGMEM +# define PROGMEM __attribute__(()) +#else # undef PROGMEM # define PROGMEM __attribute__(( section(".progmem.data") )) +#endif + # undef PSTR # define PSTR(s) (__extension__({static prog_char __c[] PROGMEM = (s); \ (prog_char_t *)&__c[0];})) From 4109374959412ca210472a7816bad95ed17c1429 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Oct 2011 09:18:23 +1100 Subject: [PATCH 03/15] first rough build for desktop CPUs this allows ArduPlane to build and startup on 'desktop' systems (eg. a Linux box). Very rough for now, and only for HIL so far --- libraries/AP_Common/Desktop.mk | 430 ++++++ libraries/Desktop/include/HardwareSerial.h | 76 + libraries/Desktop/include/Print.h | 66 + libraries/Desktop/include/SPI.h | 70 + libraries/Desktop/include/Stream.h | 16 + libraries/Desktop/include/WConstants.h | 1 + libraries/Desktop/include/WProgram.h | 29 + libraries/Desktop/include/WString.h | 112 ++ libraries/Desktop/include/Wire.h | 67 + libraries/Desktop/include/avr/eeprom.h | 24 + libraries/Desktop/include/avr/interrupt.h | 12 + libraries/Desktop/include/avr/io.h | 21 + libraries/Desktop/include/avr/iom2560.h | 94 ++ libraries/Desktop/include/avr/iomxx0_1.h | 1553 ++++++++++++++++++++ libraries/Desktop/include/avr/pgmspace.h | 49 + libraries/Desktop/include/avr/wiring.h | 0 libraries/Desktop/include/binary.h | 515 +++++++ libraries/Desktop/include/pins_arduino.h | 88 ++ libraries/Desktop/include/wiring.h | 135 ++ libraries/Desktop/support/Arduino.cpp | 124 ++ libraries/Desktop/support/FastSerial.cpp | 122 ++ libraries/Desktop/support/Print.cpp | 220 +++ libraries/Desktop/support/SPI.cpp | 61 + libraries/Desktop/support/WString.cpp | 443 ++++++ libraries/Desktop/support/eeprom.c | 86 ++ libraries/Desktop/support/ftoa_engine.c | 7 + libraries/Desktop/support/main.cpp | 16 + libraries/Desktop/support/ultoa_invert.c | 12 + 28 files changed, 4449 insertions(+) create mode 100644 libraries/AP_Common/Desktop.mk create mode 100644 libraries/Desktop/include/HardwareSerial.h create mode 100644 libraries/Desktop/include/Print.h create mode 100644 libraries/Desktop/include/SPI.h create mode 100644 libraries/Desktop/include/Stream.h create mode 100644 libraries/Desktop/include/WConstants.h create mode 100644 libraries/Desktop/include/WProgram.h create mode 100644 libraries/Desktop/include/WString.h create mode 100644 libraries/Desktop/include/Wire.h create mode 100644 libraries/Desktop/include/avr/eeprom.h create mode 100644 libraries/Desktop/include/avr/interrupt.h create mode 100644 libraries/Desktop/include/avr/io.h create mode 100644 libraries/Desktop/include/avr/iom2560.h create mode 100644 libraries/Desktop/include/avr/iomxx0_1.h create mode 100644 libraries/Desktop/include/avr/pgmspace.h create mode 100644 libraries/Desktop/include/avr/wiring.h create mode 100644 libraries/Desktop/include/binary.h create mode 100644 libraries/Desktop/include/pins_arduino.h create mode 100644 libraries/Desktop/include/wiring.h create mode 100644 libraries/Desktop/support/Arduino.cpp create mode 100644 libraries/Desktop/support/FastSerial.cpp create mode 100644 libraries/Desktop/support/Print.cpp create mode 100644 libraries/Desktop/support/SPI.cpp create mode 100644 libraries/Desktop/support/WString.cpp create mode 100644 libraries/Desktop/support/eeprom.c create mode 100644 libraries/Desktop/support/ftoa_engine.c create mode 100644 libraries/Desktop/support/main.cpp create mode 100644 libraries/Desktop/support/ultoa_invert.c diff --git a/libraries/AP_Common/Desktop.mk b/libraries/AP_Common/Desktop.mk new file mode 100644 index 0000000000..c5bf1d6be7 --- /dev/null +++ b/libraries/AP_Common/Desktop.mk @@ -0,0 +1,430 @@ +# +# Copyright (c) 2010 Andrew Tridgell. All rights reserved. +# based on Arduino.mk, Copyright (c) 2010 Michael Smith +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in the +# documentation and/or other materials provided with the distribution. +# +# THIS SOFTWARE IS PROVIDED BY THE AUTHOR AND CONTRIBUTORS ``AS IS'' AND +# ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +# ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE +# FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +# DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS +# OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) +# HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY +# OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF +# SUCH DAMAGE. +# + +# +# Locate the sketch sources based on the initial Makefile's path +# +SRCROOT := $(realpath $(dir $(firstword $(MAKEFILE_LIST)))) + +# +# We need to know the location of the sketchbook. If it hasn't been overridden, +# try the parent of the current directory. If there is no libraries directory +# there, assume that we are in a library's examples directory and try backing up +# further. +# +ifeq ($(SKETCHBOOK),) + SKETCHBOOK := $(shell cd $(SRCROOT)/.. && pwd) + ifeq ($(wildcard $(SKETCHBOOK)/libraries),) + SKETCHBOOK := $(shell cd $(SRCROOT)/../.. && pwd) + endif + ifeq ($(wildcard $(SKETCHBOOK)/libraries),) + SKETCHBOOK := $(shell cd $(SRCROOT)/../../.. && pwd) + endif + ifeq ($(wildcard $(SKETCHBOOK)/libraries),) + SKETCHBOOK := $(shell cd $(SRCROOT)/../../../.. && pwd) + endif + ifeq ($(wildcard $(SKETCHBOOK)/libraries),) + $(error ERROR: cannot determine sketchbook location - please specify on the commandline with SKETCHBOOK=) + endif +else + ifeq ($(wildcard $(SKETCHBOOK)/libraries),) + $(warning WARNING: sketchbook directory $(SKETCHBOOK) contains no libraries) + endif +endif + +# +# Work out the sketch name from the name of the source directory. +# +SKETCH := $(lastword $(subst /, ,$(SRCROOT))) +# Workaround a $(lastword ) bug on cygwin +ifeq ($(SKETCH),) + WORDLIST := $(subst /, ,$(SRCROOT)) + SKETCH := $(word $(words $(WORDLIST)),$(WORDLIST)) +endif + +# +# Work out where we are going to be building things +# +TMPDIR ?= /tmp +BUILDROOT := $(abspath $(TMPDIR)/$(SKETCH).build) +ifneq ($(findstring CYGWIN, $(SYSTYPE)),) + # Workaround a $(abspath ) bug on cygwin + ifeq ($(BUILDROOT),) + BUILDROOT := C:$(TMPDIR)/$(SKETCH).build + $(warning your abspath function is not working) + $(warning > setting BUILDROOT to $(BUILDROOT)) + endif +endif + +# Jump over the next makefile sections when runing a "make configure" +ifneq ($(MAKECMDGOALS),configure) + +HARDWARE=desktop +BOARD=desktop + +CXX := g++ +CC := gcc +AS := gcc +AR := ar +LD := g++ +GDB := gdb +OBJCOPY := objcopy + +# Find awk +AWK ?= gawk +ifeq ($(shell which $(AWK)),) +$(error ERROR: cannot find $(AWK) - you may need to install GNU awk) +endif + +# +# Tool options +# +DEFINES = $(EXTRAFLAGS) +OPTFLAGS = -g -Wformat -Wall -Wshadow -Wpointer-arith -Wcast-align -Wwrite-strings -Wformat=2 -Wno-reorder +DEPFLAGS = -MD -MT $@ + +# XXX warning options TBD +CXXOPTS = -fno-exceptions -D__AVR_ATmega2560__ -I$(SKETCHBOOK)/libraries/Desktop/include -DDESKTOP_BUILD=1 +COPTS = -I$(SKETCHBOOK)/libraries/Desktop/include -DDESKTOP_BUILD=1 +ASOPTS = -assembler-with-cpp + +CXXFLAGS = -g $(DEFINES) $(OPTFLAGS) $(DEPFLAGS) $(CXXOPTS) +CFLAGS = -g $(DEFINES) $(OPTFLAGS) $(DEPFLAGS) $(COPTS) +ASFLAGS = -g $(DEFINES) $(DEPFLAGS) $(ASOPTS) +LDFLAGS = -g $(OPTFLAGS) -Wl,--gc-sections -Wl,-Map -Wl,$(SKETCHMAP) + +LIBS = -lm -lbsd + +SRCSUFFIXES = *.cpp *.c + +ifeq ($(VERBOSE),) +v = @ +else +v = +endif + + +################################################################################ +# Sketch +# + +# Sketch source files +SKETCHPDESRCS := $(wildcard $(SRCROOT)/*.pde) +SKETCHSRCS := $(wildcard $(addprefix $(SRCROOT)/,$(SRCSUFFIXES))) +SKETCHPDE := $(wildcard $(SRCROOT)/$(SKETCH).pde) +SKETCHCPP := $(BUILDROOT)/$(SKETCH).cpp +ifeq ($(SKETCHPDE),) +$(error ERROR: sketch $(SKETCH) is missing $(SKETCH).pde) +endif + +# Sketch object files +SKETCHOBJS := $(subst $(SRCROOT),$(BUILDROOT),$(SKETCHSRCS)) $(SKETCHCPP) +SKETCHOBJS := $(addsuffix .o,$(basename $(SKETCHOBJS))) + +# List of input files to the sketch.cpp file in the order they should +# be appended to create it +SKETCHCPP_SRC := $(SKETCHPDE) $(sort $(filter-out $(SKETCHPDE),$(SKETCHPDESRCS))) + +################################################################################ +# Libraries +# +# Pick libraries to add to the include path and to link with based on +# #include directives in the sketchfiles. +# +# For example: +# +# #include +# +# implies that there might be a Foo library. +# +# Note that the # and $ require special treatment to avoid upsetting +# make. +# +SEXPR = 's/^[[:space:]]*\#include[[:space:]][<\"]([^>\"./]+).*$$/\1/p' +ifeq ($(SYSTYPE),Darwin) + LIBTOKENS := $(sort $(shell cat $(SKETCHPDESRCS) $(SKETCHSRCS) | sed -nEe $(SEXPR))) +else + LIBTOKENS := $(sort $(shell cat $(SKETCHPDESRCS) $(SKETCHSRCS) | sed -nre $(SEXPR))) +endif + +NODESKTOP := FastSerial/FastSerial.cpp + +# +# Find sketchbook libraries referenced by the sketch. +# +# Include paths for sketch libraries +# +SKETCHLIBS := $(wildcard $(addprefix $(SKETCHBOOK)/libraries/,$(LIBTOKENS))) +SKETCHLIBNAMES := $(notdir $(SKETCHLIBS)) +SKETCHLIBSRCDIRS := $(SKETCHLIBS) $(SKETCHBOOK)/libraries/Desktop/support $(addsuffix /utility,$(SKETCHLIBS)) +SKETCHLIBSRCS := $(wildcard $(foreach suffix,$(SRCSUFFIXES),$(addsuffix /$(suffix),$(SKETCHLIBSRCDIRS)))) +FILTEREDSRCS := $(filter-out $(addprefix $(SKETCHBOOK)/libraries/,$(NODESKTOP)),$(SKETCHLIBSRCS)) +SKETCHLIBOBJS := $(addsuffix .o,$(basename $(subst $(SKETCHBOOK),$(BUILDROOT),$(FILTEREDSRCS)))) +SKETCHLIBINCLUDES := $(addprefix -I,$(SKETCHLIBS)) + +# +# Find Arduino libraries referenced by the sketch. Exclude any that +# are overloaded by versions in the sketchbook. +# +ARDUINOLIBS := $(wildcard $(addprefix $(ARDUINO)/libraries/,$(filter-out $(SKETCHLIBNAMES),$(LIBTOKENS)))) +ARDUINOLIBNAMES := $(notdir $(ARDUINOLIBS)) +ARDUINOLIBSRCDIRS := $(ARDUINOLIBS) $(addsuffix /utility,$(ARDUINOLIBS)) +ARDUINOLIBSRCS := $(wildcard $(foreach suffix,$(SRCSUFFIXES),$(addsuffix /$(suffix),$(ARDUINOLIBSRCDIRS)))) +ARDUINOLIBOBJS := $(addsuffix .o,$(basename $(subst $(ARDUINO),$(BUILDROOT),$(ARDUINOLIBSRCS)))) +ARDUINOLIBINCLUDES := $(addprefix -I,$(ARDUINOLIBS)) +ARDUINOLIBINCLUDES := $(ARDUINOLIBINCLUDES) + +# Library object files +LIBOBJS := $(SKETCHLIBOBJS) + +################################################################################ +# Built products +# + +# The ELF file +SKETCHELF = $(BUILDROOT)/$(SKETCH).elf + +# Map file +SKETCHMAP = $(BUILDROOT)/$(SKETCH).map + +# The core library +CORELIB = + +# All of the objects that may be built +ALLOBJS = $(SKETCHOBJS) $(LIBOBJS) $(CORELIBOBJS) + +# All of the dependency files that may be generated +ALLDEPS = $(ALLOBJS:%.o=%.d) +endif + +################################################################################ +# Targets +# + +all: $(SKETCHELF) + +clean: + @rm -fr $(BUILDROOT) + +################################################################################ +# Rules +# + +# fetch dependency info from a previous build if any of it exists +-include $(ALLDEPS) + +# common header for rules, prints what is being built +define RULEHDR + @echo %% $(subst $(BUILDROOT)/,,$@) + @mkdir -p $(dir $@) +endef + +showsources: + @echo "SKETCHLIBSRCDIRS=$(SKETCHLIBSRCDIRS)" + @echo "SKETCHLIBSRCS=$(SKETCHLIBSRCS)" + @echo "SKETCHOBJS=$(SKETCHOBJS)" + @echo "LIBOBJS=$(LIBOBJS)" + @echo "CORELIB=$(CORELIB)" + +# Link the final object +$(SKETCHELF): $(SKETCHOBJS) $(LIBOBJS) $(CORELIB) + $(RULEHDR) + $(v)$(LD) $(LDFLAGS) -o $@ $^ $(LIBS) + +# +# Build sketch objects +# +SKETCH_INCLUDES = $(SKETCHLIBINCLUDES) $(ARDUINOLIBINCLUDES) $(COREINCLUDES) + +$(BUILDROOT)/%.o: $(BUILDROOT)/%.cpp + $(RULEHDR) + $(v)$(CXX) $(CXXFLAGS) -c -o $@ $< -I$(SRCROOT) $(SKETCH_INCLUDES) + +$(BUILDROOT)/%.o: $(SRCROOT)/%.cpp + $(RULEHDR) + $(v)$(CXX) $(CXXFLAGS) -c -o $@ $< $(SKETCH_INCLUDES) + +$(BUILDROOT)/%.o: $(SRCROOT)/%.c + $(RULEHDR) + $(v)$(CC) $(CFLAGS) -c -o $@ $< $(SKETCH_INCLUDES) + +$(BUILDROOT)/%.o: $(SRCROOT)/%.S + $(RULEHDR) + $(v)$(AS) $(ASFLAGS) -c -o $@ $< $(SKETCH_INCLUDES) + +# +# Build library objects from sources in the sketchbook +# +SLIB_INCLUDES = -I$(dir $<)/utility $(SKETCHLIBINCLUDES) $(ARDUINOLIBINCLUDES) $(COREINCLUDES) + +$(BUILDROOT)/libraries/%.o: $(SKETCHBOOK)/libraries/%.cpp + $(RULEHDR) + $(v)$(CXX) $(CXXFLAGS) -c -o $@ $< $(SLIB_INCLUDES) + +$(BUILDROOT)/libraries/%.o: $(SKETCHBOOK)/libraries/%.c + $(RULEHDR) + $(v)$(CC) $(CFLAGS) -c -o $@ $< $(SLIB_INCLUDES) + +$(BUILDROOT)/libraries/%.o: $(SKETCHBOOK)/libraries/%.S + $(RULEHDR) + $(v)$(AS) $(ASFLAGS) -c -o $@ $< $(SLIB_INCLUDES) + +# +# Build library objects from Ardiuno library sources +# +ALIB_INCLUDES = -I$(dir $<)/utility $(ARDUINOLIBINCLUDES) $(COREINCLUDES) + +$(BUILDROOT)/libraries/%.o: $(ARDUINO)/libraries/%.cpp + $(RULEHDR) + $(v)$(CXX) $(CXXFLAGS) -c -o $@ $< $(ALIB_INCLUDES) + +$(BUILDROOT)/libraries/%.o: $(ARDUINO)/libraries/%.c + $(RULEHDR) + $(v)$(CC) $(CFLAGS) -c -o $@ $< $(ALIB_INCLUDES) + +$(BUILDROOT)/libraries/%.o: $(ARDUINO)/libraries/%.S + $(RULEHDR) + $(v)$(AS) $(ASFLAGS) -c -o $@ $< $(ALIB_INCLUDES) + +# +# Build objects from the hardware core +# +$(BUILDROOT)/$(HARDWARE)/%.o: $(CORESRC_DIR)/%.cpp + $(RULEHDR) + $(v)$(CXX) $(filter-out -W%,$(CXXFLAGS)) -c -o $@ $< -I$(CORESRC_DIR) + +$(BUILDROOT)/$(HARDWARE)/%.o: $(CORESRC_DIR)/%.c + @mkdir -p $(dir $@) + $(v)$(CC) $(filter-out -W%,$(CFLAGS)) -c -o $@ $< -I$(CORESRC_DIR) + +$(BUILDROOT)/$(HARDWARE)/%.o: $(CORESRC_DIR)/%.S + $(RULEHDR) + $(v)$(AS) $(ASFLAGS) -c -o $@ $< -I$(CORESRC_DIR) + +# +# Build the core library +# +$(CORELIB): $(CORELIBOBJS) + $(RULEHDR) + $(v)$(AR) -rcs $@ $^ + +# +# Build the sketch.cpp file +# +# This process strives to be as faithful to the Arduino implementation as +# possible. Conceptually, the process is as follows: +# +# * All of the .pde files are concatenated, starting with the file named +# for the sketch and followed by the others in alphabetical order. +# * An insertion point is created in the concatenated file at +# the first statement that isn't a preprocessor directive or comment. +# * An include of "WProgram.h" is inserted at the insertion point. +# * The file following the insertion point is scanned for function definitions +# and prototypes for these functions are inserted at the insertion point. +# +# In addition, we add #line directives wherever the originating file changes +# to help backtrack from compiler messages and in the debugger. +# +$(SKETCHCPP): $(SKETCHCPP_SRC) + $(RULEHDR) + $(v)$(AWK) -v mode=header '$(SKETCH_SPLITTER)' $(SKETCHCPP_SRC) > $@ + $(v)echo "#line 1 \"autogenerated\"" >> $@ + $(v)echo "#include \"WProgram.h\"" >> $@ + $(v)$(AWK) '$(SKETCH_PROTOTYPER)' $(SKETCHCPP_SRC) >> $@ + $(v)$(AWK) -v mode=body '$(SKETCH_SPLITTER)' $(SKETCHCPP_SRC) >> $@ + +# delete the sketch.cpp file if a processing error occurs +.DELETE_ON_ERROR: $(SKETCHCPP) + +# +# The sketch splitter is an awk script used to split off the +# header and body of the concatenated .pde files. It also +# inserts #line directives to help in backtracking from compiler +# and debugger messages to the original source file. +# +# Note that # and $ require special treatment here to avoid upsetting +# make. +# +# This script requires BWK or GNU awk. +# +define SKETCH_SPLITTER + BEGIN { \ + scanning = 1; \ + printing = (mode ~ "header") ? 1 : 0; \ + } \ + { toggles = 1 } \ + (FNR == 1) && printing { \ + printf "#line %d \"%s\"\n", FNR, FILENAME; \ + } \ + /^[[:space:]]*\/\*/,/\*\// { \ + toggles = 0; \ + } \ + /^[[:space:]]*$$/ || /^[[:space:]]*\/\/.*/ || /^\#.*$$/ { \ + toggles = 0; \ + } \ + scanning && toggles { \ + scanning = 0; \ + printing = !printing; \ + if (printing) { \ + printf "#line %d \"%s\"\n", FNR, FILENAME; \ + } \ + } \ + printing +endef + +# +# The prototype scanner is an awk script used to generate function +# prototypes from the concantenated .pde files. +# +# Function definitions are expected to follow the form +# +# [...]([]){ +# +# with whitespace permitted between the various elements. The pattern +# is assembled from separate subpatterns to make adjustments easier. +# +# Note that $ requires special treatment here to avoid upsetting make, +# and backslashes are doubled in the partial patterns to satisfy +# escaping rules. +# +# This script requires BWK or GNU awk. +# +define SKETCH_PROTOTYPER + BEGIN { \ + RS="{"; \ + type = "((\\n)|(^))[[:space:]]*[[:alnum:]_]+[[:space:]]+"; \ + qualifiers = "([[:alnum:]_\\*&]+[[:space:]]*)*"; \ + name = "[[:alnum:]_]+[[:space:]]*"; \ + args = "\\([[:space:][:alnum:]_,&\\*\\[\\]]*\\)"; \ + bodycuddle = "[[:space:]]*$$"; \ + pattern = type qualifiers name args bodycuddle; \ + } \ + match($$0, pattern) { \ + proto = substr($$0, RSTART, RLENGTH); \ + gsub("\n", " ", proto); \ + printf "%s;\n", proto; \ + } +endef diff --git a/libraries/Desktop/include/HardwareSerial.h b/libraries/Desktop/include/HardwareSerial.h new file mode 100644 index 0000000000..3efa775f84 --- /dev/null +++ b/libraries/Desktop/include/HardwareSerial.h @@ -0,0 +1,76 @@ +/* + 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 + +#include + +#include "Stream.h" + +struct ring_buffer; + +class HardwareSerial : public Stream +{ + private: + ring_buffer *_rx_buffer; + 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 _udre; + uint8_t _u2x; + public: + HardwareSerial(ring_buffer *rx_buffer, + 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 udre, uint8_t u2x); + void begin(long); + void end(); + virtual int available(void); + virtual int peek(void); + virtual int read(void); + virtual void flush(void); + virtual void write(uint8_t); + using Print::write; // pull in write(str) and write(buf, size) from Print +}; + +#if defined(UBRRH) || defined(UBRR0H) + extern HardwareSerial Serial; +#elif defined(USBCON) + #include "usb_api.h" +#endif +#if defined(UBRR1H) + extern HardwareSerial Serial1; +#endif +#if defined(UBRR2H) + extern HardwareSerial Serial2; +#endif +#if defined(UBRR3H) + extern HardwareSerial Serial3; +#endif + +#endif diff --git a/libraries/Desktop/include/Print.h b/libraries/Desktop/include/Print.h new file mode 100644 index 0000000000..b092ae51d1 --- /dev/null +++ b/libraries/Desktop/include/Print.h @@ -0,0 +1,66 @@ +/* + 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 +*/ + +#ifndef Print_h +#define Print_h + +#include +#include // for size_t + +#include "WString.h" + +#define DEC 10 +#define HEX 16 +#define OCT 8 +#define BIN 2 +#define BYTE 0 + +class Print +{ + private: + void printNumber(unsigned long, uint8_t); + void printFloat(double, uint8_t); + public: + virtual void write(uint8_t) = 0; + virtual void write(const char *str); + virtual void write(const uint8_t *buffer, size_t size); + + void print(const String &); + void print(const char[]); + void print(char, int = BYTE); + void print(unsigned char, int = BYTE); + void print(int, int = DEC); + void print(unsigned int, int = DEC); + void print(long, int = DEC); + void print(unsigned long, int = DEC); + void print(double, int = 2); + + void println(const String &s); + void println(const char[]); + void println(char, int = BYTE); + void println(unsigned char, int = BYTE); + void println(int, int = DEC); + void println(unsigned int, int = DEC); + void println(long, int = DEC); + void println(unsigned long, int = DEC); + void println(double, int = 2); + void println(void); +}; + +#endif diff --git a/libraries/Desktop/include/SPI.h b/libraries/Desktop/include/SPI.h new file mode 100644 index 0000000000..9808b08dcf --- /dev/null +++ b/libraries/Desktop/include/SPI.h @@ -0,0 +1,70 @@ +/* + * Copyright (c) 2010 by Cristian Maglie + * SPI Master library for arduino. + * + * 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 +#define _SPI_H_INCLUDED + +#include +#include +#include + +#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 +#define SPI_CLOCK_DIV64 0x07 + +#define SPI_MODE0 0x00 +#define SPI_MODE1 0x04 +#define SPI_MODE2 0x08 +#define SPI_MODE3 0x0C + +#define SPI_MODE_MASK 0x0C // CPOL = bit 3, CPHA = bit 2 on SPCR +#define SPI_CLOCK_MASK 0x03 // SPR1 = bit 1, SPR0 = bit 0 on SPCR +#define SPI_2XCLOCK_MASK 0x01 // SPI2X = bit 0 on SPSR + +class SPIClass { +public: + inline static byte transfer(byte _data); + + // SPI Configuration methods + + inline static void attachInterrupt(); + inline static void detachInterrupt(); // Default + + static void begin(); // Default + static void end(); + + static void setBitOrder(uint8_t); + static void setDataMode(uint8_t); + static void setClockDivider(uint8_t); +}; + +extern SPIClass SPI; + +byte SPIClass::transfer(byte _data) { + SPDR = _data; + while (!(SPSR & _BV(SPIF))) + ; + return SPDR; +} + +void SPIClass::attachInterrupt() { + SPCR |= _BV(SPIE); +} + +void SPIClass::detachInterrupt() { + SPCR &= ~_BV(SPIE); +} + +#endif diff --git a/libraries/Desktop/include/Stream.h b/libraries/Desktop/include/Stream.h new file mode 100644 index 0000000000..69278b7f7b --- /dev/null +++ b/libraries/Desktop/include/Stream.h @@ -0,0 +1,16 @@ +#ifndef Stream_h +#define Stream_h + +#include +#include "Print.h" + +class Stream : public Print +{ + public: + virtual int available() = 0; + virtual int read() = 0; + virtual int peek() = 0; + virtual void flush() = 0; +}; + +#endif diff --git a/libraries/Desktop/include/WConstants.h b/libraries/Desktop/include/WConstants.h new file mode 100644 index 0000000000..3e19ac44aa --- /dev/null +++ b/libraries/Desktop/include/WConstants.h @@ -0,0 +1 @@ +#include "wiring.h" diff --git a/libraries/Desktop/include/WProgram.h b/libraries/Desktop/include/WProgram.h new file mode 100644 index 0000000000..eb064535a3 --- /dev/null +++ b/libraries/Desktop/include/WProgram.h @@ -0,0 +1,29 @@ +#ifndef WProgram_h +#define WProgram_h + +#include "wiring.h" +#include +#include "HardwareSerial.h" + +#ifdef __cplusplus +extern "C" { +#endif + +#include +#include +#include +#include +#include + +typedef uint8_t byte; + +void delay(unsigned long msec); +char *itoa(int __val, char *__s, int __radix); +char *ltoa(long __val, char *__s, int __radix); +char *ultoa(unsigned long __val, char *__s, int __radix); + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/libraries/Desktop/include/WString.h b/libraries/Desktop/include/WString.h new file mode 100644 index 0000000000..cadddb9476 --- /dev/null +++ b/libraries/Desktop/include/WString.h @@ -0,0 +1,112 @@ +/* + WString.h - String library for Wiring & Arduino + Copyright (c) 2009-10 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 String_h +#define String_h + +//#include "WProgram.h" +#include +#include +#include + +class String +{ + public: + // constructors + String( const char *value = "" ); + String( const String &value ); + String( const char ); + String( const unsigned char ); + String( const int, const int base=10); + String( const unsigned int, const int base=10 ); + String( const long, const int base=10 ); + String( const unsigned long, const int base=10 ); + ~String() { free(_buffer); _length = _capacity = 0;} //added _length = _capacity = 0; + + // operators + const String & operator = ( const String &rhs ); + const String & operator +=( const String &rhs ); + //const String & operator +=( const char ); + int operator ==( const String &rhs ) const; + int operator !=( const String &rhs ) const; + int operator < ( const String &rhs ) const; + int operator > ( const String &rhs ) const; + int operator <=( const String &rhs ) const; + int operator >=( const String &rhs ) const; + char operator []( unsigned int index ) const; + char& operator []( unsigned int index ); + //operator const char *() const { return _buffer; } + + // general methods + char charAt( unsigned int index ) const; + int compareTo( const String &anotherString ) const; + unsigned char endsWith( const String &suffix ) const; + unsigned char equals( const String &anObject ) const; + unsigned char equalsIgnoreCase( const String &anotherString ) const; + 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; + const unsigned int length( ) const { return _length; } + void setCharAt(unsigned int index, const char ch); + unsigned char startsWith( const String &prefix ) const; + unsigned char startsWith( const String &prefix, unsigned int toffset ) const; + String substring( unsigned int beginIndex ) const; + String substring( unsigned int beginIndex, unsigned int endIndex ) const; + String toLowerCase( ) const; + String toUpperCase( ) const; + String trim( ) const; + void getBytes(unsigned char *buf, unsigned int bufsize); + void toCharArray(char *buf, unsigned int bufsize); + long toInt( ); + const String& concat( const String &str ); + String replace( char oldChar, char newChar ); + String replace( const String& match, const String& replace ); + friend String operator + ( String lhs, const String &rhs ); + + protected: + char *_buffer; // the actual char array + unsigned int _capacity; // the array length minus one (for the '\0') + unsigned int _length; // the String length (not counting the '\0') + + void getBuffer(unsigned int maxStrLen); + + private: + +}; + +// allocate buffer space +inline void String::getBuffer(unsigned int maxStrLen) +{ + _capacity = maxStrLen; + _buffer = (char *) malloc(_capacity + 1); + if (_buffer == NULL) _length = _capacity = 0; +} + +inline String operator+( String lhs, const String &rhs ) +{ + return lhs += rhs; +} + + +#endif diff --git a/libraries/Desktop/include/Wire.h b/libraries/Desktop/include/Wire.h new file mode 100644 index 0000000000..a6c29c493f --- /dev/null +++ b/libraries/Desktop/include/Wire.h @@ -0,0 +1,67 @@ +/* + TwoWire.h - TWI/I2C library for Arduino & 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 +*/ + +#ifndef TwoWire_h +#define TwoWire_h + +#include + +#define BUFFER_LENGTH 32 + +class TwoWire +{ + private: + static uint8_t rxBuffer[]; + static uint8_t rxBufferIndex; + static uint8_t rxBufferLength; + + static uint8_t txAddress; + static uint8_t txBuffer[]; + static uint8_t txBufferIndex; + static uint8_t txBufferLength; + + static uint8_t transmitting; + static void (*user_onRequest)(void); + static void (*user_onReceive)(int); + static void onRequestService(void); + static void onReceiveService(uint8_t*, int); + public: + TwoWire(); + void begin(); + void begin(uint8_t); + void begin(int); + void beginTransmission(uint8_t); + void beginTransmission(int); + uint8_t endTransmission(void); + uint8_t requestFrom(uint8_t, uint8_t); + uint8_t requestFrom(int, int); + void send(uint8_t); + void send(uint8_t*, uint8_t); + void send(int); + void send(char*); + uint8_t available(void); + uint8_t receive(void); + void onReceive( void (*)(int) ); + void onRequest( void (*)(void) ); +}; + +extern TwoWire Wire; + +#endif + diff --git a/libraries/Desktop/include/avr/eeprom.h b/libraries/Desktop/include/avr/eeprom.h new file mode 100644 index 0000000000..626a25e602 --- /dev/null +++ b/libraries/Desktop/include/avr/eeprom.h @@ -0,0 +1,24 @@ +#ifndef _AVR_EEPROM_H_ +#define _AVR_EEPROM_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include + +uint8_t eeprom_read_byte(const uint8_t *p); +uint16_t eeprom_read_word(const uint16_t *p); +uint32_t eeprom_read_dword(const uint32_t *p); +void eeprom_read_block(void *buf, void *ptr, uint8_t size); + +void eeprom_write_byte(uint8_t *p, uint8_t value); +void eeprom_write_word(uint16_t *p, uint16_t value); +void eeprom_write_dword(uint32_t *p, uint32_t value); +void eeprom_write_block(const void *buf, void *ptr, uint8_t size); + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/libraries/Desktop/include/avr/interrupt.h b/libraries/Desktop/include/avr/interrupt.h new file mode 100644 index 0000000000..7c98c5fb19 --- /dev/null +++ b/libraries/Desktop/include/avr/interrupt.h @@ -0,0 +1,12 @@ +#ifndef _AVR_INTERRUPT_H_ +#define _AVR_INTERRUPT_H_ + +#include "io.h" + +#define ISR(vector,...) extern "C" void vector(void); \ +void vector(void) + +#define cli() +#define sei() + +#endif diff --git a/libraries/Desktop/include/avr/io.h b/libraries/Desktop/include/avr/io.h new file mode 100644 index 0000000000..695adec7e3 --- /dev/null +++ b/libraries/Desktop/include/avr/io.h @@ -0,0 +1,21 @@ +#ifndef _AVR_IO_H_ +#define _AVR_IO_H_ + +#include + +#define F_CPU 16000000UL + +#define _VECTOR(N) __vector_ ## N +#define _BV(bit) (1 << (bit)) + +extern "C" volatile uint8_t __iomem[1024]; + +#define _SFR_MEM8(addr) __iomem[addr] +#define _SFR_MEM16(addr) (*(uint16_t *)&__iomem[addr]) + +#define _SFR_IO8(addr) __iomem[addr] + +#define __ATmegaxx0__ +#include "iom2560.h" + +#endif diff --git a/libraries/Desktop/include/avr/iom2560.h b/libraries/Desktop/include/avr/iom2560.h new file mode 100644 index 0000000000..07039ad7e8 --- /dev/null +++ b/libraries/Desktop/include/avr/iom2560.h @@ -0,0 +1,94 @@ +/* Copyright (c) 2005 Anatoly Sokolov + All rights reserved. + + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + + * Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in + the documentation and/or other materials provided with the + distribution. + + * Neither the name of the copyright holders nor the names of + contributors may be used to endorse or promote products derived + from this software without specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + POSSIBILITY OF SUCH DAMAGE. */ + +/* $Id */ + +/* avr/iom2560.h - definitions for ATmega2560 */ + +#ifndef _AVR_IOM2560_H_ +#define _AVR_IOM2560_H_ 1 + +#include + +/* Constants */ +#define SPM_PAGESIZE 256 +#define RAMEND 0x21FF +#define XRAMEND 0xFFFF +#define E2END 0xFFF +#define E2PAGESIZE 8 +#define FLASHEND 0x3FFFF + + +/* Fuses */ + +#define FUSE_MEMORY_SIZE 3 + +/* Low Fuse Byte */ +#define FUSE_CKSEL0 (unsigned char)~_BV(0) +#define FUSE_CKSEL1 (unsigned char)~_BV(1) +#define FUSE_CKSEL2 (unsigned char)~_BV(2) +#define FUSE_CKSEL3 (unsigned char)~_BV(3) +#define FUSE_SUT0 (unsigned char)~_BV(4) +#define FUSE_SUT1 (unsigned char)~_BV(5) +#define FUSE_CKOUT (unsigned char)~_BV(6) +#define FUSE_CKDIV8 (unsigned char)~_BV(7) +#define LFUSE_DEFAULT (FUSE_CKSEL0 & FUSE_CKSEL2 & FUSE_CKSEL3 & FUSE_SUT0 & FUSE_CKDIV8) + +/* High Fuse Byte */ +#define FUSE_BOOTRST (unsigned char)~_BV(0) +#define FUSE_BOOTSZ0 (unsigned char)~_BV(1) +#define FUSE_BOOTSZ1 (unsigned char)~_BV(2) +#define FUSE_EESAVE (unsigned char)~_BV(3) +#define FUSE_WDTON (unsigned char)~_BV(4) +#define FUSE_SPIEN (unsigned char)~_BV(5) +#define FUSE_JTAGEN (unsigned char)~_BV(6) +#define FUSE_OCDEN (unsigned char)~_BV(7) +#define HFUSE_DEFAULT (FUSE_BOOTSZ0 & FUSE_BOOTSZ1 & FUSE_SPIEN & FUSE_JTAGEN) + +/* Extended Fuse Byte */ +#define FUSE_BODLEVEL0 (unsigned char)~_BV(0) +#define FUSE_BODLEVEL1 (unsigned char)~_BV(1) +#define FUSE_BODLEVEL2 (unsigned char)~_BV(2) +#define EFUSE_DEFAULT (0xFF) + + +/* Lock Bits */ +#define __LOCK_BITS_EXIST +#define __BOOT_LOCK_BITS_0_EXIST +#define __BOOT_LOCK_BITS_1_EXIST + + +/* Signature */ +#define SIGNATURE_0 0x1E +#define SIGNATURE_1 0x98 +#define SIGNATURE_2 0x01 + + +#endif /* _AVR_IOM2560_H_ */ diff --git a/libraries/Desktop/include/avr/iomxx0_1.h b/libraries/Desktop/include/avr/iomxx0_1.h new file mode 100644 index 0000000000..c1e7d4d194 --- /dev/null +++ b/libraries/Desktop/include/avr/iomxx0_1.h @@ -0,0 +1,1553 @@ +/* Copyright (c) 2005 Anatoly Sokolov + All rights reserved. + + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + + * Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in + the documentation and/or other materials provided with the + distribution. + + * Neither the name of the copyright holders nor the names of + contributors may be used to endorse or promote products derived + from this software without specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + POSSIBILITY OF SUCH DAMAGE. */ + +/* $Id: iomxx0_1.h,v 1.12 2007/12/12 14:00:49 arcanum Exp $ */ + +/* avr/iomxx0_1.h - definitions for ATmega640, Atmega1280, ATmega1281, + ATmega2560 and ATmega2561. */ + +#ifndef _AVR_IOMXX0_1_H_ +#define _AVR_IOMXX0_1_H_ 1 + +/* This file should only be included from , never directly. */ + +#ifndef _AVR_IO_H_ +# error "Include instead of this file." +#endif + +#ifndef _AVR_IOXXX_H_ +# define _AVR_IOXXX_H_ "iomxx0_1.h" +#else +# error "Attempt to include more than one file." +#endif + +#if defined(__AVR_ATmega640__) || defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) +# define __ATmegaxx0__ +#elif defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__) +# define __ATmegaxx1__ +#endif + +/* Registers and associated bit numbers */ + +#define PINA _SFR_IO8(0X00) +#define PINA7 7 +#define PINA6 6 +#define PINA5 5 +#define PINA4 4 +#define PINA3 3 +#define PINA2 2 +#define PINA1 1 +#define PINA0 0 + +#define DDRA _SFR_IO8(0X01) +#define DDA7 7 +#define DDA6 6 +#define DDA5 5 +#define DDA4 4 +#define DDA3 3 +#define DDA2 2 +#define DDA1 1 +#define DDA0 0 + +#define PORTA _SFR_IO8(0X02) +#define PA7 7 +#define PA6 6 +#define PA5 5 +#define PA4 4 +#define PA3 3 +#define PA2 2 +#define PA1 1 +#define PA0 0 + +#define PINB _SFR_IO8(0X03) +#define PINB7 7 +#define PINB6 6 +#define PINB5 5 +#define PINB4 4 +#define PINB3 3 +#define PINB2 2 +#define PINB1 1 +#define PINB0 0 + +#define DDRB _SFR_IO8(0x04) +#define DDB7 7 +#define DDB6 6 +#define DDB5 5 +#define DDB4 4 +#define DDB3 3 +#define DDB2 2 +#define DDB1 1 +#define DDB0 0 + +#define PORTB _SFR_IO8(0x05) +#define PB7 7 +#define PB6 6 +#define PB5 5 +#define PB4 4 +#define PB3 3 +#define PB2 2 +#define PB1 1 +#define PB0 0 + +#define PINC _SFR_IO8(0x06) +#define PINC7 7 +#define PINC6 6 +#define PINC5 5 +#define PINC4 4 +#define PINC3 3 +#define PINC2 2 +#define PINC1 1 +#define PINC0 0 + +#define DDRC _SFR_IO8(0x07) +#define DDC7 7 +#define DDC6 6 +#define DDC5 5 +#define DDC4 4 +#define DDC3 3 +#define DDC2 2 +#define DDC1 1 +#define DDC0 0 + +#define PORTC _SFR_IO8(0x08) +#define PC7 7 +#define PC6 6 +#define PC5 5 +#define PC4 4 +#define PC3 3 +#define PC2 2 +#define PC1 1 +#define PC0 0 + +#define PIND _SFR_IO8(0x09) +#define PIND7 7 +#define PIND6 6 +#define PIND5 5 +#define PIND4 4 +#define PIND3 3 +#define PIND2 2 +#define PIND1 1 +#define PIND0 0 + +#define DDRD _SFR_IO8(0x0A) +#define DDD7 7 +#define DDD6 6 +#define DDD5 5 +#define DDD4 4 +#define DDD3 3 +#define DDD2 2 +#define DDD1 1 +#define DDD0 0 + +#define PORTD _SFR_IO8(0x0B) +#define PD7 7 +#define PD6 6 +#define PD5 5 +#define PD4 4 +#define PD3 3 +#define PD2 2 +#define PD1 1 +#define PD0 0 + +#define PINE _SFR_IO8(0x0C) +#define PINE7 7 +#define PINE6 6 +#define PINE5 5 +#define PINE4 4 +#define PINE3 3 +#define PINE2 2 +#define PINE1 1 +#define PINE0 0 + +#define DDRE _SFR_IO8(0x0D) +#define DDE7 7 +#define DDE6 6 +#define DDE5 5 +#define DDE4 4 +#define DDE3 3 +#define DDE2 2 +#define DDE1 1 +#define DDE0 0 + +#define PORTE _SFR_IO8(0x0E) +#define PE7 7 +#define PE6 6 +#define PE5 5 +#define PE4 4 +#define PE3 3 +#define PE2 2 +#define PE1 1 +#define PE0 0 + +#define PINF _SFR_IO8(0x0F) +#define PINF7 7 +#define PINF6 6 +#define PINF5 5 +#define PINF4 4 +#define PINF3 3 +#define PINF2 2 +#define PINF1 1 +#define PINF0 0 + +#define DDRF _SFR_IO8(0x10) +#define DDF7 7 +#define DDF6 6 +#define DDF5 5 +#define DDF4 4 +#define DDF3 3 +#define DDF2 2 +#define DDF1 1 +#define DDF0 0 + +#define PORTF _SFR_IO8(0x11) +#define PF7 7 +#define PF6 6 +#define PF5 5 +#define PF4 4 +#define PF3 3 +#define PF2 2 +#define PF1 1 +#define PF0 0 + +#define PING _SFR_IO8(0x12) +#define PING5 5 +#define PING4 4 +#define PING3 3 +#define PING2 2 +#define PING1 1 +#define PING0 0 + +#define DDRG _SFR_IO8(0x13) +#define DDG5 5 +#define DDG4 4 +#define DDG3 3 +#define DDG2 2 +#define DDG1 1 +#define DDG0 0 + +#define PORTG _SFR_IO8(0x14) +#define PG5 5 +#define PG4 4 +#define PG3 3 +#define PG2 2 +#define PG1 1 +#define PG0 0 + +#define TIFR0 _SFR_IO8(0x15) +#define OCF0B 2 +#define OCF0A 1 +#define TOV0 0 + +#define TIFR1 _SFR_IO8(0x16) +#define ICF1 5 +#define OCF1C 3 +#define OCF1B 2 +#define OCF1A 1 +#define TOV1 0 + +#define TIFR2 _SFR_IO8(0x17) +#define OCF2B 2 +#define OCF2A 1 +#define TOV2 0 + +#define TIFR3 _SFR_IO8(0x18) +#define ICF3 5 +#define OCF3C 3 +#define OCF3B 2 +#define OCF3A 1 +#define TOV3 0 + +#define TIFR4 _SFR_IO8(0x19) +#define ICF4 5 +#define OCF4C 3 +#define OCF4B 2 +#define OCF4A 1 +#define TOV4 0 + +#define TIFR5 _SFR_IO8(0x1A) +#define ICF5 5 +#define OCF5C 3 +#define OCF5B 2 +#define OCF5A 1 +#define TOV5 0 + +#define PCIFR _SFR_IO8(0x1B) +#if defined(__ATmegaxx0__) +# define PCIF2 2 +#endif /* __ATmegaxx0__ */ +#define PCIF1 1 +#define PCIF0 0 + +#define EIFR _SFR_IO8(0x1C) +#define INTF7 7 +#define INTF6 6 +#define INTF5 5 +#define INTF4 4 +#define INTF3 3 +#define INTF2 2 +#define INTF1 1 +#define INTF0 0 + +#define EIMSK _SFR_IO8(0x1D) +#define INT7 7 +#define INT6 6 +#define INT5 5 +#define INT4 4 +#define INT3 3 +#define INT2 2 +#define INT1 1 +#define INT0 0 + +#define GPIOR0 _SFR_IO8(0x1E) + +#define EECR _SFR_IO8(0x1F) +#define EEPM1 5 +#define EEPM0 4 +#define EERIE 3 +#define EEMPE 2 +#define EEPE 1 +#define EERE 0 + +#define EEDR _SFR_IO8(0X20) + +/* Combine EEARL and EEARH */ +#define EEAR _SFR_IO16(0x21) + +#define EEARL _SFR_IO8(0x21) +#define EEARH _SFR_IO8(0X22) + +/* 6-char sequence denoting where to find the EEPROM registers in memory space. + Adresses denoted in hex syntax with uppercase letters. Used by the EEPROM + subroutines. + First two letters: EECR address. + Second two letters: EEDR address. + Last two letters: EEAR address. */ +#define __EEPROM_REG_LOCATIONS__ 1F2021 + +#define GTCCR _SFR_IO8(0x23) +#define TSM 7 +#define PSRASY 1 +#define PSRSYNC 0 + +#define TCCR0A _SFR_IO8(0x24) +#define COM0A1 7 +#define COM0A0 6 +#define COM0B1 5 +#define COM0B0 4 +#define WGM01 1 +#define WGM00 0 + +#define TCCR0B _SFR_IO8(0x25) +#define FOC0A 7 +#define FOC0B 6 +#define WGM02 3 +#define CS02 2 +#define CS01 1 +#define CS00 0 + +#define TCNT0 _SFR_IO8(0X26) + +#define OCR0A _SFR_IO8(0X27) + +#define OCR0B _SFR_IO8(0X28) + +/* Reserved [0x29] */ + +#define GPIOR1 _SFR_IO8(0x2A) + +#define GPIOR2 _SFR_IO8(0x2B) + +#define SPCR _SFR_IO8(0x2C) +#define SPIE 7 +#define SPE 6 +#define DORD 5 +#define MSTR 4 +#define CPOL 3 +#define CPHA 2 +#define SPR1 1 +#define SPR0 0 + +#define SPSR _SFR_IO8(0x2D) +#define SPIF 7 +#define WCOL 6 +#define SPI2X 0 + +#define SPDR _SFR_IO8(0X2E) + +/* Reserved [0x2F] */ + +#define ACSR _SFR_IO8(0x30) +#define ACD 7 +#define ACBG 6 +#define ACO 5 +#define ACI 4 +#define ACIE 3 +#define ACIC 2 +#define ACIS1 1 +#define ACIS0 0 + +#define MONDR _SFR_IO8(0x31) +#define OCDR _SFR_IO8(0x31) +#define IDRD 7 +#define OCDR7 7 +#define OCDR6 6 +#define OCDR5 5 +#define OCDR4 4 +#define OCDR3 3 +#define OCDR2 2 +#define OCDR1 1 +#define OCDR0 0 + +/* Reserved [0x32] */ + +#define SMCR _SFR_IO8(0x33) +#define SM2 3 +#define SM1 2 +#define SM0 1 +#define SE 0 + +#define MCUSR _SFR_IO8(0x34) +#define JTRF 4 +#define WDRF 3 +#define BORF 2 +#define EXTRF 1 +#define PORF 0 + +#define MCUCR _SFR_IO8(0X35) +#define JTD 7 +#define PUD 4 +#define IVSEL 1 +#define IVCE 0 + +/* Reserved [0x36] */ + +#define SPMCSR _SFR_IO8(0x37) +#define SPMIE 7 +#define RWWSB 6 +#define SIGRD 5 +#define RWWSRE 4 +#define BLBSET 3 +#define PGWRT 2 +#define PGERS 1 +#define SPMEN 0 + +/* Reserved [0x38..0x3A] */ + +#define RAMPZ _SFR_IO8(0X3B) +#define RAMPZ0 0 + +#define EIND _SFR_IO8(0X3C) +#define EIND0 0 + +/* SP [0x3D..0x3E] */ +/* SREG [0x3F] */ + +#define WDTCSR _SFR_MEM8(0x60) +#define WDIF 7 +#define WDIE 6 +#define WDP3 5 +#define WDCE 4 +#define WDE 3 +#define WDP2 2 +#define WDP1 1 +#define WDP0 0 + +#define CLKPR _SFR_MEM8(0x61) +#define CLKPCE 7 +#define CLKPS3 3 +#define CLKPS2 2 +#define CLKPS1 1 +#define CLKPS0 0 + +/* Reserved [0x62..0x63] */ + +#define PRR0 _SFR_MEM8(0x64) +#define PRTWI 7 +#define PRTIM2 6 +#define PRTIM0 5 +#define PRTIM1 3 +#define PRSPI 2 +#define PRUSART0 1 +#define PRADC 0 + +#define PRR1 _SFR_MEM8(0x65) +#define PRTIM5 5 +#define PRTIM4 4 +#define PRTIM3 3 +#define PRUSART3 2 +#define PRUSART2 1 +#define PRUSART1 0 + +#define OSCCAL _SFR_MEM8(0x66) + +/* Reserved [0x67] */ + +#define PCICR _SFR_MEM8(0x68) +#if defined(__ATmegaxx0__) +# define PCIE2 2 +#endif /* __ATmegaxx0__ */ +#define PCIE1 1 +#define PCIE0 0 + +#define EICRA _SFR_MEM8(0x69) +#define ISC31 7 +#define ISC30 6 +#define ISC21 5 +#define ISC20 4 +#define ISC11 3 +#define ISC10 2 +#define ISC01 1 +#define ISC00 0 + +#define EICRB _SFR_MEM8(0x6A) +#define ISC71 7 +#define ISC70 6 +#define ISC61 5 +#define ISC60 4 +#define ISC51 3 +#define ISC50 2 +#define ISC41 1 +#define ISC40 0 + +#define PCMSK0 _SFR_MEM8(0x6B) +#define PCINT7 7 +#define PCINT6 6 +#define PCINT5 5 +#define PCINT4 4 +#define PCINT3 3 +#define PCINT2 2 +#define PCINT1 1 +#define PCINT0 0 + +#define PCMSK1 _SFR_MEM8(0x6C) +#define PCINT15 7 +#define PCINT14 6 +#define PCINT13 5 +#define PCINT12 4 +#define PCINT11 3 +#define PCINT10 2 +#define PCINT9 1 +#define PCINT8 0 + +#if defined(__ATmegaxx0__) +# define PCMSK2 _SFR_MEM8(0x6D) +# define PCINT23 7 +# define PCINT22 6 +# define PCINT21 5 +# define PCINT20 4 +# define PCINT19 3 +# define PCINT18 2 +# define PCINT17 1 +# define PCINT16 0 +#endif /* __ATmegaxx0__ */ + +#define TIMSK0 _SFR_MEM8(0x6E) +#define OCIE0B 2 +#define OCIE0A 1 +#define TOIE0 0 + +#define TIMSK1 _SFR_MEM8(0x6F) +#define ICIE1 5 +#define OCIE1C 3 +#define OCIE1B 2 +#define OCIE1A 1 +#define TOIE1 0 + +#define TIMSK2 _SFR_MEM8(0x70) +#define OCIE2B 2 +#define OCIE2A 1 +#define TOIE2 0 + +#define TIMSK3 _SFR_MEM8(0x71) +#define ICIE3 5 +#define OCIE3C 3 +#define OCIE3B 2 +#define OCIE3A 1 +#define TOIE3 0 + +#define TIMSK4 _SFR_MEM8(0x72) +#define ICIE4 5 +#define OCIE4C 3 +#define OCIE4B 2 +#define OCIE4A 1 +#define TOIE4 0 + +#define TIMSK5 _SFR_MEM8(0x73) +#define ICIE5 5 +#define OCIE5C 3 +#define OCIE5B 2 +#define OCIE5A 1 +#define TOIE5 0 + +#define XMCRA _SFR_MEM8(0x74) +#define SRE 7 +#define SRL2 6 +#define SRL1 5 +#define SRL0 4 +#define SRW11 3 +#define SRW10 2 +#define SRW01 1 +#define SRW00 0 + +#define XMCRB _SFR_MEM8(0x75) +#define XMBK 7 +#define XMM2 2 +#define XMM1 1 +#define XMM0 0 + +/* Reserved [0x76..0x77] */ + +/* Combine ADCL and ADCH */ +#ifndef __ASSEMBLER__ +#define ADC _SFR_MEM16(0x78) +#endif +#define ADCW _SFR_MEM16(0x78) +#define ADCL _SFR_MEM8(0x78) +#define ADCH _SFR_MEM8(0x79) + +#define ADCSRA _SFR_MEM8(0x7A) +#define ADEN 7 +#define ADSC 6 +#define ADATE 5 +#define ADIF 4 +#define ADIE 3 +#define ADPS2 2 +#define ADPS1 1 +#define ADPS0 0 + +#define ADCSRB _SFR_MEM8(0x7B) +#define ACME 6 +#if defined(__ATmegaxx0__) +# define MUX5 3 +#endif /* __ATmegaxx0__ */ +#define ADTS2 2 +#define ADTS1 1 +#define ADTS0 0 + +#define ADMUX _SFR_MEM8(0x7C) +#define REFS1 7 +#define REFS0 6 +#define ADLAR 5 +#define MUX4 4 +#define MUX3 3 +#define MUX2 2 +#define MUX1 1 +#define MUX0 0 + +#define DIDR2 _SFR_MEM8(0x7D) +#define ADC15D 7 +#define ADC14D 6 +#define ADC13D 5 +#define ADC12D 4 +#define ADC11D 3 +#define ADC10D 2 +#define ADC9D 1 +#define ADC8D 0 + +#define DIDR0 _SFR_MEM8(0x7E) +#define ADC7D 7 +#define ADC6D 6 +#define ADC5D 5 +#define ADC4D 4 +#define ADC3D 3 +#define ADC2D 2 +#define ADC1D 1 +#define ADC0D 0 + +#define DIDR1 _SFR_MEM8(0x7F) +#define AIN1D 1 +#define AIN0D 0 + +#define TCCR1A _SFR_MEM8(0x80) +#define COM1A1 7 +#define COM1A0 6 +#define COM1B1 5 +#define COM1B0 4 +#define COM1C1 3 +#define COM1C0 2 +#define WGM11 1 +#define WGM10 0 + +#define TCCR1B _SFR_MEM8(0x81) +#define ICNC1 7 +#define ICES1 6 +#define WGM13 4 +#define WGM12 3 +#define CS12 2 +#define CS11 1 +#define CS10 0 + +#define TCCR1C _SFR_MEM8(0x82) +#define FOC1A 7 +#define FOC1B 6 +#define FOC1C 5 + +/* Reserved [0x83] */ + +/* Combine TCNT1L and TCNT1H */ +#define TCNT1 _SFR_MEM16(0x84) + +#define TCNT1L _SFR_MEM8(0x84) +#define TCNT1H _SFR_MEM8(0x85) + +/* Combine ICR1L and ICR1H */ +#define ICR1 _SFR_MEM16(0x86) + +#define ICR1L _SFR_MEM8(0x86) +#define ICR1H _SFR_MEM8(0x87) + +/* Combine OCR1AL and OCR1AH */ +#define OCR1A _SFR_MEM16(0x88) + +#define OCR1AL _SFR_MEM8(0x88) +#define OCR1AH _SFR_MEM8(0x89) + +/* Combine OCR1BL and OCR1BH */ +#define OCR1B _SFR_MEM16(0x8A) + +#define OCR1BL _SFR_MEM8(0x8A) +#define OCR1BH _SFR_MEM8(0x8B) + +/* Combine OCR1CL and OCR1CH */ +#define OCR1C _SFR_MEM16(0x8C) + +#define OCR1CL _SFR_MEM8(0x8C) +#define OCR1CH _SFR_MEM8(0x8D) + +/* Reserved [0x8E..0x8F] */ + +#define TCCR3A _SFR_MEM8(0x90) +#define COM3A1 7 +#define COM3A0 6 +#define COM3B1 5 +#define COM3B0 4 +#define COM3C1 3 +#define COM3C0 2 +#define WGM31 1 +#define WGM30 0 + +#define TCCR3B _SFR_MEM8(0x91) +#define ICNC3 7 +#define ICES3 6 +#define WGM33 4 +#define WGM32 3 +#define CS32 2 +#define CS31 1 +#define CS30 0 + +#define TCCR3C _SFR_MEM8(0x92) +#define FOC3A 7 +#define FOC3B 6 +#define FOC3C 5 + +/* Reserved [0x93] */ + +/* Combine TCNT3L and TCNT3H */ +#define TCNT3 _SFR_MEM16(0x94) + +#define TCNT3L _SFR_MEM8(0x94) +#define TCNT3H _SFR_MEM8(0x95) + +/* Combine ICR3L and ICR3H */ +#define ICR3 _SFR_MEM16(0x96) + +#define ICR3L _SFR_MEM8(0x96) +#define ICR3H _SFR_MEM8(0x97) + +/* Combine OCR3AL and OCR3AH */ +#define OCR3A _SFR_MEM16(0x98) + +#define OCR3AL _SFR_MEM8(0x98) +#define OCR3AH _SFR_MEM8(0x99) + +/* Combine OCR3BL and OCR3BH */ +#define OCR3B _SFR_MEM16(0x9A) + +#define OCR3BL _SFR_MEM8(0x9A) +#define OCR3BH _SFR_MEM8(0x9B) + +/* Combine OCR3CL and OCR3CH */ +#define OCR3C _SFR_MEM16(0x9C) + +#define OCR3CL _SFR_MEM8(0x9C) +#define OCR3CH _SFR_MEM8(0x9D) + +/* Reserved [0x9E..0x9F] */ + +#define TCCR4A _SFR_MEM8(0xA0) +#define COM4A1 7 +#define COM4A0 6 +#define COM4B1 5 +#define COM4B0 4 +#define COM4C1 3 +#define COM4C0 2 +#define WGM41 1 +#define WGM40 0 + +#define TCCR4B _SFR_MEM8(0xA1) +#define ICNC4 7 +#define ICES4 6 +#define WGM43 4 +#define WGM42 3 +#define CS42 2 +#define CS41 1 +#define CS40 0 + +#define TCCR4C _SFR_MEM8(0xA2) +#define FOC4A 7 +#define FOC4B 6 +#define FOC4C 5 + +/* Reserved [0xA3] */ + +/* Combine TCNT4L and TCNT4H */ +#define TCNT4 _SFR_MEM16(0xA4) + +#define TCNT4L _SFR_MEM8(0xA4) +#define TCNT4H _SFR_MEM8(0xA5) + +/* Combine ICR4L and ICR4H */ +#define ICR4 _SFR_MEM16(0xA6) + +#define ICR4L _SFR_MEM8(0xA6) +#define ICR4H _SFR_MEM8(0xA7) + +/* Combine OCR4AL and OCR4AH */ +#define OCR4A _SFR_MEM16(0xA8) + +#define OCR4AL _SFR_MEM8(0xA8) +#define OCR4AH _SFR_MEM8(0xA9) + +/* Combine OCR4BL and OCR4BH */ +#define OCR4B _SFR_MEM16(0xAA) + +#define OCR4BL _SFR_MEM8(0xAA) +#define OCR4BH _SFR_MEM8(0xAB) + +/* Combine OCR4CL and OCR4CH */ +#define OCR4C _SFR_MEM16(0xAC) + +#define OCR4CL _SFR_MEM8(0xAC) +#define OCR4CH _SFR_MEM8(0xAD) + +/* Reserved [0xAE..0xAF] */ + +#define TCCR2A _SFR_MEM8(0xB0) +#define COM2A1 7 +#define COM2A0 6 +#define COM2B1 5 +#define COM2B0 4 +#define WGM21 1 +#define WGM20 0 + +#define TCCR2B _SFR_MEM8(0xB1) +#define FOC2A 7 +#define FOC2B 6 +#define WGM22 3 +#define CS22 2 +#define CS21 1 +#define CS20 0 + +#define TCNT2 _SFR_MEM8(0xB2) + +#define OCR2A _SFR_MEM8(0xB3) + +#define OCR2B _SFR_MEM8(0xB4) + +/* Reserved [0xB5] */ + +#define ASSR _SFR_MEM8(0xB6) +#define EXCLK 6 +#define AS2 5 +#define TCN2UB 4 +#define OCR2AUB 3 +#define OCR2BUB 2 +#define TCR2AUB 1 +#define TCR2BUB 0 + +/* Reserved [0xB7] */ + +#define TWBR _SFR_MEM8(0xB8) + +#define TWSR _SFR_MEM8(0xB9) +#define TWS7 7 +#define TWS6 6 +#define TWS5 5 +#define TWS4 4 +#define TWS3 3 +#define TWPS1 1 +#define TWPS0 0 + +#define TWAR _SFR_MEM8(0xBA) +#define TWA6 7 +#define TWA5 6 +#define TWA4 5 +#define TWA3 4 +#define TWA2 3 +#define TWA1 2 +#define TWA0 1 +#define TWGCE 0 + +#define TWDR _SFR_MEM8(0xBB) + +#define TWCR _SFR_MEM8(0xBC) +#define TWINT 7 +#define TWEA 6 +#define TWSTA 5 +#define TWSTO 4 +#define TWWC 3 +#define TWEN 2 +#define TWIE 0 + +#define TWAMR _SFR_MEM8(0xBD) +#define TWAM6 7 +#define TWAM5 6 +#define TWAM4 5 +#define TWAM3 4 +#define TWAM2 3 +#define TWAM1 2 +#define TWAM0 1 + +/* Reserved [0xBE..0xBF] */ + +#define UCSR0A _SFR_MEM8(0xC0) +#define RXC0 7 +#define TXC0 6 +#define UDRE0 5 +#define FE0 4 +#define DOR0 3 +#define UPE0 2 +#define U2X0 1 +#define MPCM0 0 + +#define UCSR0B _SFR_MEM8(0XC1) +#define RXCIE0 7 +#define TXCIE0 6 +#define UDRIE0 5 +#define RXEN0 4 +#define TXEN0 3 +#define UCSZ02 2 +#define RXB80 1 +#define TXB80 0 + +#define UCSR0C _SFR_MEM8(0xC2) +#define UMSEL01 7 +#define UMSEL00 6 +#define UPM01 5 +#define UPM00 4 +#define USBS0 3 +#define UCSZ01 2 +#define UCSZ00 1 +#define UCPOL0 0 + +/* Reserved [0xC3] */ + +/* Combine UBRR0L and UBRR0H */ +#define UBRR0 _SFR_MEM16(0xC4) + +#define UBRR0L _SFR_MEM8(0xC4) +#define UBRR0H _SFR_MEM8(0xC5) + +#define UDR0 _SFR_MEM8(0XC6) + +/* Reserved [0xC7] */ + +#define UCSR1A _SFR_MEM8(0xC8) +#define RXC1 7 +#define TXC1 6 +#define UDRE1 5 +#define FE1 4 +#define DOR1 3 +#define UPE1 2 +#define U2X1 1 +#define MPCM1 0 + +#define UCSR1B _SFR_MEM8(0XC9) +#define RXCIE1 7 +#define TXCIE1 6 +#define UDRIE1 5 +#define RXEN1 4 +#define TXEN1 3 +#define UCSZ12 2 +#define RXB81 1 +#define TXB81 0 + +#define UCSR1C _SFR_MEM8(0xCA) +#define UMSEL11 7 +#define UMSEL10 6 +#define UPM11 5 +#define UPM10 4 +#define USBS1 3 +#define UCSZ11 2 +#define UCSZ10 1 +#define UCPOL1 0 + +/* Reserved [0xCB] */ + +/* Combine UBRR1L and UBRR1H */ +#define UBRR1 _SFR_MEM16(0xCC) + +#define UBRR1L _SFR_MEM8(0xCC) +#define UBRR1H _SFR_MEM8(0xCD) + +#define UDR1 _SFR_MEM8(0XCE) + +/* Reserved [0xCF] */ + +#if defined(__ATmegaxx0__) + +# define UCSR2A _SFR_MEM8(0xD0) +# define RXC2 7 +# define TXC2 6 +# define UDRE2 5 +# define FE2 4 +# define DOR2 3 +# define UPE2 2 +# define U2X2 1 +# define MPCM2 0 + +# define UCSR2B _SFR_MEM8(0XD1) +# define RXCIE2 7 +# define TXCIE2 6 +# define UDRIE2 5 +# define RXEN2 4 +# define TXEN2 3 +# define UCSZ22 2 +# define RXB82 1 +# define TXB82 0 + +# define UCSR2C _SFR_MEM8(0xD2) +# define UMSEL21 7 +# define UMSEL20 6 +# define UPM21 5 +# define UPM20 4 +# define USBS2 3 +# define UCSZ21 2 +# define UCSZ20 1 +# define UCPOL2 0 + +/* Reserved [0xD3] */ + +/* Combine UBRR2L and UBRR2H */ +# define UBRR2 _SFR_MEM16(0xD4) + +# define UBRR2L _SFR_MEM8(0xD4) +# define UBRR2H _SFR_MEM8(0xD5) + +# define UDR2 _SFR_MEM8(0XD6) + +#endif /* __ATmegaxx0__ */ + +/* Reserved [0xD7..0xFF] */ + +#if defined(__ATmegaxx0__) + +# define PINH _SFR_MEM8(0x100) +# define PINH7 7 +# define PINH6 6 +# define PINH5 5 +# define PINH4 4 +# define PINH3 3 +# define PINH2 2 +# define PINH1 1 +# define PINH0 0 + +# define DDRH _SFR_MEM8(0x101) +# define DDH7 7 +# define DDH6 6 +# define DDH5 5 +# define DDH4 4 +# define DDH3 3 +# define DDH2 2 +# define DDH1 1 +# define DDH0 0 + +# define PORTH _SFR_MEM8(0x102) +# define PH7 7 +# define PH6 6 +# define PH5 5 +# define PH4 4 +# define PH3 3 +# define PH2 2 +# define PH1 1 +# define PH0 0 + +# define PINJ _SFR_MEM8(0x103) +# define PINJ7 7 +# define PINJ6 6 +# define PINJ5 5 +# define PINJ4 4 +# define PINJ3 3 +# define PINJ2 2 +# define PINJ1 1 +# define PINJ0 0 + +# define DDRJ _SFR_MEM8(0x104) +# define DDJ7 7 +# define DDJ6 6 +# define DDJ5 5 +# define DDJ4 4 +# define DDJ3 3 +# define DDJ2 2 +# define DDJ1 1 +# define DDJ0 0 + +# define PORTJ _SFR_MEM8(0x105) +# define PJ7 7 +# define PJ6 6 +# define PJ5 5 +# define PJ4 4 +# define PJ3 3 +# define PJ2 2 +# define PJ1 1 +# define PJ0 0 + +# define PINK _SFR_MEM8(0x106) +# define PINK7 7 +# define PINK6 6 +# define PINK5 5 +# define PINK4 4 +# define PINK3 3 +# define PINK2 2 +# define PINK1 1 +# define PINK0 0 + +# define DDRK _SFR_MEM8(0x107) +# define DDK7 7 +# define DDK6 6 +# define DDK5 5 +# define DDK4 4 +# define DDK3 3 +# define DDK2 2 +# define DDK1 1 +# define DDK0 0 + +# define PORTK _SFR_MEM8(0x108) +# define PK7 7 +# define PK6 6 +# define PK5 5 +# define PK4 4 +# define PK3 3 +# define PK2 2 +# define PK1 1 +# define PK0 0 + +# define PINL _SFR_MEM8(0x109) +# define PINL7 7 +# define PINL6 6 +# define PINL5 5 +# define PINL4 4 +# define PINL3 3 +# define PINL2 2 +# define PINL1 1 +# define PINL0 0 + +# define DDRL _SFR_MEM8(0x10A) +# define DDL7 7 +# define DDL6 6 +# define DDL5 5 +# define DDL4 4 +# define DDL3 3 +# define DDL2 2 +# define DDL1 1 +# define DDL0 0 + +# define PORTL _SFR_MEM8(0x10B) +# define PL7 7 +# define PL6 6 +# define PL5 5 +# define PL4 4 +# define PL3 3 +# define PL2 2 +# define PL1 1 +# define PL0 0 + +#endif /* __ATmegaxx0__ */ + +/* Reserved [0x10C..0x11F] */ + +#define TCCR5A _SFR_MEM8(0x120) +#define COM5A1 7 +#define COM5A0 6 +#define COM5B1 5 +#define COM5B0 4 +#define COM5C1 3 +#define COM5C0 2 +#define WGM51 1 +#define WGM50 0 + +#define TCCR5B _SFR_MEM8(0x121) +#define ICNC5 7 +#define ICES5 6 +#define WGM53 4 +#define WGM52 3 +#define CS52 2 +#define CS51 1 +#define CS50 0 + +#define TCCR5C _SFR_MEM8(0x122) +#define FOC5A 7 +#define FOC5B 6 +#define FOC5C 5 + +/* Reserved [0x123] */ + +/* Combine TCNT5L and TCNT5H */ +#define TCNT5 _SFR_MEM16(0x124) + +#define TCNT5L _SFR_MEM8(0x124) +#define TCNT5H _SFR_MEM8(0x125) + +/* Combine ICR5L and ICR5H */ +#define ICR5 _SFR_MEM16(0x126) + +#define ICR5L _SFR_MEM8(0x126) +#define ICR5H _SFR_MEM8(0x127) + +/* Combine OCR5AL and OCR5AH */ +#define OCR5A _SFR_MEM16(0x128) + +#define OCR5AL _SFR_MEM8(0x128) +#define OCR5AH _SFR_MEM8(0x129) + +/* Combine OCR5BL and OCR5BH */ +#define OCR5B _SFR_MEM16(0x12A) + +#define OCR5BL _SFR_MEM8(0x12A) +#define OCR5BH _SFR_MEM8(0x12B) + +/* Combine OCR5CL and OCR5CH */ +#define OCR5C _SFR_MEM16(0x12C) + +#define OCR5CL _SFR_MEM8(0x12C) +#define OCR5CH _SFR_MEM8(0x12D) + +/* Reserved [0x12E..0x12F] */ + +#if defined(__ATmegaxx0__) + +# define UCSR3A _SFR_MEM8(0x130) +# define RXC3 7 +# define TXC3 6 +# define UDRE3 5 +# define FE3 4 +# define DOR3 3 +# define UPE3 2 +# define U2X3 1 +# define MPCM3 0 + +# define UCSR3B _SFR_MEM8(0X131) +# define RXCIE3 7 +# define TXCIE3 6 +# define UDRIE3 5 +# define RXEN3 4 +# define TXEN3 3 +# define UCSZ32 2 +# define RXB83 1 +# define TXB83 0 + +# define UCSR3C _SFR_MEM8(0x132) +# define UMSEL31 7 +# define UMSEL30 6 +# define UPM31 5 +# define UPM30 4 +# define USBS3 3 +# define UCSZ31 2 +# define UCSZ30 1 +# define UCPOL3 0 + +/* Reserved [0x133] */ + +/* Combine UBRR3L and UBRR3H */ +# define UBRR3 _SFR_MEM16(0x134) + +# define UBRR3L _SFR_MEM8(0x134) +# define UBRR3H _SFR_MEM8(0x135) + +# define UDR3 _SFR_MEM8(0X136) + +#endif /* __ATmegaxx0__ */ + +/* Reserved [0x137..1FF] */ + +/* Interrupt vectors */ +/* Vector 0 is the reset vector */ +/* External Interrupt Request 0 */ +#define INT0_vect _VECTOR(1) +#define SIG_INTERRUPT0 _VECTOR(1) + +/* External Interrupt Request 1 */ +#define INT1_vect _VECTOR(2) +#define SIG_INTERRUPT1 _VECTOR(2) + +/* External Interrupt Request 2 */ +#define INT2_vect _VECTOR(3) +#define SIG_INTERRUPT2 _VECTOR(3) + +/* External Interrupt Request 3 */ +#define INT3_vect _VECTOR(4) +#define SIG_INTERRUPT3 _VECTOR(4) + +/* External Interrupt Request 4 */ +#define INT4_vect _VECTOR(5) +#define SIG_INTERRUPT4 _VECTOR(5) + +/* External Interrupt Request 5 */ +#define INT5_vect _VECTOR(6) +#define SIG_INTERRUPT5 _VECTOR(6) + +/* External Interrupt Request 6 */ +#define INT6_vect _VECTOR(7) +#define SIG_INTERRUPT6 _VECTOR(7) + +/* External Interrupt Request 7 */ +#define INT7_vect _VECTOR(8) +#define SIG_INTERRUPT7 _VECTOR(8) + +/* Pin Change Interrupt Request 0 */ +#define PCINT0_vect _VECTOR(9) +#define SIG_PIN_CHANGE0 _VECTOR(9) + +/* Pin Change Interrupt Request 1 */ +#define PCINT1_vect _VECTOR(10) +#define SIG_PIN_CHANGE1 _VECTOR(10) + +#if defined(__ATmegaxx0__) +/* Pin Change Interrupt Request 2 */ +#define PCINT2_vect _VECTOR(11) +#define SIG_PIN_CHANGE2 _VECTOR(11) + +#endif /* __ATmegaxx0__ */ + +/* Watchdog Time-out Interrupt */ +#define WDT_vect _VECTOR(12) +#define SIG_WATCHDOG_TIMEOUT _VECTOR(12) + +/* Timer/Counter2 Compare Match A */ +#define TIMER2_COMPA_vect _VECTOR(13) +#define SIG_OUTPUT_COMPARE2A _VECTOR(13) + +/* Timer/Counter2 Compare Match B */ +#define TIMER2_COMPB_vect _VECTOR(14) +#define SIG_OUTPUT_COMPARE2B _VECTOR(14) + +/* Timer/Counter2 Overflow */ +#define TIMER2_OVF_vect _VECTOR(15) +#define SIG_OVERFLOW2 _VECTOR(15) + +/* Timer/Counter1 Capture Event */ +#define TIMER1_CAPT_vect _VECTOR(16) +#define SIG_INPUT_CAPTURE1 _VECTOR(16) + +/* Timer/Counter1 Compare Match A */ +#define TIMER1_COMPA_vect _VECTOR(17) +#define SIG_OUTPUT_COMPARE1A _VECTOR(17) + +/* Timer/Counter1 Compare Match B */ +#define TIMER1_COMPB_vect _VECTOR(18) +#define SIG_OUTPUT_COMPARE1B _VECTOR(18) + +/* Timer/Counter1 Compare Match C */ +#define TIMER1_COMPC_vect _VECTOR(19) +#define SIG_OUTPUT_COMPARE1C _VECTOR(19) + +/* Timer/Counter1 Overflow */ +#define TIMER1_OVF_vect _VECTOR(20) +#define SIG_OVERFLOW1 _VECTOR(20) + +/* Timer/Counter0 Compare Match A */ +#define TIMER0_COMPA_vect _VECTOR(21) +#define SIG_OUTPUT_COMPARE0A _VECTOR(21) + +/* Timer/Counter0 Compare Match B */ +#define TIMER0_COMPB_vect _VECTOR(22) +#define SIG_OUTPUT_COMPARE0B _VECTOR(22) + +/* Timer/Counter0 Overflow */ +#define TIMER0_OVF_vect _VECTOR(23) +#define SIG_OVERFLOW0 _VECTOR(23) + +/* SPI Serial Transfer Complete */ +#define SPI_STC_vect _VECTOR(24) +#define SIG_SPI _VECTOR(24) + +/* USART0, Rx Complete */ +#define USART0_RX_vect _VECTOR(25) +#define SIG_USART0_RECV _VECTOR(25) + +/* USART0 Data register Empty */ +#define USART0_UDRE_vect _VECTOR(26) +#define SIG_USART0_DATA _VECTOR(26) + +/* USART0, Tx Complete */ +#define USART0_TX_vect _VECTOR(27) +#define SIG_USART0_TRANS _VECTOR(27) + +/* Analog Comparator */ +#define ANALOG_COMP_vect _VECTOR(28) +#define SIG_COMPARATOR _VECTOR(28) + +/* ADC Conversion Complete */ +#define ADC_vect _VECTOR(29) +#define SIG_ADC _VECTOR(29) + +/* EEPROM Ready */ +#define EE_READY_vect _VECTOR(30) +#define SIG_EEPROM_READY _VECTOR(30) + +/* Timer/Counter3 Capture Event */ +#define TIMER3_CAPT_vect _VECTOR(31) +#define SIG_INPUT_CAPTURE3 _VECTOR(31) + +/* Timer/Counter3 Compare Match A */ +#define TIMER3_COMPA_vect _VECTOR(32) +#define SIG_OUTPUT_COMPARE3A _VECTOR(32) + +/* Timer/Counter3 Compare Match B */ +#define TIMER3_COMPB_vect _VECTOR(33) +#define SIG_OUTPUT_COMPARE3B _VECTOR(33) + +/* Timer/Counter3 Compare Match C */ +#define TIMER3_COMPC_vect _VECTOR(34) +#define SIG_OUTPUT_COMPARE3C _VECTOR(34) + +/* Timer/Counter3 Overflow */ +#define TIMER3_OVF_vect _VECTOR(35) +#define SIG_OVERFLOW3 _VECTOR(35) + +/* USART1, Rx Complete */ +#define USART1_RX_vect _VECTOR(36) +#define SIG_USART1_RECV _VECTOR(36) + +/* USART1 Data register Empty */ +#define USART1_UDRE_vect _VECTOR(37) +#define SIG_USART1_DATA _VECTOR(37) + +/* USART1, Tx Complete */ +#define USART1_TX_vect _VECTOR(38) +#define SIG_USART1_TRANS _VECTOR(38) + +/* 2-wire Serial Interface */ +#define TWI_vect _VECTOR(39) +#define SIG_2WIRE_SERIAL _VECTOR(39) + +/* Store Program Memory Read */ +#define SPM_READY_vect _VECTOR(40) +#define SIG_SPM_READY _VECTOR(40) + +#if defined(__ATmegaxx0__) +/* Timer/Counter4 Capture Event */ +#define TIMER4_CAPT_vect _VECTOR(41) +#define SIG_INPUT_CAPTURE4 _VECTOR(41) + +#endif /* __ATmegaxx0__ */ + +/* Timer/Counter4 Compare Match A */ +#define TIMER4_COMPA_vect _VECTOR(42) +#define SIG_OUTPUT_COMPARE4A _VECTOR(42) + +/* Timer/Counter4 Compare Match B */ +#define TIMER4_COMPB_vect _VECTOR(43) +#define SIG_OUTPUT_COMPARE4B _VECTOR(43) + +/* Timer/Counter4 Compare Match C */ +#define TIMER4_COMPC_vect _VECTOR(44) +#define SIG_OUTPUT_COMPARE4C _VECTOR(44) + +/* Timer/Counter4 Overflow */ +#define TIMER4_OVF_vect _VECTOR(45) +#define SIG_OVERFLOW4 _VECTOR(45) + +#if defined(__ATmegaxx0__) +/* Timer/Counter5 Capture Event */ +#define TIMER5_CAPT_vect _VECTOR(46) +#define SIG_INPUT_CAPTURE5 _VECTOR(46) + +#endif /* __ATmegaxx0__ */ + +/* Timer/Counter5 Compare Match A */ +#define TIMER5_COMPA_vect _VECTOR(47) +#define SIG_OUTPUT_COMPARE5A _VECTOR(47) + +/* Timer/Counter5 Compare Match B */ +#define TIMER5_COMPB_vect _VECTOR(48) +#define SIG_OUTPUT_COMPARE5B _VECTOR(48) + +/* Timer/Counter5 Compare Match C */ +#define TIMER5_COMPC_vect _VECTOR(49) +#define SIG_OUTPUT_COMPARE5C _VECTOR(49) + +/* Timer/Counter5 Overflow */ +#define TIMER5_OVF_vect _VECTOR(50) +#define SIG_OVERFLOW5 _VECTOR(50) + +#if defined(__ATmegaxx1__) + +# define _VECTORS_SIZE 204 + +#else + +/* USART2, Rx Complete */ +#define USART2_RX_vect _VECTOR(51) +#define SIG_USART2_RECV _VECTOR(51) + +/* USART2 Data register Empty */ +#define USART2_UDRE_vect _VECTOR(52) +#define SIG_USART2_DATA _VECTOR(52) + +/* USART2, Tx Complete */ +#define USART2_TX_vect _VECTOR(53) +#define SIG_USART2_TRANS _VECTOR(53) + +/* USART3, Rx Complete */ +#define USART3_RX_vect _VECTOR(54) +#define SIG_USART3_RECV _VECTOR(54) + +/* USART3 Data register Empty */ +#define USART3_UDRE_vect _VECTOR(55) +#define SIG_USART3_DATA _VECTOR(55) + +/* USART3, Tx Complete */ +#define USART3_TX_vect _VECTOR(56) +#define SIG_USART3_TRANS _VECTOR(56) + +# define _VECTORS_SIZE 228 + +#endif /* __ATmegaxx1__ */ + +#if defined(__ATmegaxx0__) +# undef __ATmegaxx0__ +#endif + +#if defined(__ATmegaxx1__) +# undef __ATmegaxx1__ +#endif + +#endif /* _AVR_IOMXX0_1_H_ */ diff --git a/libraries/Desktop/include/avr/pgmspace.h b/libraries/Desktop/include/avr/pgmspace.h new file mode 100644 index 0000000000..c9ceb57367 --- /dev/null +++ b/libraries/Desktop/include/avr/pgmspace.h @@ -0,0 +1,49 @@ +#ifndef _PGMSPACE_H +#define _PGMSPACE_H + +#include +#include +#include + +#ifndef __ATTR_PROGMEM__ +#define __ATTR_PROGMEM__ __attribute__(()) +#endif + +#ifndef __ATTR_PURE__ +#define __ATTR_PURE__ __attribute__((__pure__)) +#endif + +#undef PROGMEM +#define PROGMEM __ATTR_PROGMEM__ + +#ifndef PGM_P +#define PGM_P const prog_char * +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +typedef char PROGMEM prog_char; +extern int strcasecmp_P(const char *, PGM_P) __ATTR_PURE__; +extern int strcmp_P(const char *, PGM_P) __ATTR_PURE__; +extern size_t strlcat_P (char *, PGM_P, size_t ); +extern size_t strnlen_P (PGM_P, size_t ); + +static inline uint8_t pgm_read_byte(PGM_P s) { return (uint8_t)*s; } +static inline uint16_t pgm_read_word(const void *s) { return *(const uint16_t *)s; } + +#define GETBYTE(flag, mask, pnt) ({ \ + unsigned char __c; \ + __c = ((flag) & (mask)) \ + ? pgm_read_byte(pnt) : *pnt; \ + pnt++; \ + __c; \ +}) + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/libraries/Desktop/include/avr/wiring.h b/libraries/Desktop/include/avr/wiring.h new file mode 100644 index 0000000000..e69de29bb2 diff --git a/libraries/Desktop/include/binary.h b/libraries/Desktop/include/binary.h new file mode 100644 index 0000000000..af1498033a --- /dev/null +++ b/libraries/Desktop/include/binary.h @@ -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 diff --git a/libraries/Desktop/include/pins_arduino.h b/libraries/Desktop/include/pins_arduino.h new file mode 100644 index 0000000000..bc931c597c --- /dev/null +++ b/libraries/Desktop/include/pins_arduino.h @@ -0,0 +1,88 @@ +/* + 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 + +#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 + +#define TIMER3A 8 +#define TIMER3B 9 +#define TIMER3C 10 +#define TIMER4A 11 +#define TIMER4B 12 +#define TIMER4C 13 +#define TIMER5A 14 +#define TIMER5B 15 +#define TIMER5C 16 + +#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) +const static uint8_t SS = 53; +const static uint8_t MOSI = 51; +const static uint8_t MISO = 50; +const static uint8_t SCK = 52; +#else +const static uint8_t SS = 10; +const static uint8_t MOSI = 11; +const static uint8_t MISO = 12; +const static uint8_t SCK = 13; +#endif + +// On the ATmega1280, the addresses of some of the port registers are +// greater than 255, so we can't store them in uint8_t's. +extern const uint16_t PROGMEM port_to_mode_PGM[]; +extern const uint16_t PROGMEM port_to_input_PGM[]; +extern const uint16_t PROGMEM port_to_output_PGM[]; + +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_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))) ) + +#endif diff --git a/libraries/Desktop/include/wiring.h b/libraries/Desktop/include/wiring.h new file mode 100644 index 0000000000..a441ef6f62 --- /dev/null +++ b/libraries/Desktop/include/wiring.h @@ -0,0 +1,135 @@ +/* + wiring.h - 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$ +*/ + +#ifndef Wiring_h +#define Wiring_h + +#include +#include +#include "binary.h" + +#ifdef __cplusplus +extern "C"{ +#endif + +#define HIGH 0x1 +#define LOW 0x0 + +#define INPUT 0x0 +#define OUTPUT 0x1 + +#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 + +#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) +#define INTERNAL1V1 2 +#define INTERNAL2V56 3 +#else +#define INTERNAL 3 +#endif +#define DEFAULT 1 +#define EXTERNAL 0 + +// 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))) +//#define round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) +#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() + +#define clockCyclesPerMicrosecond() ( F_CPU / 1000000L ) +#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 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); + +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); + +#ifdef __cplusplus +} // extern "C" +#endif + +void setup(void); +void loop(void); + +#endif diff --git a/libraries/Desktop/support/Arduino.cpp b/libraries/Desktop/support/Arduino.cpp new file mode 100644 index 0000000000..005083b525 --- /dev/null +++ b/libraries/Desktop/support/Arduino.cpp @@ -0,0 +1,124 @@ +#include "WProgram.h" +#include +#include +#include +#include +#include "avr/pgmspace.h" +#include +#include + +extern "C" { + +volatile uint8_t __iomem[1024]; + +unsigned __brkval = 0x2000; +unsigned __bss_end = 0x1000; + +void pinMode(uint8_t pin, uint8_t mode) +{ + +} + + +long unsigned int millis(void) +{ + extern struct timeval sketch_start_time; + struct timeval tp; + gettimeofday(&tp,NULL); + return 1.0e3*(tp.tv_sec + (tp.tv_usec*1.0e-6)) - + (sketch_start_time.tv_sec + (sketch_start_time.tv_usec*1.0e-6)); +} + +long unsigned int micros(void) +{ + extern struct timeval sketch_start_time; + struct timeval tp; + gettimeofday(&tp,NULL); + return 1.0e6*(tp.tv_sec + (tp.tv_usec*1.0e-6)) - + (sketch_start_time.tv_sec + (sketch_start_time.tv_usec*1.0e-6)); +} + +void delay(long unsigned msec) +{ + usleep(msec*1000); +} + +size_t strlcat_P(char *dst, PGM_P src, size_t size) +{ + return strlcat(dst, src, size); +} + +size_t strnlen_P(PGM_P str, size_t size) +{ + return strnlen(str, size); +} + +int strcasecmp_P(PGM_P str1, PGM_P str2) +{ + return strcasecmp(str1, str2); +} + + +void digitalWrite(uint8_t pin, uint8_t val) +{ +} + +int analogRead(uint8_t pin) +{ + return 0; +} + +} + + +char *itoa(int __val, char *__s, int __radix) +{ + switch (__radix) { + case 8: + sprintf(__s, "%o", __val); + break; + case 16: + sprintf(__s, "%x", __val); + break; + case 10: + default: + sprintf(__s, "%d", __val); + break; + } + return __s; +} + +char *ultoa(unsigned long __val, char *__s, int __radix) +{ + switch (__radix) { + case 8: + sprintf(__s, "%lo", __val); + break; + case 16: + sprintf(__s, "%lx", __val); + break; + case 10: + default: + sprintf(__s, "%lu", __val); + break; + } + return __s; +} + +char *ltoa(long __val, char *__s, int __radix) +{ + switch (__radix) { + case 8: + sprintf(__s, "%lo", __val); + break; + case 16: + sprintf(__s, "%lx", __val); + break; + case 10: + default: + sprintf(__s, "%ld", __val); + break; + } + return __s; +} + diff --git a/libraries/Desktop/support/FastSerial.cpp b/libraries/Desktop/support/FastSerial.cpp new file mode 100644 index 0000000000..2411c9c8d5 --- /dev/null +++ b/libraries/Desktop/support/FastSerial.cpp @@ -0,0 +1,122 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- +// +// Interrupt-driven serial transmit/receive library. +// +// Copyright (c) 2010 Michael Smith. All rights reserved. +// +// Receive and baudrate calculations derived from the Arduino +// HardwareSerial driver: +// +// Copyright (c) 2006 Nicholas Zambetti. All right reserved. +// +// Transmit algorithm inspired by work: +// +// Code Jose Julio and Jordi Munoz. DIYDrones.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 "../AP_Common/AP_Common.h" +#include "FastSerial.h" +#include "WProgram.h" +#include + +#if defined(UDR3) +# define FS_MAX_PORTS 4 +#elif defined(UDR2) +# define FS_MAX_PORTS 3 +#elif defined(UDR1) +# define FS_MAX_PORTS 2 +#else +# define FS_MAX_PORTS 1 +#endif + +FastSerial::Buffer __FastSerial__rxBuffer[FS_MAX_PORTS]; +FastSerial::Buffer __FastSerial__txBuffer[FS_MAX_PORTS]; + +// Constructor ///////////////////////////////////////////////////////////////// + +FastSerial::FastSerial(const uint8_t portNumber, volatile uint8_t *ubrrh, volatile uint8_t *ubrrl, + volatile uint8_t *ucsra, volatile uint8_t *ucsrb, const uint8_t u2x, + const uint8_t portEnableBits, const uint8_t portTxBits) : + _ubrrh(ubrrh), + _ubrrl(ubrrl), + _ucsra(ucsra), + _ucsrb(ucsrb), + _u2x(u2x), + _portEnableBits(portEnableBits), + _portTxBits(portTxBits), + _rxBuffer(&__FastSerial__rxBuffer[portNumber]), + _txBuffer(&__FastSerial__txBuffer[portNumber]) +{ +} + +// Public Methods ////////////////////////////////////////////////////////////// + +void FastSerial::begin(long baud) +{ +} + +void FastSerial::begin(long baud, unsigned int rxSpace, unsigned int txSpace) +{ +} + +void FastSerial::end() +{ +} + +int FastSerial::available(void) +{ + return 0; +} + +int FastSerial::txspace(void) +{ + return 128; +} + +int FastSerial::read(void) +{ + char c; + pread(0, (void *)&c, 1, 0); + return (int)c; +} + +int FastSerial::peek(void) +{ + return -1; +} + +void FastSerial::flush(void) +{ +} + +void FastSerial::write(uint8_t c) +{ + fwrite(&c, 1, 1, stdout); +} + +// Buffer management /////////////////////////////////////////////////////////// + +bool FastSerial::_allocBuffer(Buffer *buffer, unsigned int size) +{ + return false; +} + +void FastSerial::_freeBuffer(Buffer *buffer) +{ +} + diff --git a/libraries/Desktop/support/Print.cpp b/libraries/Desktop/support/Print.cpp new file mode 100644 index 0000000000..fd689423a4 --- /dev/null +++ b/libraries/Desktop/support/Print.cpp @@ -0,0 +1,220 @@ +/* + 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 +#include +#include +#include +#include "wiring.h" + +#include "Print.h" + +// Public Methods ////////////////////////////////////////////////////////////// + +/* default implementation: may be overridden */ +void Print::write(const char *str) +{ + while (*str) + write(*str++); +} + +/* default implementation: may be overridden */ +void Print::write(const uint8_t *buffer, size_t size) +{ + while (size--) + write(*buffer++); +} + +void Print::print(const String &s) +{ + for (unsigned int i = 0; i < s.length(); i++) { + write(s[i]); + } +} + +void Print::print(const char str[]) +{ + write(str); +} + +void Print::print(char c, int base) +{ + print((long) c, base); +} + +void Print::print(unsigned char b, int base) +{ + print((unsigned long) b, base); +} + +void Print::print(int n, int base) +{ + print((long) n, base); +} + +void Print::print(unsigned int n, int base) +{ + print((unsigned long) n, base); +} + +void Print::print(long n, int base) +{ + if (base == 0) { + write(n); + } else if (base == 10) { + if (n < 0) { + print('-'); + n = -n; + } + printNumber(n, 10); + } else { + printNumber(n, base); + } +} + +void Print::print(unsigned long n, int base) +{ + if (base == 0) write(n); + else printNumber(n, base); +} + +void Print::print(double n, int digits) +{ + printFloat(n, digits); +} + +void Print::println(void) +{ + print('\r'); + print('\n'); +} + +void Print::println(const String &s) +{ + print(s); + println(); +} + +void Print::println(const char c[]) +{ + print(c); + println(); +} + +void Print::println(char c, int base) +{ + print(c, base); + println(); +} + +void Print::println(unsigned char b, int base) +{ + print(b, base); + println(); +} + +void Print::println(int n, int base) +{ + print(n, base); + println(); +} + +void Print::println(unsigned int n, int base) +{ + print(n, base); + println(); +} + +void Print::println(long n, int base) +{ + print(n, base); + println(); +} + +void Print::println(unsigned long n, int base) +{ + print(n, base); + println(); +} + +void Print::println(double n, int digits) +{ + print(n, digits); + println(); +} + +// Private Methods ///////////////////////////////////////////////////////////// + +void Print::printNumber(unsigned long n, uint8_t base) +{ + unsigned char buf[8 * sizeof(long)]; // Assumes 8-bit chars. + unsigned long i = 0; + + if (n == 0) { + print('0'); + return; + } + + while (n > 0) { + buf[i++] = n % base; + n /= base; + } + + for (; i > 0; i--) + print((char) (buf[i - 1] < 10 ? + '0' + buf[i - 1] : + 'A' + buf[i - 1] - 10)); +} + +void Print::printFloat(double number, uint8_t digits) +{ + // Handle negative numbers + if (number < 0.0) + { + 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 0) + print("."); + + // Extract digits from the remainder one at a time + while (digits-- > 0) + { + remainder *= 10.0; + int toPrint = int(remainder); + print(toPrint); + remainder -= toPrint; + } +} diff --git a/libraries/Desktop/support/SPI.cpp b/libraries/Desktop/support/SPI.cpp new file mode 100644 index 0000000000..42915df1eb --- /dev/null +++ b/libraries/Desktop/support/SPI.cpp @@ -0,0 +1,61 @@ +/* + * Copyright (c) 2010 by Cristian Maglie + * SPI Master library for arduino. + * + * 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. + */ + +#include "pins_arduino.h" +#include "SPI.h" + +SPIClass SPI; + +void SPIClass::begin() { + // Set direction register for SCK and MOSI pin. + // MISO pin automatically overrides to INPUT. + // When the SS pin is set as OUTPUT, it can be used as + // a general purpose output port (it doesn't influence + // SPI operations). + + pinMode(SCK, OUTPUT); + pinMode(MOSI, OUTPUT); + pinMode(SS, OUTPUT); + + digitalWrite(SCK, LOW); + digitalWrite(MOSI, LOW); + digitalWrite(SS, HIGH); + + // Warning: if the SS pin ever becomes a LOW INPUT then SPI + // automatically switches to Slave, so the data direction of + // the SS pin MUST be kept as OUTPUT. + SPCR |= _BV(MSTR); + SPCR |= _BV(SPE); +} + +void SPIClass::end() { + SPCR &= ~_BV(SPE); +} + +void SPIClass::setBitOrder(uint8_t bitOrder) +{ + if(bitOrder == LSBFIRST) { + SPCR |= _BV(DORD); + } else { + SPCR &= ~(_BV(DORD)); + } +} + +void SPIClass::setDataMode(uint8_t mode) +{ + SPCR = (SPCR & ~SPI_MODE_MASK) | mode; +} + +void SPIClass::setClockDivider(uint8_t rate) +{ + SPCR = (SPCR & ~SPI_CLOCK_MASK) | (rate & SPI_CLOCK_MASK); + SPSR = (SPSR & ~SPI_2XCLOCK_MASK) | ((rate >> 2) & SPI_2XCLOCK_MASK); +} + diff --git a/libraries/Desktop/support/WString.cpp b/libraries/Desktop/support/WString.cpp new file mode 100644 index 0000000000..db5a441dc2 --- /dev/null +++ b/libraries/Desktop/support/WString.cpp @@ -0,0 +1,443 @@ +/* + WString.cpp - String library for Wiring & Arduino + Copyright (c) 2009-10 Hernando Barragan. All rights reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include "WProgram.h" +#include "WString.h" + + +String::String( const char *value ) +{ + if ( value == NULL ) + value = ""; + getBuffer( _length = strlen( value ) ); + if ( _buffer != NULL ) + strcpy( _buffer, value ); +} + +String::String( const String &value ) +{ + getBuffer( _length = value._length ); + if ( _buffer != NULL ) + strcpy( _buffer, value._buffer ); +} + +String::String( const char value ) +{ + _length = 1; + getBuffer(1); + if ( _buffer != NULL ) { + _buffer[0] = value; + _buffer[1] = 0; + } +} + +String::String( const unsigned char value ) +{ + _length = 1; + getBuffer(1); + if ( _buffer != NULL) { + _buffer[0] = value; + _buffer[1] = 0; + } +} + +String::String( const int value, const int base ) +{ + char buf[33]; + itoa((signed long)value, buf, base); + getBuffer( _length = strlen(buf) ); + if ( _buffer != NULL ) + strcpy( _buffer, buf ); +} + +String::String( const unsigned int value, const int base ) +{ + char buf[33]; + ultoa((unsigned long)value, buf, base); + getBuffer( _length = strlen(buf) ); + if ( _buffer != NULL ) + strcpy( _buffer, buf ); +} + +String::String( const long value, const int base ) +{ + char buf[33]; + ltoa(value, buf, base); + getBuffer( _length = strlen(buf) ); + if ( _buffer != NULL ) + strcpy( _buffer, buf ); +} + +String::String( const unsigned long value, const int base ) +{ + char buf[33]; + ultoa(value, buf, 10); + getBuffer( _length = strlen(buf) ); + if ( _buffer != NULL ) + strcpy( _buffer, buf ); +} + +char String::charAt( unsigned int loc ) const +{ + return operator[]( loc ); +} + +void String::setCharAt( unsigned int loc, const char aChar ) +{ + if(_buffer == NULL) return; + if(_length > loc) { + _buffer[loc] = aChar; + } +} + +int String::compareTo( const String &s2 ) const +{ + return strcmp( _buffer, s2._buffer ); +} + +const String & String::concat( const String &s2 ) +{ + return (*this) += s2; +} + +const String & String::operator=( const String &rhs ) +{ + if ( this == &rhs ) + return *this; + + if ( rhs._length > _length ) + { + free(_buffer); + getBuffer( rhs._length ); + } + + if ( _buffer != NULL ) { + _length = rhs._length; + strcpy( _buffer, rhs._buffer ); + } + return *this; +} + +//const String & String::operator+=( const char aChar ) +//{ +// if ( _length == _capacity ) +// doubleBuffer(); +// +// _buffer[ _length++ ] = aChar; +// _buffer[ _length ] = '\0'; +// return *this; +//} + +const String & String::operator+=( const String &other ) +{ + _length += other._length; + if ( _length > _capacity ) + { + char *temp = (char *)realloc(_buffer, _length + 1); + if ( temp != NULL ) { + _buffer = temp; + _capacity = _length; + } else { + _length -= other._length; + return *this; + } + } + strcat( _buffer, other._buffer ); + return *this; +} + + +int String::operator==( const String &rhs ) const +{ + return ( _length == rhs._length && strcmp( _buffer, rhs._buffer ) == 0 ); +} + +int String::operator!=( const String &rhs ) const +{ + return ( _length != rhs.length() || strcmp( _buffer, rhs._buffer ) != 0 ); +} + +int String::operator<( const String &rhs ) const +{ + return strcmp( _buffer, rhs._buffer ) < 0; +} + +int String::operator>( const String &rhs ) const +{ + return strcmp( _buffer, rhs._buffer ) > 0; +} + +int String::operator<=( const String &rhs ) const +{ + return strcmp( _buffer, rhs._buffer ) <= 0; +} + +int String::operator>=( const String & rhs ) const +{ + return strcmp( _buffer, rhs._buffer ) >= 0; +} + +char & String::operator[]( unsigned int index ) +{ + static char dummy_writable_char; + if (index >= _length || !_buffer) { + dummy_writable_char = 0; + return dummy_writable_char; + } + return _buffer[ index ]; +} + +char String::operator[]( unsigned int index ) const +{ + // need to check for valid index, to do later + return _buffer[ index ]; +} + +boolean String::endsWith( const String &s2 ) const +{ + if ( _length < s2._length ) + return 0; + + return strcmp( &_buffer[ _length - s2._length], s2._buffer ) == 0; +} + +boolean String::equals( const String &s2 ) const +{ + return ( _length == s2._length && strcmp( _buffer,s2._buffer ) == 0 ); +} + +boolean String::equalsIgnoreCase( const String &s2 ) const +{ + if ( this == &s2 ) + return true; //1; + else if ( _length != s2._length ) + return false; //0; + + return strcmp(toLowerCase()._buffer, s2.toLowerCase()._buffer) == 0; +} + +String String::replace( char findChar, char replaceChar ) +{ + if ( _buffer == NULL ) return *this; + String theReturn = _buffer; + char* temp = theReturn._buffer; + while( (temp = strchr( temp, findChar )) != 0 ) + *temp = replaceChar; + + return theReturn; +} + +String String::replace( const String& match, const String& replace ) +{ + if ( _buffer == NULL ) return *this; + String temp = _buffer, newString; + + int loc; + while ( (loc = temp.indexOf( match )) != -1 ) + { + newString += temp.substring( 0, loc ); + newString += replace; + temp = temp.substring( loc + match._length ); + } + newString += temp; + return newString; +} + +int String::indexOf( char temp ) const +{ + return indexOf( temp, 0 ); +} + +int String::indexOf( char ch, unsigned int fromIndex ) const +{ + if ( fromIndex >= _length ) + 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 >= _length ) + return -1; + + const char *theFind = strstr( &_buffer[ fromIndex ], s2._buffer ); + + if ( theFind == NULL ) + return -1; + + return theFind - _buffer; // pointer subtraction +} + +int String::lastIndexOf( char theChar ) const +{ + return lastIndexOf( theChar, _length - 1 ); +} + +int String::lastIndexOf( char ch, unsigned int fromIndex ) const +{ + if ( fromIndex >= _length ) + 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, _length - s2._length ); +} + +int String::lastIndexOf( const String &s2, unsigned int fromIndex ) const +{ + // check for empty strings + if ( s2._length == 0 || s2._length - 1 > fromIndex || fromIndex >= _length ) + return -1; + + // matching first character + char temp = s2[ 0 ]; + + for ( int i = fromIndex; i >= 0; i-- ) + { + if ( _buffer[ i ] == temp && (*this).substring( i, i + s2._length ).equals( s2 ) ) + return i; + } + return -1; +} + +boolean String::startsWith( const String &s2 ) const +{ + if ( _length < s2._length ) + return 0; + + return startsWith( s2, 0 ); +} + +boolean String::startsWith( const String &s2, unsigned int offset ) const +{ + if ( offset > _length - s2._length ) + return 0; + + return strncmp( &_buffer[offset], s2._buffer, s2._length ) == 0; +} + +String String::substring( unsigned int left ) const +{ + return substring( left, _length ); +} + +String String::substring( unsigned int left, unsigned int right ) const +{ + if ( left > right ) + { + int temp = right; + right = left; + left = temp; + } + + if ( right > _length ) + { + right = _length; + } + + char temp = _buffer[ right ]; // save the replaced character + _buffer[ right ] = '\0'; + String outPut = ( _buffer + left ); // pointer arithmetic + _buffer[ right ] = temp; //restore character + return outPut; +} + +String String::toLowerCase() const +{ + String temp = _buffer; + + for ( unsigned int i = 0; i < _length; i++ ) + temp._buffer[ i ] = (char)tolower( temp._buffer[ i ] ); + return temp; +} + +String String::toUpperCase() const +{ + String temp = _buffer; + + for ( unsigned int i = 0; i < _length; i++ ) + temp._buffer[ i ] = (char)toupper( temp._buffer[ i ] ); + return temp; +} + +String String::trim() const +{ + if ( _buffer == NULL ) return *this; + String temp = _buffer; + unsigned int i,j; + + for ( i = 0; i < _length; i++ ) + { + if ( !isspace(_buffer[i]) ) + break; + } + + for ( j = temp._length - 1; j > i; j-- ) + { + if ( !isspace(_buffer[j]) ) + break; + } + + return temp.substring( i, j + 1); +} + +void String::getBytes(unsigned char *buf, unsigned int bufsize) +{ + if (!bufsize || !buf) return; + unsigned int len = bufsize - 1; + if (len > _length) len = _length; + strncpy((char *)buf, _buffer, len); + buf[len] = 0; +} + +void String::toCharArray(char *buf, unsigned int bufsize) +{ + if (!bufsize || !buf) return; + unsigned int len = bufsize - 1; + if (len > _length) len = _length; + strncpy(buf, _buffer, len); + buf[len] = 0; +} + + +long String::toInt() { + return atol(_buffer); +} diff --git a/libraries/Desktop/support/eeprom.c b/libraries/Desktop/support/eeprom.c new file mode 100644 index 0000000000..d5dc5eea35 --- /dev/null +++ b/libraries/Desktop/support/eeprom.c @@ -0,0 +1,86 @@ +#include +#include +#include +#include +#include +#include + +static int eeprom_fd; + +static void eeprom_open(void) +{ + if (eeprom_fd == 0) { + eeprom_fd = open("eeprom.bin", O_RDWR|O_CREAT, 0777); + } +} + +void eeprom_write_byte(uint8_t *p, uint8_t value) +{ + intptr_t ofs = (intptr_t)p; + assert(ofs < 4096); + eeprom_open(); + pwrite(eeprom_fd, &value, 1, ofs); +} + + +void eeprom_write_word(uint16_t *p, uint16_t value) +{ + intptr_t ofs = (intptr_t)p; + assert(ofs < 4096); + eeprom_open(); + pwrite(eeprom_fd, &value, 2, ofs); +} + +void eeprom_write_dword(uint16_t *p, uint32_t value) +{ + intptr_t ofs = (intptr_t)p; + assert(ofs < 4096); + eeprom_open(); + pwrite(eeprom_fd, &value, 4, ofs); +} + +uint8_t eeprom_read_byte(const uint8_t *p) +{ + intptr_t ofs = (intptr_t)p; + uint8_t value; + assert(ofs < 4096); + eeprom_open(); + pread(eeprom_fd, &value, 1, ofs); + return value; +} + +uint16_t eeprom_read_word(const uint16_t *p) +{ + intptr_t ofs = (intptr_t)p; + uint16_t value; + assert(ofs < 4096); + eeprom_open(); + pread(eeprom_fd, &value, 2, ofs); + return value; +} + +uint32_t eeprom_read_dword(const uint32_t *p) +{ + intptr_t ofs = (intptr_t)p; + uint32_t value; + assert(ofs < 4096); + eeprom_open(); + pread(eeprom_fd, &value, 4, ofs); + return value; +} + +void eeprom_read_block(void *buf, void *ptr, uint8_t size) +{ + intptr_t ofs = (intptr_t)ptr; + assert(ofs < 4096); + eeprom_open(); + pread(eeprom_fd, buf, size, ofs); +} + +void eeprom_write_block(const void *buf, void *ptr, uint8_t size) +{ + intptr_t ofs = (intptr_t)ptr; + assert(ofs < 4096); + eeprom_open(); + pwrite(eeprom_fd, buf, size, ofs); +} diff --git a/libraries/Desktop/support/ftoa_engine.c b/libraries/Desktop/support/ftoa_engine.c new file mode 100644 index 0000000000..65fa10d01d --- /dev/null +++ b/libraries/Desktop/support/ftoa_engine.c @@ -0,0 +1,7 @@ +#include + +int __ftoa_engine(double val, char *buf, + unsigned char prec, unsigned char maxdgs) +{ + return sprintf(buf, "%*.*lf", prec, maxdgs, val); +} diff --git a/libraries/Desktop/support/main.cpp b/libraries/Desktop/support/main.cpp new file mode 100644 index 0000000000..017b7d29fc --- /dev/null +++ b/libraries/Desktop/support/main.cpp @@ -0,0 +1,16 @@ +#include +#include +#include + +void setup(void); +void loop(void); + +struct timeval sketch_start_time; + +int main(void) +{ + gettimeofday(&sketch_start_time, NULL); + setup(); + while (true) loop(); + return 0; +} diff --git a/libraries/Desktop/support/ultoa_invert.c b/libraries/Desktop/support/ultoa_invert.c new file mode 100644 index 0000000000..b7e941cd3f --- /dev/null +++ b/libraries/Desktop/support/ultoa_invert.c @@ -0,0 +1,12 @@ +#include + +char * __ultoa_invert(unsigned long val, char *s, int base) +{ + switch (base) { + case 8: + return s+sprintf(s, "%lo", val); + case 16: + return s+sprintf(s, "%lx", val); + } + return s+sprintf(s, "%lu", val); +} From dfef42ff48a04332f5146ef4302e732753cfbef4 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 9 Oct 2011 15:55:02 +1100 Subject: [PATCH 04/15] desktop: flush all serial writes --- libraries/Desktop/support/FastSerial.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/Desktop/support/FastSerial.cpp b/libraries/Desktop/support/FastSerial.cpp index 2411c9c8d5..8b1850fe37 100644 --- a/libraries/Desktop/support/FastSerial.cpp +++ b/libraries/Desktop/support/FastSerial.cpp @@ -33,6 +33,7 @@ #include "FastSerial.h" #include "WProgram.h" #include +#include #if defined(UDR3) # define FS_MAX_PORTS 4 @@ -68,10 +69,12 @@ FastSerial::FastSerial(const uint8_t portNumber, volatile uint8_t *ubrrh, volati void FastSerial::begin(long baud) { + printf("Starting serial port\n"); } void FastSerial::begin(long baud, unsigned int rxSpace, unsigned int txSpace) { + begin(baud); } void FastSerial::end() @@ -107,6 +110,7 @@ void FastSerial::flush(void) void FastSerial::write(uint8_t c) { fwrite(&c, 1, 1, stdout); + fflush(stdout); } // Buffer management /////////////////////////////////////////////////////////// From e3fd61d75800c1a0666b35bf3021b05c4516b100 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 9 Oct 2011 15:55:21 +1100 Subject: [PATCH 05/15] desktop: expand eeprom to 4k initial size --- libraries/Desktop/support/eeprom.c | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/Desktop/support/eeprom.c b/libraries/Desktop/support/eeprom.c index d5dc5eea35..c6c8b11b81 100644 --- a/libraries/Desktop/support/eeprom.c +++ b/libraries/Desktop/support/eeprom.c @@ -11,6 +11,7 @@ static void eeprom_open(void) { if (eeprom_fd == 0) { eeprom_fd = open("eeprom.bin", O_RDWR|O_CREAT, 0777); + ftruncate(eeprom_fd, 4096); } } From ea2823cd5f407ad84989747c8c7b71f34d521106 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 9 Oct 2011 20:40:51 +1100 Subject: [PATCH 06/15] desktop: use non-blocking IO --- libraries/Desktop/support/FastSerial.cpp | 26 +++++++++++++++++++++--- 1 file changed, 23 insertions(+), 3 deletions(-) diff --git a/libraries/Desktop/support/FastSerial.cpp b/libraries/Desktop/support/FastSerial.cpp index 8b1850fe37..fbca781a2c 100644 --- a/libraries/Desktop/support/FastSerial.cpp +++ b/libraries/Desktop/support/FastSerial.cpp @@ -34,6 +34,7 @@ #include "WProgram.h" #include #include +#include #if defined(UDR3) # define FS_MAX_PORTS 4 @@ -57,7 +58,7 @@ FastSerial::FastSerial(const uint8_t portNumber, volatile uint8_t *ubrrh, volati _ubrrl(ubrrl), _ucsra(ucsra), _ucsrb(ucsrb), - _u2x(u2x), + _u2x(portNumber), _portEnableBits(portEnableBits), _portTxBits(portTxBits), _rxBuffer(&__FastSerial__rxBuffer[portNumber]), @@ -69,7 +70,13 @@ FastSerial::FastSerial(const uint8_t portNumber, volatile uint8_t *ubrrh, volati void FastSerial::begin(long baud) { - printf("Starting serial port\n"); + if (_u2x == 0) { + unsigned v; + v = fcntl(0, F_GETFL, 0); + fcntl(0, F_SETFL, v | O_NONBLOCK); + v = fcntl(1, F_GETFL, 0); + fcntl(1, F_SETFL, v | O_NONBLOCK); + } } void FastSerial::begin(long baud, unsigned int rxSpace, unsigned int txSpace) @@ -83,6 +90,11 @@ void FastSerial::end() int FastSerial::available(void) { + if (_u2x != 0) return 0; + int num_ready; + if (ioctl(0, FIONREAD, &num_ready) == 0) { + return num_ready; + } return 0; } @@ -93,8 +105,13 @@ int FastSerial::txspace(void) int FastSerial::read(void) { + if (_u2x != 0) { + return -1; + } char c; - pread(0, (void *)&c, 1, 0); + if (fread(&c, 1, 1, stdin) != 1) { + return -1; + } return (int)c; } @@ -109,6 +126,9 @@ void FastSerial::flush(void) void FastSerial::write(uint8_t c) { + if (_u2x != 0) { + return; + } fwrite(&c, 1, 1, stdout); fflush(stdout); } From 320d4a330b54873ce479924bb448e20c26bae248 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 9 Oct 2011 20:41:03 +1100 Subject: [PATCH 07/15] desktop: use a bit less CPU --- libraries/Desktop/support/main.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/libraries/Desktop/support/main.cpp b/libraries/Desktop/support/main.cpp index 017b7d29fc..f8efc34ac7 100644 --- a/libraries/Desktop/support/main.cpp +++ b/libraries/Desktop/support/main.cpp @@ -1,4 +1,5 @@ #include +#include #include #include @@ -11,6 +12,9 @@ int main(void) { gettimeofday(&sketch_start_time, NULL); setup(); - while (true) loop(); + while (true) { + loop(); + usleep(10); + } return 0; } From 41d734846e17138c0edc34407389be007557f6cb Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 9 Oct 2011 21:21:50 +1100 Subject: [PATCH 08/15] fixed millis() and micros() --- libraries/Desktop/support/Arduino.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/Desktop/support/Arduino.cpp b/libraries/Desktop/support/Arduino.cpp index 005083b525..7a6c7dc4bd 100644 --- a/libraries/Desktop/support/Arduino.cpp +++ b/libraries/Desktop/support/Arduino.cpp @@ -25,8 +25,8 @@ long unsigned int millis(void) extern struct timeval sketch_start_time; struct timeval tp; gettimeofday(&tp,NULL); - return 1.0e3*(tp.tv_sec + (tp.tv_usec*1.0e-6)) - - (sketch_start_time.tv_sec + (sketch_start_time.tv_usec*1.0e-6)); + return 1.0e3*((tp.tv_sec + (tp.tv_usec*1.0e-6)) - + (sketch_start_time.tv_sec + (sketch_start_time.tv_usec*1.0e-6))); } long unsigned int micros(void) @@ -34,8 +34,8 @@ long unsigned int micros(void) extern struct timeval sketch_start_time; struct timeval tp; gettimeofday(&tp,NULL); - return 1.0e6*(tp.tv_sec + (tp.tv_usec*1.0e-6)) - - (sketch_start_time.tv_sec + (sketch_start_time.tv_usec*1.0e-6)); + return 1.0e6*((tp.tv_sec + (tp.tv_usec*1.0e-6)) - + (sketch_start_time.tv_sec + (sketch_start_time.tv_usec*1.0e-6))); } void delay(long unsigned msec) From 95475c6221e824c1ff48d0544d0e747424d81a9d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 9 Oct 2011 21:22:10 +1100 Subject: [PATCH 09/15] use nanosleep() instead of usleep() --- libraries/Desktop/support/main.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/libraries/Desktop/support/main.cpp b/libraries/Desktop/support/main.cpp index f8efc34ac7..b45a3e1230 100644 --- a/libraries/Desktop/support/main.cpp +++ b/libraries/Desktop/support/main.cpp @@ -13,8 +13,11 @@ int main(void) gettimeofday(&sketch_start_time, NULL); setup(); while (true) { + struct timespec ts; loop(); - usleep(10); + ts.tv_sec = 0; + ts.tv_nsec = 100; + nanosleep(&ts, NULL); } return 0; } From ab755ab11f0abcde4d59671d21e3d55664c52866 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 9 Oct 2011 22:03:42 +1100 Subject: [PATCH 10/15] use ifdef for DESKTOP_BUILD --- libraries/AP_Common/AP_Common.h | 2 +- libraries/FastSerial/vprintf.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Common/AP_Common.h b/libraries/AP_Common/AP_Common.h index fe0a3c9e99..ce197fa584 100644 --- a/libraries/AP_Common/AP_Common.h +++ b/libraries/AP_Common/AP_Common.h @@ -77,7 +77,7 @@ typedef struct { // has an equivalent effect but avoids the warnings, which otherwise // make finding real issues difficult. // -#if DESKTOP_BUILD +#ifdef DESKTOP_BUILD # undef PROGMEM # define PROGMEM __attribute__(()) #else diff --git a/libraries/FastSerial/vprintf.cpp b/libraries/FastSerial/vprintf.cpp index 5bbcac232c..f49ee8d19d 100644 --- a/libraries/FastSerial/vprintf.cpp +++ b/libraries/FastSerial/vprintf.cpp @@ -54,7 +54,7 @@ extern "C" { #undef PSTR #define PSTR(s) (__extension__({static prog_char __c[] PROGMEM = (s); &__c[0];})) -#if DESKTOP_BUILD +#ifdef DESKTOP_BUILD #define GETBYTE(flag, mask, pnt) ({ \ unsigned char __c; \ __c = ((flag) & (mask)) \ From 689918939538dec7e93ecacef8728efff062f032 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 9 Oct 2011 22:06:03 +1100 Subject: [PATCH 11/15] added a README --- libraries/Desktop/README | 3 +++ 1 file changed, 3 insertions(+) create mode 100644 libraries/Desktop/README diff --git a/libraries/Desktop/README b/libraries/Desktop/README new file mode 100644 index 0000000000..2653fc423b --- /dev/null +++ b/libraries/Desktop/README @@ -0,0 +1,3 @@ +This provides some support files for building APM on normal desktop +systems. This makes it possible to use debugging tools (such as gdb +and valgrind) on the APM code From 85e831680918a04bd1862bbbb6104c8ffd3784b1 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 9 Oct 2011 22:38:14 +1100 Subject: [PATCH 12/15] use memcheck_available_memory() instead of freeRAM() this provides a more accurate view of memory --- ArduCopter/system.pde | 17 +---------------- 1 file changed, 1 insertion(+), 16 deletions(-) diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index 848713b396..e206bb8708 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -75,7 +75,7 @@ static void init_ardupilot() Serial.printf_P(PSTR("\n\nInit " THISFIRMWARE "\n\nFree RAM: %lu\n"), - freeRAM()); + memcheck_available_memory()); // @@ -503,21 +503,6 @@ init_optflow() } #endif -/* This function gets the current value of the heap and stack pointers. -* The stack pointer starts at the top of RAM and grows downwards. The heap pointer -* starts just above the static variables etc. and grows upwards. SP should always -* be larger than HP or you'll be in big trouble! The smaller the gap, the more -* careful you need to be. Julian Gall 6 - Feb - 2009. -*/ -static unsigned long freeRAM() { - uint8_t * heapptr, * stackptr; - stackptr = (uint8_t *)malloc(4); // use stackptr temporarily - heapptr = stackptr; // save value of heap pointer - free(stackptr); // free up the memory again (sets stackptr to 0) - stackptr = (uint8_t *)(SP); // save value of stack pointer - return stackptr - heapptr; -} - static void init_simple_bearing() { From 06ddaa2d813701bd7e1885ae8ce5dcdcf36f79a6 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 9 Oct 2011 22:38:49 +1100 Subject: [PATCH 13/15] don't initialise DataFlash if logging is disabled --- ArduCopter/system.pde | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index e206bb8708..bdbb861447 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -222,7 +222,9 @@ static void init_ardupilot() // Logging: // -------- // DataFlash log initialization +#if LOGGING_ENABLED == ENABLED DataFlash.Init(); +#endif #if CLI_ENABLED == ENABLED // If the switch is in 'menu' mode, run the main menu. From f4184d0b02c6dfc22ae675209f8c77a7109f54b6 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 9 Oct 2011 22:39:23 +1100 Subject: [PATCH 14/15] don't check the slider switch if CLI is disabled this prevents a build error in desktop mode --- ArduCopter/system.pde | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index bdbb861447..bc8d48cad3 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -521,6 +521,7 @@ init_throttle_cruise() } } +#if CLI_ENABLED == ENABLED #if BROKEN_SLIDER == 1 static boolean @@ -549,8 +550,8 @@ check_startup_for_CLI() return (digitalRead(SLIDE_SWITCH_PIN) == 0); } -#endif - +#endif // BROKEN_SLIDER +#endif // CLI_ENABLED /* map from a 8 bit EEPROM baud rate to a real baud rate From 67630d42e79eb513ea769e8dc49433a17b632ba2 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 9 Oct 2011 22:40:00 +1100 Subject: [PATCH 15/15] opticalflow: use the right path for SPI.h --- libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp index b387e9ed91..b320bc03a8 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp @@ -25,7 +25,7 @@ #include "AP_OpticalFlow_ADNS3080.h" #include "WProgram.h" -#include "../SPI/SPI.h" +#include "SPI.h" #define AP_SPI_TIMEOUT 1000