Add bare AVR gateway.
This commit is contained in:
parent
cab5daed10
commit
49411c3dc6
23 changed files with 1968 additions and 1 deletions
|
@ -32,10 +32,17 @@ blr_si7020
|
|||
|
||||
For [Button size node](https://www.openhardware.io/view/299/Button-size-radionode-with-sensors-swarm-extension) board. It's got Si7020 temperature and humidity sensor, and BH1750 lux sensor. (Plus a few more things, like SPI flash and ATSHA204a, which I don't use.)
|
||||
|
||||
gateway_bareavr
|
||||
---------------
|
||||
|
||||
Gateway rewritten so that it doesn't depend on any arduino/platformio stuff. Just uses `avr-gcc`, `avr-libc`, and `make`.
|
||||
|
||||
`ex_bareavr` is a bare `avr-gcc` example with uart, millis and one demo pwm enabled - basically the bits that are usually needed, without using arduino/platformio sugar.
|
||||
|
||||
|
||||
## Sig
|
||||
|
||||
© 2014-9 flabbergast / BSD license
|
||||
© 2014-21 flabbergast / BSD license
|
||||
|
||||
[jeelib]: https://github.com/jcw/jeelib
|
||||
[RFM69]: https://github.com/lowpowerlab/RFM69
|
||||
|
|
502
ex_bareavr/Makefile
Normal file
502
ex_bareavr/Makefile
Normal file
|
@ -0,0 +1,502 @@
|
|||
# ----------------------------------------------------------------------------
|
||||
# Makefile based on WinAVR Makefile Template written by Eric B. Weddington,
|
||||
# J<>rg Wunsch, et al.
|
||||
#
|
||||
#
|
||||
# Adjust F_CPU below to the clock frequency in Mhz of your AVR target
|
||||
#
|
||||
# Adjust the size of the uart receive and transmit ringbuffer in bytes using
|
||||
# defines -DUART_RX_BUFFER_SIZE=128 and -DUART_TX_BUFFER_SIZE=128 in the
|
||||
# CDEF section below
|
||||
#
|
||||
#----------------------------------------------------------------------------
|
||||
# On command line:
|
||||
#
|
||||
# make all = Make software.
|
||||
#
|
||||
# make clean = Clean out built project files.
|
||||
#
|
||||
# make coff = Convert ELF to AVR COFF.
|
||||
#
|
||||
# make extcoff = Convert ELF to AVR Extended COFF.
|
||||
#
|
||||
# make program = Download the hex file to the device, using avrdude.
|
||||
# Please customize the avrdude settings below first!
|
||||
#
|
||||
# make debug = Start either simulavr or avarice as specified for debugging,
|
||||
# with avr-gdb or avr-insight as the front end for debugging.
|
||||
#
|
||||
# make filename.s = Just compile filename.c into the assembler code only.
|
||||
#
|
||||
# make filename.i = Create a preprocessed source file for use in submitting
|
||||
# bug reports to the GCC project.
|
||||
#
|
||||
# To rebuild project do "make clean" then "make all".
|
||||
#----------------------------------------------------------------------------
|
||||
|
||||
|
||||
# MCU name
|
||||
MCU = atmega328p
|
||||
|
||||
# Processor frequency.
|
||||
# This will define a symbol, F_CPU, in all source code files equal to the
|
||||
# processor frequency. You can then use this symbol in your source code to
|
||||
# calculate timings. Do NOT tack on a 'UL' at the end, this will be done
|
||||
# automatically to create a 32-bit value in your source code.
|
||||
F_CPU = 16000000
|
||||
|
||||
# Output format. (can be srec, ihex, binary)
|
||||
FORMAT = ihex
|
||||
|
||||
# Target file name (without extension).
|
||||
TARGET = main
|
||||
|
||||
# List C source files here. (C dependencies are automatically generated.)
|
||||
SRC = $(TARGET).c uart_async.c millis.c pwm_pb1.c
|
||||
|
||||
# List Assembler source files here.
|
||||
# Make them always end in a capital .S. Files ending in a lowercase .s
|
||||
# will not be considered source files but generated files (assembler
|
||||
# output from the compiler), and will be deleted upon "make clean"!
|
||||
# Even though the DOS/Win* filesystem matches both .s and .S the same,
|
||||
# it will preserve the spelling of the filenames, and gcc itself does
|
||||
# care about how the name is spelled on its command-line.
|
||||
ASRC =
|
||||
|
||||
|
||||
# Optimization level, can be [0, 1, 2, 3, s].
|
||||
# 0 = turn off optimization. s = optimize for size.
|
||||
# (Note: 3 is not always the best optimization level. See avr-libc FAQ.)
|
||||
OPT = s
|
||||
|
||||
|
||||
# Debugging format.
|
||||
# Native formats for AVR-GCC's -g are dwarf-2 [default] or stabs.
|
||||
# AVR Studio 4.10 requires dwarf-2.
|
||||
# AVR [Extended] COFF format requires stabs, plus an avr-objcopy run.
|
||||
DEBUG = dwarf-2
|
||||
|
||||
|
||||
# List any extra directories to look for include files here.
|
||||
# Each directory must be seperated by a space.
|
||||
# Use forward slashes for directory separators.
|
||||
# For a directory that has spaces, enclose it in quotes.
|
||||
EXTRAINCDIRS =
|
||||
|
||||
|
||||
# Compiler flag to set the C Standard level.
|
||||
# c89 = "ANSI" C
|
||||
# gnu89 = c89 plus GCC extensions
|
||||
# c99 = ISO C99 standard (not yet fully implemented)
|
||||
# gnu99 = c99 plus GCC extensions
|
||||
CSTANDARD = -std=gnu99
|
||||
|
||||
|
||||
# Place -D or -U options here
|
||||
CDEFS = -DF_CPU=$(F_CPU)UL
|
||||
|
||||
# uncomment and adapt these line if you want different UART library buffer size
|
||||
#CDEFS += -DUART_RX_BUFFER_SIZE=128
|
||||
#CDEFS += -DUART_TX_BUFFER_SIZE=128
|
||||
|
||||
|
||||
# Place -I options here
|
||||
CINCS =
|
||||
|
||||
|
||||
|
||||
#---------------- Compiler Options ----------------
|
||||
# -g*: generate debugging information
|
||||
# -O*: optimization level
|
||||
# -f...: tuning, see GCC manual and avr-libc documentation
|
||||
# -Wall...: warning level
|
||||
# -Wa,...: tell GCC to pass this to the assembler.
|
||||
# -adhlns...: create assembler listing
|
||||
CFLAGS = -g$(DEBUG)
|
||||
CFLAGS += $(CDEFS) $(CINCS)
|
||||
CFLAGS += -O$(OPT)
|
||||
CFLAGS += -funsigned-char -funsigned-bitfields -fpack-struct -fshort-enums
|
||||
CFLAGS += -Wall -Wstrict-prototypes
|
||||
CFLAGS += -Wa,-adhlns=$(<:.c=.lst)
|
||||
CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS))
|
||||
CFLAGS += $(CSTANDARD)
|
||||
|
||||
|
||||
#---------------- Assembler Options ----------------
|
||||
# -Wa,...: tell GCC to pass this to the assembler.
|
||||
# -ahlms: create listing
|
||||
# -gstabs: have the assembler create line number information; note that
|
||||
# for use in COFF files, additional information about filenames
|
||||
# and function names needs to be present in the assembler source
|
||||
# files -- see avr-libc docs [FIXME: not yet described there]
|
||||
ASFLAGS = -Wa,-adhlns=$(<:.S=.lst),-gstabs
|
||||
|
||||
|
||||
# ---------------- Library Options ----------------
|
||||
# Minimalistic printf version
|
||||
PRINTF_LIB_MIN = -Wl,-u,vfprintf -lprintf_min
|
||||
|
||||
# Floating point printf version (requires MATH_LIB = -lm below)
|
||||
PRINTF_LIB_FLOAT = -Wl,-u,vfprintf -lprintf_flt
|
||||
|
||||
# If this is left blank, then it will use the Standard printf version.
|
||||
PRINTF_LIB =
|
||||
#PRINTF_LIB = $(PRINTF_LIB_MIN)
|
||||
#PRINTF_LIB = $(PRINTF_LIB_FLOAT)
|
||||
|
||||
|
||||
# Minimalistic scanf version
|
||||
SCANF_LIB_MIN = -Wl,-u,vfscanf -lscanf_min
|
||||
|
||||
# Floating point + %[ scanf version (requires MATH_LIB = -lm below)
|
||||
SCANF_LIB_FLOAT = -Wl,-u,vfscanf -lscanf_flt
|
||||
|
||||
# If this is left blank, then it will use the Standard scanf version.
|
||||
SCANF_LIB =
|
||||
#SCANF_LIB = $(SCANF_LIB_MIN)
|
||||
#SCANF_LIB = $(SCANF_LIB_FLOAT)
|
||||
|
||||
|
||||
MATH_LIB = -lm
|
||||
|
||||
|
||||
|
||||
#---------------- External Memory Options ----------------
|
||||
|
||||
# 64 KB of external RAM, starting after internal RAM (ATmega128!),
|
||||
# used for variables (.data/.bss) and heap (malloc()).
|
||||
#EXTMEMOPTS = -Wl,-Tdata=0x801100,--defsym=__heap_end=0x80ffff
|
||||
|
||||
# 64 KB of external RAM, starting after internal RAM (ATmega128!),
|
||||
# only used for heap (malloc()).
|
||||
#EXTMEMOPTS = -Wl,--defsym=__heap_start=0x801100,--defsym=__heap_end=0x80ffff
|
||||
|
||||
EXTMEMOPTS =
|
||||
|
||||
|
||||
|
||||
#---------------- Linker Options ----------------
|
||||
# -Wl,...: tell GCC to pass this to linker.
|
||||
# -Map: create map file
|
||||
# --cref: add cross reference to map file
|
||||
LDFLAGS = -Wl,-Map=$(TARGET).map,--cref
|
||||
LDFLAGS += $(EXTMEMOPTS)
|
||||
LDFLAGS += $(PRINTF_LIB) $(SCANF_LIB) $(MATH_LIB)
|
||||
|
||||
|
||||
|
||||
#---------------- Programming Options (avrdude) ----------------
|
||||
|
||||
# Programming hardware: alf avr910 avrisp bascom bsd
|
||||
# dt006 pavr picoweb pony-stk200 sp12 stk200 stk500
|
||||
#
|
||||
# Type: avrdude -c ?
|
||||
# to get a full listing.
|
||||
#
|
||||
AVRDUDE_PROGRAMMER = arduino
|
||||
|
||||
# com1 = serial port. Use lpt1 to connect to parallel port.
|
||||
AVRDUDE_PORT = /dev/ttyUSB* # programmer connected to serial device
|
||||
|
||||
AVRDUDE_WRITE_FLASH = -U flash:w:$(TARGET).hex
|
||||
#AVRDUDE_WRITE_EEPROM = -U eeprom:w:$(TARGET).eep
|
||||
|
||||
|
||||
# Uncomment the following if you want avrdude's erase cycle counter.
|
||||
# Note that this counter needs to be initialized first using -Yn,
|
||||
# see avrdude manual.
|
||||
#AVRDUDE_ERASE_COUNTER = -y
|
||||
|
||||
# Uncomment the following if you do /not/ wish a verification to be
|
||||
# performed after programming the device.
|
||||
#AVRDUDE_NO_VERIFY = -V
|
||||
|
||||
# Increase verbosity level. Please use this when submitting bug
|
||||
# reports about avrdude. See <http://savannah.nongnu.org/projects/avrdude>
|
||||
# to submit bug reports.
|
||||
#AVRDUDE_VERBOSE = -v -v
|
||||
|
||||
AVRDUDE_FLAGS = -p $(MCU) -P $(AVRDUDE_PORT) -c $(AVRDUDE_PROGRAMMER) -b 115200
|
||||
AVRDUDE_FLAGS += $(AVRDUDE_NO_VERIFY)
|
||||
AVRDUDE_FLAGS += $(AVRDUDE_VERBOSE)
|
||||
AVRDUDE_FLAGS += $(AVRDUDE_ERASE_COUNTER)
|
||||
|
||||
|
||||
|
||||
#---------------- Debugging Options ----------------
|
||||
|
||||
# For simulavr only - target MCU frequency.
|
||||
DEBUG_MFREQ = $(F_CPU)
|
||||
|
||||
# Set the DEBUG_UI to either gdb or insight.
|
||||
# DEBUG_UI = gdb
|
||||
DEBUG_UI = insight
|
||||
|
||||
# Set the debugging back-end to either avarice, simulavr.
|
||||
DEBUG_BACKEND = avarice
|
||||
#DEBUG_BACKEND = simulavr
|
||||
|
||||
# GDB Init Filename.
|
||||
GDBINIT_FILE = __avr_gdbinit
|
||||
|
||||
# When using avarice settings for the JTAG
|
||||
JTAG_DEV = /dev/com1
|
||||
|
||||
# Debugging port used to communicate between GDB / avarice / simulavr.
|
||||
DEBUG_PORT = 4242
|
||||
|
||||
# Debugging host used to communicate between GDB / avarice / simulavr, normally
|
||||
# just set to localhost unless doing some sort of crazy debugging when
|
||||
# avarice is running on a different computer.
|
||||
DEBUG_HOST = localhost
|
||||
|
||||
|
||||
|
||||
#============================================================================
|
||||
|
||||
|
||||
# Define programs and commands.
|
||||
SHELL = sh
|
||||
CC = avr-gcc
|
||||
OBJCOPY = avr-objcopy
|
||||
OBJDUMP = avr-objdump
|
||||
SIZE = avr-size
|
||||
NM = avr-nm
|
||||
AVRDUDE = avrdude
|
||||
REMOVE = rm -f
|
||||
COPY = cp
|
||||
WINSHELL = cmd
|
||||
|
||||
|
||||
# Define Messages
|
||||
# English
|
||||
MSG_ERRORS_NONE = Errors: none
|
||||
MSG_BEGIN = -------- begin --------
|
||||
MSG_END = -------- end --------
|
||||
MSG_SIZE_BEFORE = Size before:
|
||||
MSG_SIZE_AFTER = Size after:
|
||||
MSG_COFF = Converting to AVR COFF:
|
||||
MSG_EXTENDED_COFF = Converting to AVR Extended COFF:
|
||||
MSG_FLASH = Creating load file for Flash:
|
||||
MSG_EEPROM = Creating load file for EEPROM:
|
||||
MSG_EXTENDED_LISTING = Creating Extended Listing:
|
||||
MSG_SYMBOL_TABLE = Creating Symbol Table:
|
||||
MSG_LINKING = Linking:
|
||||
MSG_COMPILING = Compiling:
|
||||
MSG_ASSEMBLING = Assembling:
|
||||
MSG_CLEANING = Cleaning project:
|
||||
|
||||
|
||||
|
||||
|
||||
# Define all object files.
|
||||
OBJ = $(SRC:.c=.o) $(ASRC:.S=.o)
|
||||
|
||||
# Define all listing files.
|
||||
LST = $(SRC:.c=.lst) $(ASRC:.S=.lst)
|
||||
|
||||
|
||||
# Compiler flags to generate dependency files.
|
||||
GENDEPFLAGS = -MD -MP -MF .dep/$(@F).d
|
||||
|
||||
|
||||
# Combine all necessary flags and optional flags.
|
||||
# Add target processor to flags.
|
||||
ALL_CFLAGS = -mmcu=$(MCU) -I. $(CFLAGS) $(GENDEPFLAGS)
|
||||
ALL_ASFLAGS = -mmcu=$(MCU) -I. -x assembler-with-cpp $(ASFLAGS)
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
# Default target.
|
||||
all: begin gccversion sizebefore build sizeafter end
|
||||
|
||||
build: elf hex eep lss sym
|
||||
|
||||
elf: $(TARGET).elf
|
||||
hex: $(TARGET).hex
|
||||
eep: $(TARGET).eep
|
||||
lss: $(TARGET).lss
|
||||
sym: $(TARGET).sym
|
||||
|
||||
|
||||
|
||||
# Eye candy.
|
||||
# AVR Studio 3.x does not check make's exit code but relies on
|
||||
# the following magic strings to be generated by the compile job.
|
||||
begin:
|
||||
@echo
|
||||
@echo $(MSG_BEGIN)
|
||||
|
||||
end:
|
||||
@echo $(MSG_END)
|
||||
@echo
|
||||
|
||||
|
||||
# Display size of file.
|
||||
HEXSIZE = $(SIZE) --target=$(FORMAT) $(TARGET).hex
|
||||
ELFSIZE = $(SIZE) -A $(TARGET).elf
|
||||
AVRMEM = avr-mem.sh $(TARGET).elf $(MCU)
|
||||
|
||||
sizebefore:
|
||||
@if test -f $(TARGET).elf; then echo; echo $(MSG_SIZE_BEFORE); $(ELFSIZE); \
|
||||
$(AVRMEM) 2>/dev/null; echo; fi
|
||||
|
||||
sizeafter:
|
||||
@if test -f $(TARGET).elf; then echo; echo $(MSG_SIZE_AFTER); $(ELFSIZE); \
|
||||
$(AVRMEM) 2>/dev/null; echo; fi
|
||||
|
||||
|
||||
|
||||
# Display compiler version information.
|
||||
gccversion :
|
||||
@$(CC) --version
|
||||
|
||||
|
||||
|
||||
# Program the device.
|
||||
program: $(TARGET).hex $(TARGET).eep
|
||||
$(AVRDUDE) $(AVRDUDE_FLAGS) $(AVRDUDE_WRITE_FLASH) $(AVRDUDE_WRITE_EEPROM)
|
||||
|
||||
|
||||
# Generate avr-gdb config/init file which does the following:
|
||||
# define the reset signal, load the target file, connect to target, and set
|
||||
# a breakpoint at main().
|
||||
gdb-config:
|
||||
@$(REMOVE) $(GDBINIT_FILE)
|
||||
@echo define reset >> $(GDBINIT_FILE)
|
||||
@echo SIGNAL SIGHUP >> $(GDBINIT_FILE)
|
||||
@echo end >> $(GDBINIT_FILE)
|
||||
@echo file $(TARGET).elf >> $(GDBINIT_FILE)
|
||||
@echo target remote $(DEBUG_HOST):$(DEBUG_PORT) >> $(GDBINIT_FILE)
|
||||
ifeq ($(DEBUG_BACKEND),simulavr)
|
||||
@echo load >> $(GDBINIT_FILE)
|
||||
endif
|
||||
@echo break main >> $(GDBINIT_FILE)
|
||||
|
||||
debug: gdb-config $(TARGET).elf
|
||||
ifeq ($(DEBUG_BACKEND), avarice)
|
||||
@echo Starting AVaRICE - Press enter when "waiting to connect" message displays.
|
||||
@$(WINSHELL) /c start avarice --jtag $(JTAG_DEV) --erase --program --file \
|
||||
$(TARGET).elf $(DEBUG_HOST):$(DEBUG_PORT)
|
||||
@$(WINSHELL) /c pause
|
||||
|
||||
else
|
||||
@$(WINSHELL) /c start simulavr --gdbserver --device $(MCU) --clock-freq \
|
||||
$(DEBUG_MFREQ) --port $(DEBUG_PORT)
|
||||
endif
|
||||
@$(WINSHELL) /c start avr-$(DEBUG_UI) --command=$(GDBINIT_FILE)
|
||||
|
||||
|
||||
|
||||
|
||||
# Convert ELF to COFF for use in debugging / simulating in AVR Studio or VMLAB.
|
||||
COFFCONVERT=$(OBJCOPY) --debugging \
|
||||
--change-section-address .data-0x800000 \
|
||||
--change-section-address .bss-0x800000 \
|
||||
--change-section-address .noinit-0x800000 \
|
||||
--change-section-address .eeprom-0x810000
|
||||
|
||||
|
||||
coff: $(TARGET).elf
|
||||
@echo
|
||||
@echo $(MSG_COFF) $(TARGET).cof
|
||||
$(COFFCONVERT) -O coff-avr $< $(TARGET).cof
|
||||
|
||||
|
||||
extcoff: $(TARGET).elf
|
||||
@echo
|
||||
@echo $(MSG_EXTENDED_COFF) $(TARGET).cof
|
||||
$(COFFCONVERT) -O coff-ext-avr $< $(TARGET).cof
|
||||
|
||||
|
||||
|
||||
# Create final output files (.hex, .eep) from ELF output file.
|
||||
%.hex: %.elf
|
||||
@echo
|
||||
@echo $(MSG_FLASH) $@
|
||||
$(OBJCOPY) -O $(FORMAT) -R .eeprom $< $@
|
||||
|
||||
%.eep: %.elf
|
||||
@echo
|
||||
@echo $(MSG_EEPROM) $@
|
||||
-$(OBJCOPY) -j .eeprom --set-section-flags=.eeprom="alloc,load" \
|
||||
--change-section-lma .eeprom=0 -O $(FORMAT) $< $@
|
||||
|
||||
# Create extended listing file from ELF output file.
|
||||
%.lss: %.elf
|
||||
@echo
|
||||
@echo $(MSG_EXTENDED_LISTING) $@
|
||||
$(OBJDUMP) -h -S $< > $@
|
||||
|
||||
# Create a symbol table from ELF output file.
|
||||
%.sym: %.elf
|
||||
@echo
|
||||
@echo $(MSG_SYMBOL_TABLE) $@
|
||||
$(NM) -n $< > $@
|
||||
|
||||
|
||||
|
||||
# Link: create ELF output file from object files.
|
||||
.SECONDARY : $(TARGET).elf
|
||||
.PRECIOUS : $(OBJ)
|
||||
%.elf: $(OBJ)
|
||||
@echo
|
||||
@echo $(MSG_LINKING) $@
|
||||
$(CC) $(ALL_CFLAGS) $^ --output $@ $(LDFLAGS)
|
||||
|
||||
|
||||
# Compile: create object files from C source files.
|
||||
%.o : %.c
|
||||
@echo
|
||||
@echo $(MSG_COMPILING) $<
|
||||
$(CC) -c $(ALL_CFLAGS) $< -o $@
|
||||
|
||||
|
||||
# Compile: create assembler files from C source files.
|
||||
%.s : %.c
|
||||
$(CC) -S $(ALL_CFLAGS) $< -o $@
|
||||
|
||||
|
||||
# Assemble: create object files from assembler source files.
|
||||
%.o : %.S
|
||||
@echo
|
||||
@echo $(MSG_ASSEMBLING) $<
|
||||
$(CC) -c $(ALL_ASFLAGS) $< -o $@
|
||||
|
||||
# Create preprocessed source for use in sending a bug report.
|
||||
%.i : %.c
|
||||
$(CC) -E -mmcu=$(MCU) -I. $(CFLAGS) $< -o $@
|
||||
|
||||
|
||||
# Target: clean project.
|
||||
clean: begin clean_list end
|
||||
|
||||
clean_list :
|
||||
@echo
|
||||
@echo $(MSG_CLEANING)
|
||||
$(REMOVE) $(TARGET).hex
|
||||
$(REMOVE) $(TARGET).eep
|
||||
$(REMOVE) $(TARGET).cof
|
||||
$(REMOVE) $(TARGET).elf
|
||||
$(REMOVE) $(TARGET).map
|
||||
$(REMOVE) $(TARGET).sym
|
||||
$(REMOVE) $(TARGET).lss
|
||||
$(REMOVE) $(OBJ)
|
||||
$(REMOVE) $(LST)
|
||||
$(REMOVE) $(SRC:.c=.s)
|
||||
$(REMOVE) $(SRC:.c=.d)
|
||||
$(REMOVE) .dep/*
|
||||
|
||||
|
||||
|
||||
# Include the dependency files.
|
||||
-include $(shell mkdir .dep 2>/dev/null) $(wildcard .dep/*)
|
||||
|
||||
|
||||
# Listing of phony targets.
|
||||
.PHONY : all begin finish end sizebefore sizeafter gccversion \
|
||||
build elf hex eep lss sym coff extcoff \
|
||||
clean clean_list program debug gdb-config
|
||||
|
68
ex_bareavr/main.c
Normal file
68
ex_bareavr/main.c
Normal file
|
@ -0,0 +1,68 @@
|
|||
/*
|
||||
* Basic setup for moving away from arduino:
|
||||
* - millis - uart -
|
||||
*
|
||||
*
|
||||
* Based on example by:
|
||||
* Copyright 2011 Mika Tuupola
|
||||
*
|
||||
* Licensed under the MIT license:
|
||||
* http://www.opensource.org/licenses/mit-license.php
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef F_CPU
|
||||
#define F_CPU 16000000UL
|
||||
#endif
|
||||
|
||||
#include <stdio.h>
|
||||
|
||||
#include <avr/io.h>
|
||||
#include <avr/interrupt.h>
|
||||
#include <util/delay.h>
|
||||
#include <avr/pgmspace.h>
|
||||
|
||||
#include "uart.h"
|
||||
#include "millis.h"
|
||||
#include "pwm_pb1.h"
|
||||
|
||||
int main(void) {
|
||||
|
||||
DDRB |= _BV(PORTB5); // make PB5 = "Arduino pin 13" an output
|
||||
|
||||
uart_init();
|
||||
stdout = &uart_output;
|
||||
stdin = &uart_input;
|
||||
|
||||
millis_init(F_CPU); // frequency the atmega328p is running at
|
||||
|
||||
pwm_pb1_init(1);
|
||||
pwm_pb1_on();
|
||||
|
||||
sei(); // both uart and timer use interrupts
|
||||
|
||||
unsigned long prev_millis;
|
||||
prev_millis = millis();
|
||||
|
||||
int c;
|
||||
|
||||
while (1) {
|
||||
|
||||
if(millis() - prev_millis > 1000) {
|
||||
prev_millis = millis();
|
||||
|
||||
PORTB ^= _BV(PORTB5); // toggle PB5 = "Arduino pin 13"
|
||||
|
||||
puts_P(PSTR("Hello async world!"));
|
||||
}
|
||||
// _delay_ms(500);
|
||||
|
||||
if ((c=uart_getchar(NULL)) != EOF) {
|
||||
putchar(c);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
return 0;
|
||||
|
||||
}
|
1
ex_bareavr/main.h
Normal file
1
ex_bareavr/main.h
Normal file
|
@ -0,0 +1 @@
|
|||
int main(void);
|
58
ex_bareavr/millis.c
Normal file
58
ex_bareavr/millis.c
Normal file
|
@ -0,0 +1,58 @@
|
|||
/*
|
||||
|
||||
This file is GPL2 licensed.
|
||||
|
||||
Original by Monoclecat https://github.com/monoclecat/avr-millis-function/
|
||||
|
||||
The millis() function known from Arduino
|
||||
Calling millis() will return the milliseconds since the program started
|
||||
|
||||
Tested on atmega328p
|
||||
|
||||
Using content from http://www.adnbr.co.uk/articles/counting-milliseconds
|
||||
Author: Monoclecat, https://github.com/monoclecat/avr-millis-function
|
||||
|
||||
REMEMBER: Add sei(); after init_millis() to enable global interrupts!
|
||||
*/
|
||||
|
||||
// This uses TIMER0 A
|
||||
|
||||
#include <avr/io.h>
|
||||
#include <avr/interrupt.h>
|
||||
#include <util/atomic.h>
|
||||
|
||||
#include "millis.h"
|
||||
|
||||
volatile unsigned long timer1_millis;
|
||||
//NOTE: A unsigned long holds values from 0 to 4,294,967,295 (2^32 - 1). It will roll over to 0 after reaching its maximum value.
|
||||
|
||||
ISR(TIMER0_COMPA_vect) {
|
||||
timer1_millis++;
|
||||
}
|
||||
|
||||
void millis_init(unsigned long f_cpu) {
|
||||
uint8_t ctc_match_overflow = ((f_cpu / 1000) / 64); //when timer0 is this value, 1ms has passed
|
||||
|
||||
// (Set timer to clear when matching ctc_match_overflow)
|
||||
TCCR0A |= (1 << WGM01);
|
||||
// (Set clock divisor to 64)
|
||||
TCCR0B |= (1 << CS01) | (1 << CS00);
|
||||
|
||||
// high byte first, then low byte
|
||||
OCR0A = ctc_match_overflow;
|
||||
|
||||
// Enable the compare match interrupt
|
||||
TIMSK0 |= (1 << OCIE0A);
|
||||
|
||||
//REMEMBER TO ENABLE GLOBAL INTERRUPTS AFTER THIS WITH sei(); !!!
|
||||
}
|
||||
|
||||
unsigned long millis (void) {
|
||||
unsigned long millis_return;
|
||||
|
||||
// Ensure this cannot be disrupted
|
||||
ATOMIC_BLOCK(ATOMIC_FORCEON) {
|
||||
millis_return = timer1_millis;
|
||||
}
|
||||
return millis_return;
|
||||
}
|
59
ex_bareavr/millis.c.timer1a
Normal file
59
ex_bareavr/millis.c.timer1a
Normal file
|
@ -0,0 +1,59 @@
|
|||
/*
|
||||
|
||||
This file is GPL2 licensed.
|
||||
|
||||
Original by Monoclecat https://github.com/monoclecat/avr-millis-function/
|
||||
|
||||
The millis() function known from Arduino
|
||||
Calling millis() will return the milliseconds since the program started
|
||||
|
||||
Tested on atmega328p
|
||||
|
||||
Using content from http://www.adnbr.co.uk/articles/counting-milliseconds
|
||||
Author: Monoclecat, https://github.com/monoclecat/avr-millis-function
|
||||
|
||||
REMEMBER: Add sei(); after init_millis() to enable global interrupts!
|
||||
*/
|
||||
|
||||
// This uses TIMER1 A
|
||||
|
||||
#include <avr/io.h>
|
||||
#include <avr/interrupt.h>
|
||||
#include <util/atomic.h>
|
||||
|
||||
#include "millis.h"
|
||||
|
||||
volatile unsigned long timer1_millis;
|
||||
//NOTE: A unsigned long holds values from 0 to 4,294,967,295 (2^32 - 1). It will roll over to 0 after reaching its maximum value.
|
||||
|
||||
ISR(TIMER1_COMPA_vect) {
|
||||
timer1_millis++;
|
||||
}
|
||||
|
||||
void init_millis(unsigned long f_cpu) {
|
||||
unsigned long ctc_match_overflow;
|
||||
|
||||
ctc_match_overflow = ((f_cpu / 1000) / 8); //when timer1 is this value, 1ms has passed
|
||||
|
||||
// (Set timer to clear when matching ctc_match_overflow) | (Set clock divisor to 8)
|
||||
TCCR1B |= (1 << WGM12) | (1 << CS11);
|
||||
|
||||
// high byte first, then low byte
|
||||
OCR1AH = (ctc_match_overflow >> 8);
|
||||
OCR1AL = ctc_match_overflow;
|
||||
|
||||
// Enable the compare match interrupt
|
||||
TIMSK1 |= (1 << OCIE1A);
|
||||
|
||||
//REMEMBER TO ENABLE GLOBAL INTERRUPTS AFTER THIS WITH sei(); !!!
|
||||
}
|
||||
|
||||
unsigned long millis (void) {
|
||||
unsigned long millis_return;
|
||||
|
||||
// Ensure this cannot be disrupted
|
||||
ATOMIC_BLOCK(ATOMIC_FORCEON) {
|
||||
millis_return = timer1_millis;
|
||||
}
|
||||
return millis_return;
|
||||
}
|
16
ex_bareavr/millis.h
Normal file
16
ex_bareavr/millis.h
Normal file
|
@ -0,0 +1,16 @@
|
|||
#ifndef _MILLIS_H_
|
||||
#define _MILLIS_H_
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
void millis_init(unsigned long f_cpu);
|
||||
unsigned long millis(void);
|
||||
|
||||
#ifdef __cplusplus
|
||||
} // extern "C"
|
||||
#endif
|
||||
|
||||
#endif // _MILLIS_H_
|
20
ex_bareavr/pwm_pb1.c
Normal file
20
ex_bareavr/pwm_pb1.c
Normal file
|
@ -0,0 +1,20 @@
|
|||
// PB1 is OC1A, so "A" output from TIMER1
|
||||
// it's a 16 bit timer, but let's only do 8 bit resolution
|
||||
|
||||
#include "pwm_pb1.h"
|
||||
|
||||
void pwm_pb1_init(uint8_t ovf) {
|
||||
DDRB |= (1 << PORTB1); // PB1 is output
|
||||
TCCR1A |= (1 << COM1A1); // noninverted mode for OC1A output
|
||||
TCCR1A |= (1 << WGM10);
|
||||
TCCR1B |= (1 << WGM12); // 8bit Fast PWM mode (TOP=0xFF)
|
||||
OCR1A = ovf; // cutoff for ON count, out of TOP
|
||||
}
|
||||
|
||||
void pwm_pb1_on(void) {
|
||||
TCCR1B |= (1 << CS11); // prescale / 8 and ... GO
|
||||
}
|
||||
|
||||
void pwm_pb1_off(void) {
|
||||
TCCR1B &= ~(0b111); // clear CS bits (timer1 off)
|
||||
}
|
10
ex_bareavr/pwm_pb1.h
Normal file
10
ex_bareavr/pwm_pb1.h
Normal file
|
@ -0,0 +1,10 @@
|
|||
#ifndef _PWM_PB1_H_
|
||||
#define _PWM_PB1_H_
|
||||
|
||||
#include <avr/io.h>
|
||||
|
||||
void pwm_pb1_init(uint8_t ovf);
|
||||
void pwm_pb1_on(void);
|
||||
void pwm_pb1_off(void);
|
||||
|
||||
#endif // _PWM_PB1_H_
|
25
ex_bareavr/uart.h
Normal file
25
ex_bareavr/uart.h
Normal file
|
@ -0,0 +1,25 @@
|
|||
#ifndef _UART_H_
|
||||
#define _UART_H_
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
int uart_putchar(char c, FILE *stream);
|
||||
int uart_getchar(FILE *stream);
|
||||
|
||||
void uart_init(void);
|
||||
|
||||
struct rx_ring;
|
||||
struct tx_ring;
|
||||
|
||||
/* http://www.ermicro.com/blog/?p=325 */
|
||||
|
||||
extern FILE uart_fp;
|
||||
|
||||
#ifdef __cplusplus
|
||||
} // extern "C"
|
||||
#endif
|
||||
|
||||
#endif // _UART_H_
|
117
ex_bareavr/uart_async.c
Normal file
117
ex_bareavr/uart_async.c
Normal file
|
@ -0,0 +1,117 @@
|
|||
/* Based on Atmel Application Note AVR 306 */
|
||||
|
||||
#include <avr/io.h>
|
||||
#include <avr/interrupt.h>
|
||||
#include <stdio.h>
|
||||
|
||||
#include "uart.h"
|
||||
|
||||
#ifndef BAUD
|
||||
#define BAUD 115200
|
||||
#endif
|
||||
#include <util/setbaud.h>
|
||||
|
||||
#ifndef UART_RX_BUFFER_SIZE
|
||||
#define UART_RX_BUFFER_SIZE 32
|
||||
#endif
|
||||
|
||||
#ifndef UART_TX_BUFFER_SIZE
|
||||
#define UART_TX_BUFFER_SIZE 64
|
||||
#endif
|
||||
|
||||
struct tx_ring {
|
||||
uint8_t buffer[UART_TX_BUFFER_SIZE];
|
||||
int start;
|
||||
int end;
|
||||
};
|
||||
|
||||
struct rx_ring {
|
||||
uint8_t buffer[UART_RX_BUFFER_SIZE];
|
||||
int start;
|
||||
int end;
|
||||
};
|
||||
|
||||
static struct tx_ring tx_buffer;
|
||||
static struct rx_ring rx_buffer;
|
||||
|
||||
FILE uart_output = FDEV_SETUP_STREAM(uart_putchar, NULL, _FDEV_SETUP_WRITE);
|
||||
FILE uart_input = FDEV_SETUP_STREAM(NULL, uart_getchar, _FDEV_SETUP_READ);
|
||||
|
||||
|
||||
/* http://www.cs.mun.ca/~rod/Winter2007/4723/notes/serial/serial.html */
|
||||
|
||||
void uart_init(void) {
|
||||
|
||||
tx_buffer.start = 0;
|
||||
tx_buffer.end = 1;
|
||||
|
||||
rx_buffer.start = 0;
|
||||
rx_buffer.end = 1;
|
||||
|
||||
UBRR0H = UBRRH_VALUE;
|
||||
UBRR0L = UBRRL_VALUE;
|
||||
|
||||
#if USE_2X
|
||||
UCSR0A |= (1 << U2X0);
|
||||
#else
|
||||
UCSR0A &= ~(1 << U2X0);
|
||||
#endif
|
||||
|
||||
UCSR0C = _BV(UCSZ01) | _BV(UCSZ00); // 8-bit data
|
||||
UCSR0B = _BV(RXEN0) | _BV(TXEN0) | _BV(RXCIE0); // Enable RX and TX, RX interrupts
|
||||
}
|
||||
|
||||
int uart_putchar(char c, FILE *stream) {
|
||||
if (c == '\n') {
|
||||
uart_putchar('\r', stream);
|
||||
}
|
||||
|
||||
int write_pointer = (tx_buffer.end + 1) % UART_TX_BUFFER_SIZE;
|
||||
|
||||
if (write_pointer != tx_buffer.start){
|
||||
tx_buffer.buffer[tx_buffer.end] = (uint8_t)c;
|
||||
tx_buffer.end = write_pointer;
|
||||
|
||||
/* Data available. Enable the transmit interrupt for serial port 0. */
|
||||
UCSR0B |= _BV(UDRIE0);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int uart_getchar(FILE *stream) {
|
||||
int read_pointer = (rx_buffer.start + 1) % UART_RX_BUFFER_SIZE;
|
||||
|
||||
if(read_pointer != rx_buffer.end) {
|
||||
rx_buffer.start = read_pointer;
|
||||
return rx_buffer.buffer[read_pointer];
|
||||
} else {
|
||||
return EOF;
|
||||
}
|
||||
}
|
||||
|
||||
ISR(USART_RX_vect) {
|
||||
int write_pointer = (rx_buffer.end + 1) % UART_RX_BUFFER_SIZE;
|
||||
|
||||
rx_buffer.buffer[rx_buffer.end] = UDR0; // this clears RX interrupt flag
|
||||
rx_buffer.end = write_pointer;
|
||||
if (write_pointer == rx_buffer.start){ // there is no space left
|
||||
// we are overwriting old data
|
||||
rx_buffer.start = (rx_buffer.start + 1) % UART_RX_BUFFER_SIZE;
|
||||
}
|
||||
}
|
||||
|
||||
ISR(USART_UDRE_vect){
|
||||
int read_pointer = (tx_buffer.start + 1) % UART_TX_BUFFER_SIZE;
|
||||
|
||||
/* Transmit next byte if data available in ringbuffer. */
|
||||
if (read_pointer != tx_buffer.end) {
|
||||
UDR0 = tx_buffer.buffer[read_pointer];
|
||||
tx_buffer.start = read_pointer;
|
||||
} else {
|
||||
/* Nothing to send. Disable the transmit interrupt for serial port 0. */
|
||||
UCSR0B &= ~_BV(UDRIE0);
|
||||
}
|
||||
}
|
||||
|
||||
|
141
gateway_bareavr/Makefile
Normal file
141
gateway_bareavr/Makefile
Normal file
|
@ -0,0 +1,141 @@
|
|||
# Makefile for AVR C++ projects
|
||||
# From: https://gist.github.com/rynr/72734da4b8c7b962aa65
|
||||
|
||||
# ----- Update the settings of your project here -----
|
||||
|
||||
# Hardware
|
||||
MCU = atmega328p
|
||||
F_CPU = 16000000UL
|
||||
PROJECT = gateway
|
||||
|
||||
# ----- These configurations are quite likely not to be changed -----
|
||||
|
||||
# Binaries
|
||||
GCC = avr-gcc
|
||||
G++ = avr-g++
|
||||
OBJCOPY = avr-objcopy
|
||||
SIZE = avr-size
|
||||
RM = rm -f
|
||||
AVRDUDE = avrdude
|
||||
AVRDUDE_PROGRAMMER = arduino
|
||||
AVRDUDE_PORT = /dev/ttyUSB*
|
||||
AVRDUDE_BAUD = 115200
|
||||
AVRDUDE_WRITE_FLASH = -U flash:w:$(PROJECT).hex
|
||||
#AVRDUDE_WRITE_EEPROM = -U eeprom:w:$(PROJECT).eep
|
||||
|
||||
# Files
|
||||
EXT_C = c
|
||||
EXT_C++ = cpp
|
||||
EXT_ASM = asm
|
||||
|
||||
# ---------------- Library Options ----------------
|
||||
# Minimalistic printf version
|
||||
PRINTF_LIB_MIN = -Wl,-u,vfprintf -lprintf_min
|
||||
# Floating point printf version (requires MATH_LIB = -lm below)
|
||||
PRINTF_LIB_FLOAT = -Wl,-u,vfprintf -lprintf_flt
|
||||
# If this is left blank, then it will use the Standard printf version.
|
||||
#PRINTF_LIB =
|
||||
PRINTF_LIB = $(PRINTF_LIB_MIN)
|
||||
#PRINTF_LIB = $(PRINTF_LIB_FLOAT)
|
||||
|
||||
# Minimalistic scanf version
|
||||
SCANF_LIB_MIN = -Wl,-u,vfscanf -lscanf_min
|
||||
# Floating point + %[ scanf version (requires MATH_LIB = -lm below)
|
||||
SCANF_LIB_FLOAT = -Wl,-u,vfscanf -lscanf_flt
|
||||
# If this is left blank, then it will use the Standard scanf version.
|
||||
#SCANF_LIB =
|
||||
SCANF_LIB = $(SCANF_LIB_MIN)
|
||||
#SCANF_LIB = $(SCANF_LIB_FLOAT)
|
||||
|
||||
MATH_LIB = -lm
|
||||
|
||||
# ----- No changes should be necessary below this line -----
|
||||
|
||||
OBJECTS = \
|
||||
$(patsubst %.$(EXT_C),%.o,$(wildcard *.$(EXT_C))) \
|
||||
$(patsubst %.$(EXT_C++),%.o,$(wildcard *.$(EXT_C++))) \
|
||||
$(patsubst %.$(EXT_ASM),%.o,$(wildcard *.$(EXT_ASM)))
|
||||
|
||||
CFLAGS = $(INC)
|
||||
CFLAGS += -Os
|
||||
CFLAGS += -funsigned-char -funsigned-bitfields -fpack-struct -fshort-enums
|
||||
CFLAGS += -Wall -Wstrict-prototypes
|
||||
CFLAGS += -std=gnu99
|
||||
CFLAGS += -DF_CPU=$(F_CPU)
|
||||
CFLAGS += -mmcu=$(MCU)
|
||||
|
||||
C++FLAGS = $(INC)
|
||||
C++FLAGS += -Os
|
||||
C++FLAGS += -funsigned-char -funsigned-bitfields -fpack-struct -fshort-enums
|
||||
C++FLAGS += -Wall
|
||||
C++FLAGS += -std=gnu++17
|
||||
C++FLAGS += -DF_CPU=$(F_CPU)
|
||||
C++FLAGS += -mmcu=$(MCU)
|
||||
|
||||
ASMFLAGS = $(INC)
|
||||
ASMFLAGS += -Os
|
||||
ASMFLAGS += -funsigned-char -funsigned-bitfields -fpack-struct -fshort-enums
|
||||
ASMFLAGS += -Wall -Wstrict-prototypes
|
||||
ASMFLAGS += -DF_CPU=$(F_CPU)
|
||||
ASMFLAGS += -x assembler-with-cpp
|
||||
ASMFLAGS += -mmcu=$(MCU)
|
||||
|
||||
LDFLAGS += $(PRINTF_LIB) $(SCANF_LIB) $(MATH_LIB)
|
||||
|
||||
AVRDUDE_PARAMS = -p $(MCU) -P $(AVRDUDE_PORT) -c $(AVRDUDE_PROGRAMMER) -b $(AVRDUDE_BAUD)
|
||||
|
||||
default: $(PROJECT).hex
|
||||
echo $(OBJECTS)
|
||||
|
||||
%.hex: %.elf
|
||||
$(OBJCOPY) -O ihex -R .eeprom $< $@
|
||||
|
||||
%.elf: $(OBJECTS)
|
||||
$(GCC) $(CFLAGS) $(OBJECTS) --output $@ $(LDFLAGS)
|
||||
|
||||
%.o : %.$(EXT_C)
|
||||
$(GCC) $< $(CFLAGS) -c -o $@
|
||||
|
||||
%.o : %.$(EXT_C++)
|
||||
$(G++) $< $(C++FLAGS) -c -o $@
|
||||
|
||||
%.o : %.$(EXT_ASM)
|
||||
$(G++) $< $(ASMFLAGS) -c -o $@
|
||||
|
||||
clean:
|
||||
$(RM) $(PROJECT).elf $(PROJECT).hex $(OBJECTS)
|
||||
|
||||
flash: $(PROJECT).hex
|
||||
$(AVRDUDE) $(AVRDUDE_EXTRAFLAGS) $(AVRDUDE_PARAMS) $(AVRDUDE_WRITE_FLASH) $(AVRDUDE_WRITE_EEPROM)
|
||||
|
||||
size: $(PROJECT).elf
|
||||
$(SIZE) $(PROJECT).elf
|
||||
|
||||
help:
|
||||
@echo "usage:"
|
||||
@echo " make <target>"
|
||||
@echo ""
|
||||
@echo "targets:"
|
||||
@echo " clean Remove any non-source files"
|
||||
@echo " flash Attempt to upload firmware to the chip"
|
||||
@echo " size Show firmware size"
|
||||
@echo " config Shows the current configuration"
|
||||
@echo " help Shows this help"
|
||||
|
||||
config:
|
||||
@echo "configuration:"
|
||||
@echo ""
|
||||
@echo "Binaries for:"
|
||||
@echo " C compiler: $(GCC)"
|
||||
@echo " C++ compiler: $(G++)"
|
||||
@echo " Programmer: $(AVRDUDE)"
|
||||
@echo " remove file: $(RM)"
|
||||
@echo ""
|
||||
@echo "Hardware settings:"
|
||||
@echo " MCU: $(MCU)"
|
||||
@echo " F_CPU: $(F_CPU)"
|
||||
@echo ""
|
||||
@echo "Defaults:"
|
||||
@echo " C-files: *.$(EXT_C)"
|
||||
@echo " C++-files: *.$(EXT_C++)"
|
||||
@echo " ASM-files: *.$(EXT_ASM)"
|
281
gateway_bareavr/gateway.cpp
Normal file
281
gateway_bareavr/gateway.cpp
Normal file
|
@ -0,0 +1,281 @@
|
|||
// Gateway sketch
|
||||
// (c) 2014-19 flabbergast
|
||||
// Based on:
|
||||
// Sample RFM69 receiver/gateway sketch, with ACK and optional encryption
|
||||
// Passes through any wireless received messages to the serial port (no ACKs for now)
|
||||
// Sends periodic packets every few minutes (seems to help the radio not to get "stuck")
|
||||
//
|
||||
// Seems that I have problems with high power atm (HW radio doesn't send anything if
|
||||
// high power activated.)
|
||||
//
|
||||
// Originally used https://github.com/LowPowerLab/ libraries, now changed
|
||||
// to use jcw's 'new' (aka 'native RFM69') code:
|
||||
// https://github.com/jeelabs/embello/tree/master/lib/test-arduino
|
||||
//
|
||||
// This should be compatible with Jeenode Zero.
|
||||
//
|
||||
// (uart uses code by Mika Tuupola, 2011 https://github.com/tuupola/avr_demo )
|
||||
// (millis uses code by Monoclecat https://github.com/monoclecat/avr-millis-function/ )
|
||||
//
|
||||
// (it's really all plain C, but rf69 driver is C++, so to avoid headaches, mark this as cpp)
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
/**************************************
|
||||
***** Parameters - read through! *****
|
||||
**************************************/
|
||||
|
||||
#define GW_VERSION "0.6"
|
||||
|
||||
// #define HIGH_POWER // the one on pocketb has HW
|
||||
#define TICKS_DELAY 120000 // send packets with millis every few minutes (comment to disable)
|
||||
volatile uint8_t node_id = 63; //unique for each node on same network
|
||||
// 63 is the 'receive all' node in the Jee protocol
|
||||
volatile uint8_t network_id = 109; //the same on all nodes that talk to each other
|
||||
#define FREQUENCY 8683 // autoscaled to 1-1000
|
||||
#define ENCRYPTKEY "echolocatingbat3" //exactly the same 16 characters/bytes on all nodes!
|
||||
volatile uint8_t encrypted = 1;
|
||||
|
||||
// serial BAUD rate is defined either in Makefile or in uart_async.c
|
||||
|
||||
// these are the pins on my pocketbeagle RFM69 cape (there is also 'error led' on arduino pin 6)
|
||||
// ready LED, arduino pin 9, PB1
|
||||
//#define READY_LED_ON PORTB |= _BV(PORTB1)
|
||||
//#define READY_LED_OFF PORTB &= ~_BV(PORTB1)
|
||||
//#define READY_LED_INIT DDRB |= _BV(PORTB1)
|
||||
// PB1 has PWM on it, namely OC1A, so let's use PWM
|
||||
#define READY_LED_ON pwm_pb1_on()
|
||||
#define READY_LED_OFF pwm_pb1_off()
|
||||
#define READY_LED_INIT pwm_pb1_init(1)
|
||||
// RX LED, arduino pin 8, PB0
|
||||
#define RX_LED_ON PORTB |= _BV(PORTB0)
|
||||
#define RX_LED_OFF PORTB &= ~_BV(PORTB0)
|
||||
#define RX_LED_INIT DDRB |= _BV(PORTB0)
|
||||
// TX LED, arduino pin 7, PD7
|
||||
#define TX_LED_ON PORTD |= _BV(PORTD7)
|
||||
#define TX_LED_OFF PORTD &= ~_BV(PORTD7)
|
||||
#define TX_LED_INIT DDRD |= _BV(PORTD7)
|
||||
#define BLINK_DELAY _delay_ms(50)
|
||||
|
||||
#ifndef F_CPU
|
||||
#define F_CPU 16000000UL
|
||||
#endif
|
||||
|
||||
|
||||
/**************************************
|
||||
***** Includes *****
|
||||
**************************************/
|
||||
|
||||
#include <stdio.h>
|
||||
|
||||
#include <avr/io.h>
|
||||
#include <avr/interrupt.h>
|
||||
#include <util/delay.h>
|
||||
#include <avr/pgmspace.h>
|
||||
|
||||
#include "uart.h"
|
||||
#include "millis.h"
|
||||
|
||||
#include "rf69.h"
|
||||
#include "spi.h"
|
||||
#include "pwm_pb1.h"
|
||||
|
||||
/************************
|
||||
***** Main program *****
|
||||
************************/
|
||||
|
||||
RF69<SpiDev> rf;
|
||||
|
||||
#define MAX_LEN 120
|
||||
uint8_t buffer[MAX_LEN];
|
||||
uint8_t buf_pos = 0;
|
||||
uint8_t buf_end = 0;
|
||||
int input;
|
||||
|
||||
#define TXBUFLEN 62
|
||||
#define RXBUFLEN 64
|
||||
uint8_t rxBuf[RXBUFLEN];
|
||||
uint8_t txBuf[TXBUFLEN];
|
||||
uint8_t txpos;
|
||||
|
||||
#if defined(TICKS_DELAY)
|
||||
unsigned long ticks_lasttime = 0, now = 0;
|
||||
uint8_t tickbuf[(sizeof(unsigned long)) + 1];
|
||||
#endif
|
||||
|
||||
|
||||
int main(void) {
|
||||
|
||||
uart_init();
|
||||
stdout = &uart_fp;
|
||||
stdin = &uart_fp;
|
||||
stderr = &uart_fp;
|
||||
|
||||
millis_init(F_CPU); // frequency the atmega328p is running at
|
||||
|
||||
sei(); // both uart and timer use interrupts
|
||||
|
||||
printf_P(PSTR("RFM69 gateway starting..."));
|
||||
|
||||
rf.init(node_id, network_id, FREQUENCY);
|
||||
if (encrypted) {
|
||||
rf.encrypt(ENCRYPTKEY);
|
||||
}
|
||||
// rf.txPower(31); // this is max on RFM69CW, and default
|
||||
#if defined(HIGH_POWER)
|
||||
printf_P(PSTR("(high power)..."));
|
||||
rf.setHighPower(1);
|
||||
#endif
|
||||
READY_LED_INIT;
|
||||
READY_LED_OFF;
|
||||
RX_LED_INIT;
|
||||
RX_LED_OFF;
|
||||
TX_LED_INIT;
|
||||
TX_LED_OFF;
|
||||
puts_P(PSTR("done."));
|
||||
READY_LED_ON;
|
||||
|
||||
// main loop
|
||||
while (1) {
|
||||
|
||||
//process any serial input
|
||||
if ((input = uart_getchar(NULL)) != EOF) {
|
||||
switch (input) {
|
||||
case 'i':
|
||||
puts_P(PSTR("Jee/new gateway v" GW_VERSION));
|
||||
printf_P(PSTR("NodeID:%d NetworkID:%d "), node_id, network_id);
|
||||
puts_P(encrypted ? PSTR("Encrypted") : PSTR("NotEncrypted"));
|
||||
puts_P(PSTR("Compiled: " __DATE__ ", " __TIME__ ", avr-gcc " __VERSION__));
|
||||
break;
|
||||
case 'y':
|
||||
if (encrypted) {
|
||||
encrypted = 0;
|
||||
rf.encrypt(NULL);
|
||||
puts_P(PSTR("Encryption: NO"));
|
||||
} else {
|
||||
encrypted = 1;
|
||||
rf.encrypt(ENCRYPTKEY);
|
||||
puts_P(PSTR("Encryption: YES"));
|
||||
}
|
||||
break;
|
||||
case 'h':
|
||||
puts_P(PSTR("Help: [i]nfo [h]elp toggle_encr[y]pt"));
|
||||
puts_P(PSTR(" NNN,...,NNN,RRRs : send bytes NNN,...,NNN to RRR"));
|
||||
// puts_P(PSTR(" NNN,...,NNN,RRRa : send bytes NNN,...,NNN to RRR, requesting ACK"));
|
||||
// puts_P(PSTR(" NNNn : change node ID to NNN; NNNg : change network ID to NNN"));
|
||||
break;
|
||||
case '0':
|
||||
case '1':
|
||||
case '2':
|
||||
case '3':
|
||||
case '4':
|
||||
case '5':
|
||||
case '6':
|
||||
case '7':
|
||||
case '8':
|
||||
case '9':
|
||||
case ',':
|
||||
if (buf_pos < MAX_LEN) {
|
||||
printf_P(PSTR("%c"),input);
|
||||
buffer[buf_pos++] = input;
|
||||
}
|
||||
break;
|
||||
case 's': // send buffer
|
||||
// case 'a': // send buffer with ack
|
||||
// case 'n': // node id
|
||||
// case 'g': // group
|
||||
// process serial buffer
|
||||
txpos = 0;
|
||||
buf_end = buf_pos;
|
||||
buf_pos = 0;
|
||||
for (uint8_t i = 0; i < TXBUFLEN; i++)
|
||||
txBuf[i] = 0;
|
||||
printf_P(PSTR("%c\n"),input);
|
||||
while (buf_pos < buf_end) {
|
||||
if (buffer[buf_pos] >= '0' && buffer[buf_pos] <= '9') {
|
||||
txBuf[txpos] = txBuf[txpos] * 10 + (buffer[buf_pos] - '0');
|
||||
} else if (buffer[buf_pos] == ',') {
|
||||
txpos++;
|
||||
} else {
|
||||
break;
|
||||
}
|
||||
buf_pos++;
|
||||
}
|
||||
if ((input == 's' || input == 'a') && buf_pos == buf_end) { // got a message to send
|
||||
printf_P(PSTR("Sending "));
|
||||
for (uint8_t i = 0; i < txpos; i++) {
|
||||
printf_P(PSTR("%d "),txBuf[i]);
|
||||
}
|
||||
printf_P(PSTR("to %d"), txBuf[txpos]);
|
||||
if (input == 'a') {
|
||||
puts_P(PSTR(" with ACK request"));
|
||||
} else {
|
||||
putchar('\n');
|
||||
}
|
||||
rf.send(txBuf[txpos], (const void * ) txBuf, txpos);
|
||||
// {
|
||||
// puts_P(PSTR(" ... OK!"));
|
||||
// } else {
|
||||
// puts_P(PSTR(" ... not_OK!"));
|
||||
// }
|
||||
TX_LED_ON;
|
||||
BLINK_DELAY;
|
||||
TX_LED_OFF;
|
||||
}
|
||||
//if (txpos == 0 && buf_pos == buf_end) { // processed the whole buffer and it's just one byte
|
||||
// if(input=='n') { // change node id
|
||||
// radio.setAddress(message[0]);
|
||||
// node_id = message[0];
|
||||
// printf_P(PSTR("New node ID: %d\n", node_id));
|
||||
// } else if (input=='g') { // change group id
|
||||
// radio.setNetwork(message[0]);
|
||||
// network_id = message[0];
|
||||
// printf_P(PSTR("New network ID: %d\n"), network_id);
|
||||
// }
|
||||
//}
|
||||
buf_pos = 0;
|
||||
break;
|
||||
default:
|
||||
putchar('\n');
|
||||
buf_pos = 0;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
int len = rf.receive(rxBuf, sizeof rxBuf);
|
||||
if (len >= 0) {
|
||||
rf.standby();
|
||||
printf_P(PSTR("OK %d "), rxBuf[1]);
|
||||
for(uint8_t i = 2; i < len; i++) {
|
||||
printf_P(PSTR("%d "), rxBuf[i]);
|
||||
}
|
||||
printf_P(PSTR(" (RX_RSSI:-%ddB) (TO:%d) (timestamp:%ld)"),
|
||||
rf.rssi/2, rxBuf[0] & 0x3F, millis());
|
||||
// if (radio.ACKRequested()) {
|
||||
// uint8_t theNodeID = radio.SENDERID;
|
||||
// radio.sendACK();
|
||||
// printf_P(PSTR(" (ACK_sent)"));
|
||||
// }
|
||||
putchar('\n');
|
||||
RX_LED_ON;
|
||||
BLINK_DELAY;
|
||||
RX_LED_OFF;
|
||||
}
|
||||
|
||||
#if defined(TICKS_DELAY) // send a tick if needed
|
||||
now = millis();
|
||||
if (((now - ticks_lasttime) >= TICKS_DELAY) || (now < ticks_lasttime)) {
|
||||
ticks_lasttime = now;
|
||||
tickbuf[0] = 0x8; // "packet type"
|
||||
*(unsigned long * )(tickbuf + 1) = now;
|
||||
rf.send(0, (const void * ) tickbuf, (sizeof(unsigned long)) + 1);
|
||||
// puts_P(PSTR("Tick sent."));
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
}
|
||||
|
||||
return 0;
|
||||
|
||||
}
|
58
gateway_bareavr/millis.c
Normal file
58
gateway_bareavr/millis.c
Normal file
|
@ -0,0 +1,58 @@
|
|||
/*
|
||||
|
||||
This file is GPL2 licensed.
|
||||
|
||||
Original by Monoclecat https://github.com/monoclecat/avr-millis-function/
|
||||
|
||||
The millis() function known from Arduino
|
||||
Calling millis() will return the milliseconds since the program started
|
||||
|
||||
Tested on atmega328p
|
||||
|
||||
Using content from http://www.adnbr.co.uk/articles/counting-milliseconds
|
||||
Author: Monoclecat, https://github.com/monoclecat/avr-millis-function
|
||||
|
||||
REMEMBER: Add sei(); after init_millis() to enable global interrupts!
|
||||
*/
|
||||
|
||||
// This uses TIMER0 A
|
||||
|
||||
#include <avr/io.h>
|
||||
#include <avr/interrupt.h>
|
||||
#include <util/atomic.h>
|
||||
|
||||
#include "millis.h"
|
||||
|
||||
volatile unsigned long timer1_millis;
|
||||
//NOTE: A unsigned long holds values from 0 to 4,294,967,295 (2^32 - 1). It will roll over to 0 after reaching its maximum value.
|
||||
|
||||
ISR(TIMER0_COMPA_vect) {
|
||||
timer1_millis++;
|
||||
}
|
||||
|
||||
void millis_init(unsigned long f_cpu) {
|
||||
uint8_t ctc_match_overflow = ((f_cpu / 1000) / 64); //when timer0 is this value, 1ms has passed
|
||||
|
||||
// (Set timer to clear when matching ctc_match_overflow)
|
||||
TCCR0A |= (1 << WGM01);
|
||||
// (Set clock divisor to 64)
|
||||
TCCR0B |= (1 << CS01) | (1 << CS00);
|
||||
|
||||
// high byte first, then low byte
|
||||
OCR0A = ctc_match_overflow;
|
||||
|
||||
// Enable the compare match interrupt
|
||||
TIMSK0 |= (1 << OCIE0A);
|
||||
|
||||
//REMEMBER TO ENABLE GLOBAL INTERRUPTS AFTER THIS WITH sei(); !!!
|
||||
}
|
||||
|
||||
unsigned long millis (void) {
|
||||
unsigned long millis_return;
|
||||
|
||||
// Ensure this cannot be disrupted
|
||||
ATOMIC_BLOCK(ATOMIC_FORCEON) {
|
||||
millis_return = timer1_millis;
|
||||
}
|
||||
return millis_return;
|
||||
}
|
16
gateway_bareavr/millis.h
Normal file
16
gateway_bareavr/millis.h
Normal file
|
@ -0,0 +1,16 @@
|
|||
#ifndef _MILLIS_H_
|
||||
#define _MILLIS_H_
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
void millis_init(unsigned long f_cpu);
|
||||
unsigned long millis(void);
|
||||
|
||||
#ifdef __cplusplus
|
||||
} // extern "C"
|
||||
#endif
|
||||
|
||||
#endif // _MILLIS_H_
|
20
gateway_bareavr/pwm_pb1.c
Normal file
20
gateway_bareavr/pwm_pb1.c
Normal file
|
@ -0,0 +1,20 @@
|
|||
// PB1 is OC1A, so "A" output from TIMER1
|
||||
// it's a 16 bit timer, but let's only do 8 bit resolution
|
||||
|
||||
#include "pwm_pb1.h"
|
||||
|
||||
void pwm_pb1_init(uint8_t ovf) {
|
||||
DDRB |= (1 << PORTB1); // PB1 is output
|
||||
TCCR1A |= (1 << COM1A1); // noninverted mode for OC1A output
|
||||
TCCR1A |= (1 << WGM10);
|
||||
TCCR1B |= (1 << WGM12); // 8bit Fast PWM mode (TOP=0xFF)
|
||||
OCR1A = ovf; // cutoff for ON count, out of TOP
|
||||
}
|
||||
|
||||
void pwm_pb1_on(void) {
|
||||
TCCR1B |= (1 << CS11); // prescale / 8 and ... GO
|
||||
}
|
||||
|
||||
void pwm_pb1_off(void) {
|
||||
TCCR1B &= ~(0b111); // clear CS bits (timer1 off)
|
||||
}
|
19
gateway_bareavr/pwm_pb1.h
Normal file
19
gateway_bareavr/pwm_pb1.h
Normal file
|
@ -0,0 +1,19 @@
|
|||
#ifndef _PWM_PB1_H_
|
||||
#define _PWM_PB1_H_
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
#include <avr/io.h>
|
||||
|
||||
void pwm_pb1_init(uint8_t ovf);
|
||||
void pwm_pb1_on(void);
|
||||
void pwm_pb1_off(void);
|
||||
|
||||
#ifdef __cplusplus
|
||||
} // extern "C"
|
||||
#endif
|
||||
|
||||
#endif // _PWM_PB1_H_
|
237
gateway_bareavr/rf69.cpp
Normal file
237
gateway_bareavr/rf69.cpp
Normal file
|
@ -0,0 +1,237 @@
|
|||
// Native mode RF69 driver.
|
||||
|
||||
// driver implementation
|
||||
|
||||
#include "rf69.h"
|
||||
|
||||
template< typename SPI >
|
||||
void RF69<SPI>::setMode (uint8_t newMode) {
|
||||
mode = newMode;
|
||||
if (isRFM69HW) {
|
||||
if ( newMode == MODE_TRANSMIT ) {
|
||||
setHighPowerRegs(1);
|
||||
} else {
|
||||
setHighPowerRegs(0);
|
||||
}
|
||||
}
|
||||
writeReg(REG_OPMODE, (readReg(REG_OPMODE) & 0xE3) | newMode);
|
||||
while ((readReg(REG_IRQFLAGS1) & IRQ1_MODEREADY) == 0)
|
||||
;
|
||||
}
|
||||
|
||||
template< typename SPI >
|
||||
void RF69<SPI>::setFrequency (uint32_t hz) {
|
||||
// accept any frequency scale as input, including KHz and MHz
|
||||
// multiply by 10 until freq >= 100 MHz (don't specify 0 as input!)
|
||||
while (hz < 100000000)
|
||||
hz *= 10;
|
||||
|
||||
// Frequency steps are in units of (32,000,000 >> 19) = 61.03515625 Hz
|
||||
// use multiples of 64 to avoid multi-precision arithmetic, i.e. 3906.25 Hz
|
||||
// due to this, the lower 6 bits of the calculated factor will always be 0
|
||||
// this is still 4 ppm, i.e. well below the radio's 32 MHz crystal accuracy
|
||||
// 868.0 MHz = 0xD90000, 868.3 MHz = 0xD91300, 915.0 MHz = 0xE4C000
|
||||
uint32_t frf = (hz << 2) / (32000000L >> 11);
|
||||
writeReg(REG_FRFMSB, frf >> 10);
|
||||
writeReg(REG_FRFMSB+1, frf >> 2);
|
||||
writeReg(REG_FRFMSB+2, frf << 6);
|
||||
}
|
||||
|
||||
template< typename SPI >
|
||||
void RF69<SPI>::configure (const uint8_t* p) {
|
||||
while (true) {
|
||||
uint8_t cmd = p[0];
|
||||
if (cmd == 0)
|
||||
break;
|
||||
writeReg(cmd, p[1]);
|
||||
p += 2;
|
||||
}
|
||||
}
|
||||
|
||||
static const uint8_t configRegs [] = {
|
||||
// POR value is better for first rf_sleep 0x01, 0x00, // OpMode = sleep
|
||||
0x02, 0x00, // DataModul = packet mode, fsk
|
||||
0x03, 0x02, // BitRateMsb, data rate = 49,261 khz
|
||||
0x04, 0x8A, // BitRateLsb, divider = 32 MHz / 650
|
||||
0x05, 0x02, // FdevMsb = 45 KHz
|
||||
0x06, 0xE1, // FdevLsb = 45 KHz
|
||||
0x0B, 0x20, // Low M
|
||||
0x19, 0x4A, // RxBw 100 KHz
|
||||
0x1A, 0x42, // AfcBw 125 KHz
|
||||
0x1E, 0x0C, // AfcAutoclearOn, AfcAutoOn
|
||||
//0x25, 0x40, //0x80, // DioMapping1 = SyncAddress (Rx)
|
||||
0x26, 0x07, // disable clkout
|
||||
0x29, 0xA0, // RssiThresh -80 dB
|
||||
// 0x2B, 0x40, // RSSI timeout after 128 bytes
|
||||
0x2D, 0x05, // PreambleSize = 5
|
||||
0x2E, 0x90, // SyncConfig = sync on, sync size = 3
|
||||
0x2F, 0xAA, // SyncValue1 = 0xAA
|
||||
0x30, 0x2D, // SyncValue2 = 0x2D ! this is used for group in old jee protocol, but jz4 uses 0x2d hardcoded
|
||||
0x31, 0x2A, // network group, default 42
|
||||
0x37, 0xD0, // PacketConfig1 = fixed, white, no filtering
|
||||
0x38, 0x42, // PayloadLength = 0, unlimited
|
||||
0x3C, 0x8F, // FifoTresh, not empty, level 15
|
||||
0x3D, 0x12, // 0x10, // PacketConfig2, interpkt = 1, autorxrestart off
|
||||
0x6F, 0x20, // TestDagc ...
|
||||
0x71, 0x02, // RegTestAfc
|
||||
0
|
||||
};
|
||||
|
||||
template< typename SPI >
|
||||
void RF69<SPI>::init (uint8_t id, uint8_t group, int freq) {
|
||||
myId = id;
|
||||
|
||||
// b7 = group b7^b5^b3^b1, b6 = group b6^b4^b2^b0
|
||||
parity = group ^ (group << 4);
|
||||
parity = (parity ^ (parity << 2)) & 0xC0;
|
||||
|
||||
// 10 MHz, i.e. 30 MHz / 3 (or 4 MHz if clock is still at 12 MHz)
|
||||
spi.master(3);
|
||||
do
|
||||
writeReg(REG_SYNCVALUE1, 0xAA);
|
||||
while (readReg(REG_SYNCVALUE1) != 0xAA);
|
||||
do
|
||||
writeReg(REG_SYNCVALUE1, 0x55);
|
||||
while (readReg(REG_SYNCVALUE1) != 0x55);
|
||||
|
||||
configure(configRegs);
|
||||
configure(configRegs); // TODO why is this needed ???
|
||||
setFrequency(freq);
|
||||
|
||||
writeReg(REG_SYNCVALUE3, group);
|
||||
isRFM69HW = 0;
|
||||
}
|
||||
|
||||
template< typename SPI >
|
||||
void RF69<SPI>::encrypt (const char* key) {
|
||||
uint8_t cfg = readReg(REG_PKTCONFIG2) & ~0x01;
|
||||
if (key) {
|
||||
for (int i = 0; i < 16; ++i) {
|
||||
writeReg(REG_AESKEYMSB + i, *key);
|
||||
if (*key != 0)
|
||||
++key;
|
||||
}
|
||||
cfg |= 0x01;
|
||||
}
|
||||
writeReg(REG_PKTCONFIG2, cfg);
|
||||
}
|
||||
|
||||
template< typename SPI >
|
||||
void RF69<SPI>::txPower (uint8_t level) {
|
||||
writeReg(REG_PALEVEL, (readReg(REG_PALEVEL) & ~0x1F) | level);
|
||||
}
|
||||
|
||||
template< typename SPI >
|
||||
void RF69<SPI>::setHighPower (uint8_t onOff) { // must call this with RFM69HW!
|
||||
isRFM69HW = onOff;
|
||||
writeReg(REG_OCP, isRFM69HW ? 0x0F : 0x1A);
|
||||
if (isRFM69HW) // turning ON
|
||||
writeReg(REG_PALEVEL, (readReg(REG_PALEVEL) & 0x1F) | 0x40 | 0x20); // enable P1 & P2 amplifier stages
|
||||
else
|
||||
writeReg(REG_PALEVEL, (readReg(REG_PALEVEL) & 0x1F) | 0x80 ); // enable P0 only
|
||||
}
|
||||
|
||||
template< typename SPI >
|
||||
void RF69<SPI>::setHighPowerRegs (uint8_t onOff) {
|
||||
writeReg(REG_TESTPA1, onOff ? 0x5D : 0x55);
|
||||
writeReg(REG_TESTPA2, onOff ? 0x7C : 0x70);
|
||||
}
|
||||
|
||||
template< typename SPI >
|
||||
void RF69<SPI>::sleep () {
|
||||
setMode(MODE_SLEEP);
|
||||
}
|
||||
|
||||
template< typename SPI >
|
||||
void RF69<SPI>::standby () {
|
||||
setMode(MODE_STANDBY);
|
||||
}
|
||||
|
||||
template< typename SPI >
|
||||
int RF69<SPI>::receive (void* ptr, int len) {
|
||||
if (mode != MODE_RECEIVE)
|
||||
setMode(MODE_RECEIVE);
|
||||
else {
|
||||
static uint8_t lastFlag;
|
||||
if ((readReg(REG_IRQFLAGS1) & IRQ1_RXREADY) != lastFlag) {
|
||||
lastFlag ^= IRQ1_RXREADY;
|
||||
if (lastFlag) { // flag just went from 0 to 1
|
||||
rssi = readReg(REG_RSSIVALUE);
|
||||
lna = (readReg(REG_LNAVALUE) >> 3) & 0x7;
|
||||
#if RF69_SPI_BULK
|
||||
spi.enable();
|
||||
spi.transfer(REG_AFCMSB);
|
||||
afc = spi.transfer(0) << 8;
|
||||
afc |= spi.transfer(0);
|
||||
spi.disable();
|
||||
#else
|
||||
afc = readReg(REG_AFCMSB) << 8;
|
||||
afc |= readReg(REG_AFCLSB);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
if (readReg(REG_IRQFLAGS2) & IRQ2_PAYLOADREADY) {
|
||||
|
||||
#if RF69_SPI_BULK
|
||||
spi.enable();
|
||||
spi.transfer(REG_FIFO);
|
||||
int count = spi.transfer(0);
|
||||
for (int i = 0; i < count; ++i) {
|
||||
uint8_t v = spi.transfer(0);
|
||||
if (i < len)
|
||||
((uint8_t*) ptr)[i] = v;
|
||||
}
|
||||
spi.disable();
|
||||
#else
|
||||
int count = readReg(REG_FIFO);
|
||||
for (int i = 0; i < count; ++i) {
|
||||
uint8_t v = readReg(REG_FIFO);
|
||||
if (i < len)
|
||||
((uint8_t*) ptr)[i] = v;
|
||||
}
|
||||
#endif
|
||||
|
||||
// only accept packets intended for us, or broadcasts
|
||||
// ... or any packet if we're the special catch-all node
|
||||
uint8_t dest = *(uint8_t*) ptr;
|
||||
if ((dest & 0xC0) == parity) {
|
||||
uint8_t destId = dest & 0x3F;
|
||||
if (destId == myId || destId == 0 || myId == 63)
|
||||
return count;
|
||||
}
|
||||
}
|
||||
}
|
||||
return -1;
|
||||
}
|
||||
|
||||
template< typename SPI >
|
||||
void RF69<SPI>::send (uint8_t header, const void* ptr, int len) {
|
||||
setMode(MODE_STANDBY);
|
||||
|
||||
#if RF69_SPI_BULK
|
||||
spi.enable();
|
||||
spi.transfer(REG_FIFO | 0x80);
|
||||
spi.transfer(len + 2);
|
||||
spi.transfer((header & 0x3F) | parity);
|
||||
spi.transfer((header & 0xC0) | myId);
|
||||
for (int i = 0; i < len; ++i)
|
||||
spi.transfer(((const uint8_t*) ptr)[i]);
|
||||
spi.disable();
|
||||
#else
|
||||
writeReg(REG_FIFO, len + 2);
|
||||
writeReg(REG_FIFO, (header & 0x3F) | parity);
|
||||
writeReg(REG_FIFO, (header & 0xC0) | myId);
|
||||
for (int i = 0; i < len; ++i)
|
||||
writeReg(REG_FIFO, ((const uint8_t*) ptr)[i]);
|
||||
#endif
|
||||
|
||||
setMode(MODE_TRANSMIT);
|
||||
while ((readReg(REG_IRQFLAGS2) & IRQ2_PACKETSENT) == 0)
|
||||
; // BUSY WAIT
|
||||
|
||||
setMode(MODE_STANDBY);
|
||||
}
|
||||
|
||||
// instantiate class
|
||||
template class RF69<SpiDev>;
|
90
gateway_bareavr/rf69.h
Normal file
90
gateway_bareavr/rf69.h
Normal file
|
@ -0,0 +1,90 @@
|
|||
// Native mode RF69 driver.
|
||||
|
||||
#ifndef _RF69_H_
|
||||
#define _RF69_H_
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include "spi.h"
|
||||
|
||||
template< typename SPI >
|
||||
class RF69 {
|
||||
public:
|
||||
void init (uint8_t id, uint8_t group, int freq);
|
||||
void encrypt (const char* key);
|
||||
void txPower (uint8_t level);
|
||||
void setHighPower (uint8_t onOff);
|
||||
|
||||
int receive (void* ptr, int len);
|
||||
void send (uint8_t header, const void* ptr, int len);
|
||||
void sleep ();
|
||||
void standby ();
|
||||
|
||||
int16_t afc;
|
||||
uint8_t rssi;
|
||||
uint8_t lna;
|
||||
uint8_t myId;
|
||||
uint8_t parity;
|
||||
|
||||
uint8_t readReg (uint8_t addr) {
|
||||
return spi.rwReg(addr, 0);
|
||||
}
|
||||
void writeReg (uint8_t addr, uint8_t val) {
|
||||
spi.rwReg(addr | 0x80, val);
|
||||
}
|
||||
|
||||
protected:
|
||||
enum {
|
||||
REG_FIFO = 0x00,
|
||||
REG_OPMODE = 0x01,
|
||||
REG_FRFMSB = 0x07,
|
||||
REG_PALEVEL = 0x11,
|
||||
REG_OCP = 0x13,
|
||||
REG_LNAVALUE = 0x18,
|
||||
REG_AFCMSB = 0x1F,
|
||||
REG_AFCLSB = 0x20,
|
||||
REG_FEIMSB = 0x21,
|
||||
REG_FEILSB = 0x22,
|
||||
REG_RSSIVALUE = 0x24,
|
||||
REG_IRQFLAGS1 = 0x27,
|
||||
REG_IRQFLAGS2 = 0x28,
|
||||
REG_SYNCVALUE1 = 0x2F,
|
||||
REG_SYNCVALUE2 = 0x30,
|
||||
REG_SYNCVALUE3 = 0x31,
|
||||
REG_NODEADDR = 0x39,
|
||||
REG_BCASTADDR = 0x3A,
|
||||
REG_FIFOTHRESH = 0x3C,
|
||||
REG_PKTCONFIG2 = 0x3D,
|
||||
REG_AESKEYMSB = 0x3E,
|
||||
REG_TESTPA1 = 0x5A, // only present on RFM69HW/SX1231H
|
||||
REG_TESTPA2 = 0x5C, // only present on RFM69HW/SX1231H
|
||||
|
||||
MODE_SLEEP = 0<<2,
|
||||
MODE_STANDBY = 1<<2,
|
||||
MODE_TRANSMIT = 3<<2,
|
||||
MODE_RECEIVE = 4<<2,
|
||||
|
||||
START_TX = 0xC2,
|
||||
STOP_TX = 0x42,
|
||||
|
||||
RCCALSTART = 0x80,
|
||||
IRQ1_MODEREADY = 1<<7,
|
||||
IRQ1_RXREADY = 1<<6,
|
||||
IRQ1_SYNADDRMATCH = 1<<0,
|
||||
|
||||
IRQ2_FIFONOTEMPTY = 1<<6,
|
||||
IRQ2_PACKETSENT = 1<<3,
|
||||
IRQ2_PAYLOADREADY = 1<<2,
|
||||
};
|
||||
|
||||
void setMode (uint8_t newMode);
|
||||
void configure (const uint8_t* p);
|
||||
void setFrequency (uint32_t freq);
|
||||
void setHighPowerRegs (uint8_t onOff);
|
||||
|
||||
SPI spi;
|
||||
volatile uint8_t mode;
|
||||
uint8_t isRFM69HW;
|
||||
};
|
||||
|
||||
#endif // _RF69_H_
|
64
gateway_bareavr/spi.cpp
Normal file
64
gateway_bareavr/spi.cpp
Normal file
|
@ -0,0 +1,64 @@
|
|||
// SPI setup for ATmega (JeeNode) and ATtiny (JeeNode Micro)
|
||||
// ATtiny thx to @woelfs, see http://jeelabs.net/boards/11/topics/6493
|
||||
|
||||
#include "spi.h"
|
||||
|
||||
#ifdef SPCR
|
||||
// ATmega CS=PB2
|
||||
#define CS_HIGH PORTB |= _BV(PORTB2)
|
||||
#define CS_LOW PORTB &= ~_BV(PORTB2)
|
||||
#define CS_INIT DDRB |= _BV(PORTB2)
|
||||
#else
|
||||
// ATtiny CS=PB1
|
||||
#define CS_HIGH PORTB |= _BV(PORTB1)
|
||||
#define CS_LOW PORTB &= ~_BV(PORTB1)
|
||||
#define CS_INIT DDRB |= _BV(PORTB1)
|
||||
#endif
|
||||
|
||||
uint8_t SpiDev::spiTransferByte (uint8_t out) {
|
||||
#ifdef SPCR
|
||||
SPDR = out;
|
||||
while ((SPSR & (1<<SPIF)) == 0)
|
||||
;
|
||||
return SPDR;
|
||||
#else
|
||||
// ATtiny
|
||||
USIDR = out;
|
||||
byte v1 = bit(USIWM0) | bit(USITC);
|
||||
byte v2 = bit(USIWM0) | bit(USITC) | bit(USICLK);
|
||||
for (uint8_t i = 0; i < 8; ++i) {
|
||||
USICR = v1;
|
||||
USICR = v2;
|
||||
}
|
||||
return USIDR;
|
||||
#endif
|
||||
}
|
||||
|
||||
void SpiDev::master (int div) {
|
||||
|
||||
CS_HIGH;
|
||||
CS_INIT;
|
||||
|
||||
#ifdef SPCR
|
||||
// ATmega
|
||||
DDRB |= _BV(PORTB3)|_BV(PORTB5); // SCK PB5, MOSI PB3
|
||||
DDRB &= ~_BV(PORTB4); // MISO PB4
|
||||
|
||||
SPCR = _BV(SPE) | _BV(MSTR);
|
||||
SPSR |= _BV(SPI2X);
|
||||
#else
|
||||
// ATtiny
|
||||
DDRA |= _BV(PORTA4)|_BV(PORTA6); // SCK PA4, MOSI PA6
|
||||
DDRA &= ~_BV(PORTA5); // MISO PA5
|
||||
|
||||
USICR = bit(USIWM0);
|
||||
#endif
|
||||
}
|
||||
|
||||
uint8_t SpiDev::rwReg (uint8_t cmd, uint8_t val) {
|
||||
CS_LOW;
|
||||
spiTransferByte(cmd);
|
||||
uint8_t in = spiTransferByte(val);
|
||||
CS_HIGH;
|
||||
return in;
|
||||
}
|
16
gateway_bareavr/spi.h
Normal file
16
gateway_bareavr/spi.h
Normal file
|
@ -0,0 +1,16 @@
|
|||
#ifndef _SPI_H_
|
||||
#define _SPI_H_
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include <avr/io.h>
|
||||
|
||||
class SpiDev {
|
||||
private:
|
||||
static uint8_t spiTransferByte (uint8_t out);
|
||||
public:
|
||||
void master (int div);
|
||||
uint8_t rwReg (uint8_t cmd, uint8_t val);
|
||||
};
|
||||
|
||||
#endif // _SPI_H_
|
25
gateway_bareavr/uart.h
Normal file
25
gateway_bareavr/uart.h
Normal file
|
@ -0,0 +1,25 @@
|
|||
#ifndef _UART_H_
|
||||
#define _UART_H_
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
int uart_putchar(char c, FILE *stream);
|
||||
int uart_getchar(FILE *stream);
|
||||
|
||||
void uart_init(void);
|
||||
|
||||
struct rx_ring;
|
||||
struct tx_ring;
|
||||
|
||||
/* http://www.ermicro.com/blog/?p=325 */
|
||||
|
||||
extern FILE uart_fp;
|
||||
|
||||
#ifdef __cplusplus
|
||||
} // extern "C"
|
||||
#endif
|
||||
|
||||
#endif // _UART_H_
|
117
gateway_bareavr/uart_async.c
Normal file
117
gateway_bareavr/uart_async.c
Normal file
|
@ -0,0 +1,117 @@
|
|||
/* Based on Atmel Application Note AVR 306 */
|
||||
|
||||
#include <avr/io.h>
|
||||
#include <avr/interrupt.h>
|
||||
#include <stdio.h>
|
||||
|
||||
#include "uart.h"
|
||||
|
||||
#ifndef BAUD
|
||||
#define BAUD 115200
|
||||
#endif
|
||||
#include <util/setbaud.h>
|
||||
|
||||
#ifndef UART_RX_BUFFER_SIZE
|
||||
#define UART_RX_BUFFER_SIZE 32
|
||||
#endif
|
||||
|
||||
#ifndef UART_TX_BUFFER_SIZE
|
||||
#define UART_TX_BUFFER_SIZE 128
|
||||
#endif
|
||||
|
||||
struct tx_ring {
|
||||
uint8_t buffer[UART_TX_BUFFER_SIZE];
|
||||
int start;
|
||||
int end;
|
||||
};
|
||||
|
||||
struct rx_ring {
|
||||
uint8_t buffer[UART_RX_BUFFER_SIZE];
|
||||
int start;
|
||||
int end;
|
||||
};
|
||||
|
||||
static struct tx_ring tx_buffer;
|
||||
static struct rx_ring rx_buffer;
|
||||
|
||||
FILE uart_fp;
|
||||
|
||||
/* http://www.cs.mun.ca/~rod/Winter2007/4723/notes/serial/serial.html */
|
||||
|
||||
void uart_init(void) {
|
||||
|
||||
tx_buffer.start = 0;
|
||||
tx_buffer.end = 1;
|
||||
|
||||
rx_buffer.start = 0;
|
||||
rx_buffer.end = 1;
|
||||
|
||||
UBRR0H = UBRRH_VALUE;
|
||||
UBRR0L = UBRRL_VALUE;
|
||||
|
||||
#if USE_2X
|
||||
UCSR0A |= (1 << U2X0);
|
||||
#else
|
||||
UCSR0A &= ~(1 << U2X0);
|
||||
#endif
|
||||
|
||||
UCSR0C = _BV(UCSZ01) | _BV(UCSZ00); // 8-bit data
|
||||
UCSR0B = _BV(RXEN0) | _BV(TXEN0) | _BV(RXCIE0); // Enable RX and TX, RX interrupts
|
||||
|
||||
fdev_setup_stream(&uart_fp, uart_putchar, uart_getchar, _FDEV_SETUP_RW);
|
||||
}
|
||||
|
||||
int uart_putchar(char c, FILE *stream) {
|
||||
if (c == '\n') {
|
||||
uart_putchar('\r', stream);
|
||||
}
|
||||
|
||||
int write_pointer = (tx_buffer.end + 1) % UART_TX_BUFFER_SIZE;
|
||||
|
||||
if (write_pointer != tx_buffer.start){
|
||||
tx_buffer.buffer[tx_buffer.end] = (uint8_t)c;
|
||||
tx_buffer.end = write_pointer;
|
||||
|
||||
/* Data available. Enable the transmit interrupt for serial port 0. */
|
||||
UCSR0B |= _BV(UDRIE0);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int uart_getchar(FILE *stream) {
|
||||
int read_pointer = (rx_buffer.start + 1) % UART_RX_BUFFER_SIZE;
|
||||
|
||||
if(read_pointer != rx_buffer.end) {
|
||||
rx_buffer.start = read_pointer;
|
||||
return rx_buffer.buffer[read_pointer];
|
||||
} else {
|
||||
return EOF;
|
||||
}
|
||||
}
|
||||
|
||||
ISR(USART_RX_vect) {
|
||||
int write_pointer = (rx_buffer.end + 1) % UART_RX_BUFFER_SIZE;
|
||||
|
||||
rx_buffer.buffer[rx_buffer.end] = UDR0; // this clears RX interrupt flag
|
||||
rx_buffer.end = write_pointer;
|
||||
if (write_pointer == rx_buffer.start){ // there is no space left
|
||||
// we are overwriting old data
|
||||
rx_buffer.start = (rx_buffer.start + 1) % UART_RX_BUFFER_SIZE;
|
||||
}
|
||||
}
|
||||
|
||||
ISR(USART_UDRE_vect){
|
||||
int read_pointer = (tx_buffer.start + 1) % UART_TX_BUFFER_SIZE;
|
||||
|
||||
/* Transmit next byte if data available in ringbuffer. */
|
||||
if (read_pointer != tx_buffer.end) {
|
||||
UDR0 = tx_buffer.buffer[read_pointer];
|
||||
tx_buffer.start = read_pointer;
|
||||
} else {
|
||||
/* Nothing to send. Disable the transmit interrupt for serial port 0. */
|
||||
UCSR0B &= ~_BV(UDRIE0);
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in a new issue