This commit is contained in:
Michael Oborne 2011-10-09 21:53:58 +08:00
commit 42fc10c455
34 changed files with 4506 additions and 22 deletions

View File

@ -75,7 +75,7 @@ static void init_ardupilot()
Serial.printf_P(PSTR("\n\nInit " THISFIRMWARE
"\n\nFree RAM: %lu\n"),
freeRAM());
memcheck_available_memory());
//
@ -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.
@ -503,21 +505,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()
{
@ -534,6 +521,7 @@ init_throttle_cruise()
}
}
#if CLI_ENABLED == ENABLED
#if BROKEN_SLIDER == 1
static boolean
@ -562,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

View File

@ -77,8 +77,14 @@ typedef struct {
// has an equivalent effect but avoids the warnings, which otherwise
// make finding real issues difficult.
//
#ifdef 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];}))

View File

@ -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=<path>)
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 <Foo.h>
#
# 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
#
# <newline><type>[<qualifier>...]<name>([<arguments>]){
#
# 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

View File

@ -25,7 +25,7 @@
#include "AP_OpticalFlow_ADNS3080.h"
#include "WProgram.h"
#include "../SPI/SPI.h"
#include "SPI.h"
#define AP_SPI_TIMEOUT 1000

3
libraries/Desktop/README Normal file
View File

@ -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

View File

@ -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 <inttypes.h>
#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

View File

@ -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 <inttypes.h>
#include <stdio.h> // 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

View File

@ -0,0 +1,70 @@
/*
* Copyright (c) 2010 by Cristian Maglie <c.maglie@bug.st>
* 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 <stdio.h>
#include <WProgram.h>
#include <avr/pgmspace.h>
#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

View File

@ -0,0 +1,16 @@
#ifndef Stream_h
#define Stream_h
#include <inttypes.h>
#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

View File

@ -0,0 +1 @@
#include "wiring.h"

View File

@ -0,0 +1,29 @@
#ifndef WProgram_h
#define WProgram_h
#include "wiring.h"
#include <stdarg.h>
#include "HardwareSerial.h"
#ifdef __cplusplus
extern "C" {
#endif
#include <stdlib.h>
#include <string.h>
#include <math.h>
#include <unistd.h>
#include <stdint.h>
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

View File

@ -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 <stdlib.h>
#include <string.h>
#include <ctype.h>
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

View File

@ -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 <inttypes.h>
#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

View File

@ -0,0 +1,24 @@
#ifndef _AVR_EEPROM_H_
#define _AVR_EEPROM_H_
#ifdef __cplusplus
extern "C" {
#endif
#include <stdint.h>
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

View File

@ -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

View File

@ -0,0 +1,21 @@
#ifndef _AVR_IO_H_
#define _AVR_IO_H_
#include <stdint.h>
#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

View File

@ -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 <avr/iomxx0_1.h>
/* 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_ */

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,49 @@
#ifndef _PGMSPACE_H
#define _PGMSPACE_H
#include <stdarg.h>
#include <unistd.h>
#include <inttypes.h>
#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

View File

View File

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

View File

@ -0,0 +1,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 <avr/pgmspace.h>
#define NOT_A_PIN 0
#define NOT_A_PORT 0
#define NOT_ON_TIMER 0
#define TIMER0A 1
#define TIMER0B 2
#define TIMER1A 3
#define TIMER1B 4
#define TIMER2 5
#define TIMER2A 6
#define TIMER2B 7
#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

View File

@ -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 <avr/io.h>
#include <stdlib.h>
#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

View File

@ -0,0 +1,124 @@
#include "WProgram.h"
#include <unistd.h>
#include <stdio.h>
#include <string.h>
#include <bsd/string.h>
#include "avr/pgmspace.h"
#include <BetterStream.h>
#include <sys/time.h>
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;
}

View File

@ -0,0 +1,146 @@
// -*- 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 <unistd.h>
#include <pty.h>
#include <fcntl.h>
#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(portNumber),
_portEnableBits(portEnableBits),
_portTxBits(portTxBits),
_rxBuffer(&__FastSerial__rxBuffer[portNumber]),
_txBuffer(&__FastSerial__txBuffer[portNumber])
{
}
// Public Methods //////////////////////////////////////////////////////////////
void FastSerial::begin(long baud)
{
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)
{
begin(baud);
}
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;
}
int FastSerial::txspace(void)
{
return 128;
}
int FastSerial::read(void)
{
if (_u2x != 0) {
return -1;
}
char c;
if (fread(&c, 1, 1, stdin) != 1) {
return -1;
}
return (int)c;
}
int FastSerial::peek(void)
{
return -1;
}
void FastSerial::flush(void)
{
}
void FastSerial::write(uint8_t c)
{
if (_u2x != 0) {
return;
}
fwrite(&c, 1, 1, stdout);
fflush(stdout);
}
// Buffer management ///////////////////////////////////////////////////////////
bool FastSerial::_allocBuffer(Buffer *buffer, unsigned int size)
{
return false;
}
void FastSerial::_freeBuffer(Buffer *buffer)
{
}

View File

@ -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 <stdlib.h>
#include <stdio.h>
#include <string.h>
#include <math.h>
#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<digits; ++i)
rounding /= 10.0;
number += rounding;
// Extract the integer part of the number and print it
unsigned long int_part = (unsigned long)number;
double remainder = number - (double)int_part;
print(int_part);
// Print the decimal point, but only if there are digits beyond
if (digits > 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;
}
}

View File

@ -0,0 +1,61 @@
/*
* Copyright (c) 2010 by Cristian Maglie <c.maglie@bug.st>
* 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);
}

View File

@ -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 <stdlib.h>
#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);
}

View File

@ -0,0 +1,87 @@
#include <unistd.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include <assert.h>
#include <stdint.h>
static int eeprom_fd;
static void eeprom_open(void)
{
if (eeprom_fd == 0) {
eeprom_fd = open("eeprom.bin", O_RDWR|O_CREAT, 0777);
ftruncate(eeprom_fd, 4096);
}
}
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);
}

View File

@ -0,0 +1,7 @@
#include <stdio.h>
int __ftoa_engine(double val, char *buf,
unsigned char prec, unsigned char maxdgs)
{
return sprintf(buf, "%*.*lf", prec, maxdgs, val);
}

View File

@ -0,0 +1,23 @@
#include <stdio.h>
#include <unistd.h>
#include <time.h>
#include <sys/time.h>
void setup(void);
void loop(void);
struct timeval sketch_start_time;
int main(void)
{
gettimeofday(&sketch_start_time, NULL);
setup();
while (true) {
struct timespec ts;
loop();
ts.tv_sec = 0;
ts.tv_nsec = 100;
nanosleep(&ts, NULL);
}
return 0;
}

View File

@ -0,0 +1,12 @@
#include <stdio.h>
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);
}

View File

@ -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)) \

View File

@ -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
}