1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-01-18 03:52:11 +01:00

PipX modem full source code moved into public SVN.

git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@2394 ebee16cc-31ac-478f-84a7-5cbb03baadba
This commit is contained in:
pip 2011-01-13 08:45:18 +00:00 committed by pip
parent cf71281bf4
commit df45cb7be8
23 changed files with 7208 additions and 131 deletions

View File

@ -1,8 +1,8 @@
##### #####
# Project: OpenPilot PipBee Modems # Project: OpenPilot Pip Modems
# #
# #
# Makefile for OpenPilot PipBee project # Makefile for OpenPilot Pip Modem project
# #
# The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2009. # The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2009.
# #
@ -23,12 +23,13 @@
##### #####
# Set developer code and compile options # Debugging (YES/NO) ?
# Set to YES for debugging DEBUG ?= NO
DEBUG ?= YES
# Is this code a bootloader (YES/NO) ?
USE_BOOTLOADER ?= NO USE_BOOTLOADER ?= NO
# Set to YES when using Code Sourcery toolchain # Use Code Sourcery toolchain (YES/NO) ?
CODE_SOURCERY ?= YES CODE_SOURCERY ?= YES
# Toolchain prefix (i.e arm-elf- -> arm-elf-gcc.exe) # Toolchain prefix (i.e arm-elf- -> arm-elf-gcc.exe)
@ -40,55 +41,88 @@ else
REMOVE_CMD = rm REMOVE_CMD = rm
endif endif
FLASH_TOOL = OPENOCD FLASH_TOOL = OPENOCD
# YES enables -mthumb option to flags for source-files listed
# in SRC and CPPSRC # YES enables -mthumb option to flags for source-files listed in SRC and CPPSRC
USE_THUMB_MODE = YES USE_THUMB_MODE = YES
# Include the USB files (YES/NO) ?
USE_USB = YES
# MCU name, submodel and board # MCU name, submodel and board
# - MCU used for compiler-option (-mcpu) # - MCU used for compiler-option (-mcpu)
# - MODEL used for linker-script name (-T) and passed as define # - MODEL used for linker-script name (-T) and passed as define
# - BOARD just passed as define (optional) # - BOARD just passed as define (optional)
MCU = cortex-m3 MCU = cortex-m3
CHIP = STM32F103CBT CHIP = STM32F103CBT
BOARD = STM32103CB_PIPBEE BOARD = STM32103CB_PIPXTREME
#CHIP = STM32F103C8T
#BOARD = STM32103C8_PIPXTREME
MODEL = MD
ifeq ($(USE_BOOTLOADER), YES) ifeq ($(USE_BOOTLOADER), YES)
MODEL = MD BOOT_MODEL = $(MODEL)_BL
else else
MODEL = MD BOOT_MODEL = $(MODEL)_NB
endif endif
# Directory for output files (lst, obj, dep, elf, sym, map, hex, bin etc.) # Directory for output files (lst, obj, dep, elf, sym, map, hex, bin etc.)
OUTDIR = Build OUTDIR = Build
# Target file name (without extension). # Target file name (without extension).
TARGET = PipBee TARGET = PipXtreme
# Paths # Paths
PIPBEE = ./ HOME_DIR = ./
PIPBEEINC = $(PIPBEE)/inc HOME_DIR_INC = $(HOME_DIR)/inc
PIOS = ../PiOS PIOS = ../PiOS
PIOSINC = $(PIOS)/inc PIOSINC = $(PIOS)/inc
FLIGHTLIB = ../Libraries FLIGHTLIB = ../Libraries
FLIGHTLIBINC = ../Libraries/inc FLIGHTLIBINC = $(FLIGHTLIB)/inc
PIOSSTM32F10X = $(PIOS)/STM32F10x PIOSSTM32F10X = $(PIOS)/STM32F10x
PIOSCOMMON = $(PIOS)/Common PIOSCOMMON = $(PIOS)/Common
APPLIBDIR = $(PIOSSTM32F10X)/Libraries APPLIBDIR = $(PIOSSTM32F10X)/Libraries
STMLIBDIR = $(APPLIBDIR) STMLIBDIR = $(APPLIBDIR)
STMSPDDIR = $(STMLIBDIR)/STM32F10x_StdPeriph_Driver STMSPDDIR = $(STMLIBDIR)/STM32F10x_StdPeriph_Driver
STMUSBDIR = $(STMLIBDIR)/STM32_USB-FS-Device_Driver ifeq ($(USE_USB), YES)
STMUSBDIR = $(STMLIBDIR)/STM32_USB-FS-Device_Driver
endif
STMSPDSRCDIR = $(STMSPDDIR)/src STMSPDSRCDIR = $(STMSPDDIR)/src
STMSPDINCDIR = $(STMSPDDIR)/inc STMSPDINCDIR = $(STMSPDDIR)/inc
ifeq ($(USE_USB), YES)
STMUSBSRCDIR = $(STMUSBDIR)/src
STMUSBINCDIR = $(STMUSBDIR)/inc
endif
CMSISDIR = $(STMLIBDIR)/CMSIS/Core/CM3 CMSISDIR = $(STMLIBDIR)/CMSIS/Core/CM3
BOOT = ../Bootloaders/AHRS
BOOTINC = $(BOOT)/inc
# List C source files here. (C dependencies are automatically generated.) # List C source files here. (C dependencies are automatically generated.)
# use file-extension c for "c-only"-files # use file-extension c for "c-only"-files
## PipBee: ## Core:
SRC = pipbee.c SRC += $(HOME_DIR)/main.c
SRC += pios_board.c SRC += $(HOME_DIR)/pios_board.c
SRC += $(HOME_DIR)/crc.c
SRC += $(HOME_DIR)/aes.c
SRC += $(HOME_DIR)/rfm22b.c
SRC += $(HOME_DIR)/packet_handler.c
SRC += $(HOME_DIR)/transparent_comms.c
SRC += $(HOME_DIR)/uavtalk_comms.c
SRC += $(HOME_DIR)/saved_settings.c
SRC += $(HOME_DIR)/gpio_in.c
SRC += $(HOME_DIR)/stopwatch.c
SRC += $(FLIGHTLIB)/fifo_buffer.c
ifeq ($(USE_USB), YES)
SRC += $(HOME_DIR)/pios_usb_hid_desc.c
endif
## PIOS Hardware (STM32F10x) ## PIOS Hardware (STM32F10x)
SRC += $(PIOSSTM32F10X)/pios_sys.c SRC += $(PIOSSTM32F10X)/pios_sys.c
@ -99,6 +133,17 @@ SRC += $(PIOSSTM32F10X)/pios_irq.c
SRC += $(PIOSSTM32F10X)/pios_adc.c SRC += $(PIOSSTM32F10X)/pios_adc.c
SRC += $(PIOSSTM32F10X)/pios_gpio.c SRC += $(PIOSSTM32F10X)/pios_gpio.c
SRC += $(PIOSSTM32F10X)/pios_spi.c SRC += $(PIOSSTM32F10X)/pios_spi.c
SRC += $(PIOSSTM32F10X)/pios_wdg.c
# PIOS USB related files (seperated to make code maintenance more easy)
ifeq ($(USE_USB), YES)
SRC += $(PIOSSTM32F10X)/pios_usb_hid.c
#SRC += $(PIOSSTM32F10X)/pios_usb_hid_desc.c
#SRC += $(PIOSSTM32F10X)/pios_usb_hid_endp.c
SRC += $(PIOSSTM32F10X)/pios_usb_hid_istr.c
SRC += $(PIOSSTM32F10X)/pios_usb_hid_prop.c
SRC += $(PIOSSTM32F10X)/pios_usb_hid_pwr.c
endif
## PIOS Hardware (Common) ## PIOS Hardware (Common)
SRC += $(PIOSCOMMON)/pios_com.c SRC += $(PIOSCOMMON)/pios_com.c
@ -110,21 +155,34 @@ SRC += $(CMSISDIR)/system_stm32f10x.c
## Used parts of the STM-Library ## Used parts of the STM-Library
SRC += $(STMSPDSRCDIR)/stm32f10x_adc.c SRC += $(STMSPDSRCDIR)/stm32f10x_adc.c
SRC += $(STMSPDSRCDIR)/stm32f10x_bkp.c #SRC += $(STMSPDSRCDIR)/stm32f10x_bkp.c
SRC += $(STMSPDSRCDIR)/stm32f10x_crc.c #SRC += $(STMSPDSRCDIR)/stm32f10x_crc.c
SRC += $(STMSPDSRCDIR)/stm32f10x_dac.c #SRC += $(STMSPDSRCDIR)/stm32f10x_dac.c
SRC += $(STMSPDSRCDIR)/stm32f10x_dbgmcu.c
SRC += $(STMSPDSRCDIR)/stm32f10x_dma.c SRC += $(STMSPDSRCDIR)/stm32f10x_dma.c
SRC += $(STMSPDSRCDIR)/stm32f10x_exti.c SRC += $(STMSPDSRCDIR)/stm32f10x_exti.c
SRC += $(STMSPDSRCDIR)/stm32f10x_flash.c SRC += $(STMSPDSRCDIR)/stm32f10x_flash.c
SRC += $(STMSPDSRCDIR)/stm32f10x_gpio.c SRC += $(STMSPDSRCDIR)/stm32f10x_gpio.c
SRC += $(STMSPDSRCDIR)/stm32f10x_pwr.c SRC += $(STMSPDSRCDIR)/stm32f10x_iwdg.c
#SRC += $(STMSPDSRCDIR)/stm32f10x_i2c.c
#SRC += $(STMSPDSRCDIR)/stm32f10x_pwr.c
SRC += $(STMSPDSRCDIR)/stm32f10x_rcc.c SRC += $(STMSPDSRCDIR)/stm32f10x_rcc.c
SRC += $(STMSPDSRCDIR)/stm32f10x_rtc.c #SRC += $(STMSPDSRCDIR)/stm32f10x_rtc.c
SRC += $(STMSPDSRCDIR)/stm32f10x_spi.c SRC += $(STMSPDSRCDIR)/stm32f10x_spi.c
SRC += $(STMSPDSRCDIR)/stm32f10x_tim.c SRC += $(STMSPDSRCDIR)/stm32f10x_tim.c
SRC += $(STMSPDSRCDIR)/stm32f10x_usart.c SRC += $(STMSPDSRCDIR)/stm32f10x_usart.c
SRC += $(STMSPDSRCDIR)/misc.c SRC += $(STMSPDSRCDIR)/misc.c
## STM32 USB Library
ifeq ($(USE_USB), YES)
SRC += $(STMUSBSRCDIR)/usb_core.c
SRC += $(STMUSBSRCDIR)/usb_init.c
SRC += $(STMUSBSRCDIR)/usb_int.c
SRC += $(STMUSBSRCDIR)/usb_mem.c
SRC += $(STMUSBSRCDIR)/usb_regs.c
SRC += $(STMUSBSRCDIR)/usb_sil.c
endif
# List C source files here which must be compiled in ARM-Mode (no -mthumb). # List C source files here which must be compiled in ARM-Mode (no -mthumb).
# use file-extension c for "c-only"-files # use file-extension c for "c-only"-files
## just for testing, timer.c could be compiled in thumb-mode too ## just for testing, timer.c could be compiled in thumb-mode too
@ -153,14 +211,19 @@ ASRCARM =
# List any extra directories to look for include files here. # List any extra directories to look for include files here.
# Each directory must be seperated by a space. # Each directory must be seperated by a space.
EXTRAINCDIRS += $(HOME_DIR)
EXTRAINCDIRS += $(HOME_DIR_INC)
EXTRAINCDIRS += $(PIOS) EXTRAINCDIRS += $(PIOS)
EXTRAINCDIRS += $(PIOSINC) EXTRAINCDIRS += $(PIOSINC)
EXTRAINCDIRS += $(FLIGHTLIBINC) EXTRAINCDIRS += $(FLIGHTLIBINC)
EXTRAINCDIRS += $(PIOSSTM32F10X) EXTRAINCDIRS += $(PIOSSTM32F10X)
EXTRAINCDIRS += $(PIOSCOMMON) EXTRAINCDIRS += $(PIOSCOMMON)
EXTRAINCDIRS += $(STMSPDINCDIR) EXTRAINCDIRS += $(STMSPDINCDIR)
ifeq ($(USE_USB), YES)
EXTRAINCDIRS += $(STMUSBINCDIR)
endif
EXTRAINCDIRS += $(CMSISDIR) EXTRAINCDIRS += $(CMSISDIR)
EXTRAINCDIRS += $(PIPBEEINC) EXTRAINCDIRS += $(BOOTINC)
# List any extra directories to look for library files here. # List any extra directories to look for library files here.
# Also add directories where the linker should search for # Also add directories where the linker should search for
@ -187,6 +250,7 @@ ifeq ($(DEBUG),YES)
OPT = 0 OPT = 0
else else
OPT = s OPT = s
#OPT = 2
endif endif
# Output format. (can be ihex or binary or both) # Output format. (can be ihex or binary or both)
@ -204,6 +268,9 @@ DEBUGF = dwarf-2
CDEFS = -DSTM32F10X_$(MODEL) CDEFS = -DSTM32F10X_$(MODEL)
CDEFS += -DUSE_STDPERIPH_DRIVER CDEFS += -DUSE_STDPERIPH_DRIVER
CDEFS += -DUSE_$(BOARD) CDEFS += -DUSE_$(BOARD)
ifeq ($(USE_BOOTLOADER), YES)
CDEFS += -DUSE_BOOTLOADER
endif
# Place project-specific -D and/or -U options for # Place project-specific -D and/or -U options for
# Assembler with preprocessor here. # Assembler with preprocessor here.
@ -235,6 +302,9 @@ CFLAGS = -g$(DEBUGF)
endif endif
CFLAGS += -O$(OPT) CFLAGS += -O$(OPT)
ifeq ($(DEBUG),NO)
CFLAGS += -fdata-sections -ffunction-sections
endif
CFLAGS += -mcpu=$(MCU) -mthumb CFLAGS += -mcpu=$(MCU) -mthumb
CFLAGS += $(CDEFS) CFLAGS += $(CDEFS)
CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I. CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I.
@ -270,6 +340,9 @@ MATH_LIB = -lm
# -Map: create map file # -Map: create map file
# --cref: add cross reference to map file # --cref: add cross reference to map file
LDFLAGS = -nostartfiles -Wl,-Map=$(OUTDIR)/$(TARGET).map,--cref,--gc-sections LDFLAGS = -nostartfiles -Wl,-Map=$(OUTDIR)/$(TARGET).map,--cref,--gc-sections
ifeq ($(DEBUG),NO)
LDFLAGS += -Wl,-static -Wl,-s
endif
LDFLAGS += $(patsubst %,-L%,$(EXTRA_LIBDIRS)) LDFLAGS += $(patsubst %,-L%,$(EXTRA_LIBDIRS))
LDFLAGS += -lc LDFLAGS += -lc
LDFLAGS += $(patsubst %,-l%,$(EXTRA_LIBS)) LDFLAGS += $(patsubst %,-l%,$(EXTRA_LIBS))
@ -289,7 +362,12 @@ OOCD_EXE=openocd
# debug level # debug level
OOCD_CL=-d0 OOCD_CL=-d0
# interface and board/target settings (using the OOCD target-library here) # interface and board/target settings (using the OOCD target-library here)
OOCD_CL+=-f ../Project/OpenOCD/floss-jtag.ahrs.cfg -f ../Project/OpenOCD/stm32.cfg UNAME := $(shell uname)
ifeq ($(UNAME), Darwin)
OOCD_CL+=-f ../Project/OpenOCD/floss-jtag.pipxtreme.osx.cfg -f ../Project/OpenOCD/stm32.cfg
else
OOCD_CL+=-f ../Project/OpenOCD/floss-jtag.pipxtreme.cfg -f ../Project/OpenOCD/stm32.cfg
endif
# initialize # initialize
OOCD_CL+=-c init OOCD_CL+=-c init
# show the targets # show the targets
@ -411,12 +489,19 @@ gccversion :
# @echo $(ALLOBJ) # @echo $(ALLOBJ)
# Program the device. # Program the device.
ifeq ($(USE_BOOTLOADER), YES)
# Program the device with OP Upload Tool".
program: $(OUTDIR)/$(TARGET).bin
@echo ${quote}Programming with OP Upload Tool${quote}
../../ground/src/experimental/upload-build-desktop/debug/OPUploadTool -d 1 -p $(OUTDIR)/$(TARGET).bin
else
ifeq ($(FLASH_TOOL),OPENOCD) ifeq ($(FLASH_TOOL),OPENOCD)
# Program the device with Dominic Rath's OPENOCD in "batch-mode", needs cfg and "reset-script". # Program the device with Dominic Rath's OPENOCD in "batch-mode", needs cfg and "reset-script".
program: $(OUTDIR)/$(TARGET).elf program: $(OUTDIR)/$(TARGET).elf
@echo "Programming with OPENOCD" @echo ${quote}Programming with OPENOCD${quote}
$(OOCD_EXE) $(OOCD_CL) $(OOCD_EXE) $(OOCD_CL)
endif endif
endif
# Create final output file (.hex) from ELF output file. # Create final output file (.hex) from ELF output file.
%.hex: %.elf %.hex: %.elf

475
flight/PipXtreme/aes.c Normal file
View File

@ -0,0 +1,475 @@
// http://gladman.plushost.co.uk/oldsite/AES/index.php
//#include <stdio.h>
#include "aes.h"
#define BPOLY 0x1B
#define DPOLY 0x8D
const uint8_t sbox[256] =
{
0x63,0x7c,0x77,0x7b,0xf2,0x6b,0x6f,0xc5,0x30,0x01,0x67,0x2b,0xfe,0xd7,0xab,0x76,
0xca,0x82,0xc9,0x7d,0xfa,0x59,0x47,0xf0,0xad,0xd4,0xa2,0xaf,0x9c,0xa4,0x72,0xc0,
0xb7,0xfd,0x93,0x26,0x36,0x3f,0xf7,0xcc,0x34,0xa5,0xe5,0xf1,0x71,0xd8,0x31,0x15,
0x04,0xc7,0x23,0xc3,0x18,0x96,0x05,0x9a,0x07,0x12,0x80,0xe2,0xeb,0x27,0xb2,0x75,
0x09,0x83,0x2c,0x1a,0x1b,0x6e,0x5a,0xa0,0x52,0x3b,0xd6,0xb3,0x29,0xe3,0x2f,0x84,
0x53,0xd1,0x00,0xed,0x20,0xfc,0xb1,0x5b,0x6a,0xcb,0xbe,0x39,0x4a,0x4c,0x58,0xcf,
0xd0,0xef,0xaa,0xfb,0x43,0x4d,0x33,0x85,0x45,0xf9,0x02,0x7f,0x50,0x3c,0x9f,0xa8,
0x51,0xa3,0x40,0x8f,0x92,0x9d,0x38,0xf5,0xbc,0xb6,0xda,0x21,0x10,0xff,0xf3,0xd2,
0xcd,0x0c,0x13,0xec,0x5f,0x97,0x44,0x17,0xc4,0xa7,0x7e,0x3d,0x64,0x5d,0x19,0x73,
0x60,0x81,0x4f,0xdc,0x22,0x2a,0x90,0x88,0x46,0xee,0xb8,0x14,0xde,0x5e,0x0b,0xdb,
0xe0,0x32,0x3a,0x0a,0x49,0x06,0x24,0x5c,0xc2,0xd3,0xac,0x62,0x91,0x95,0xe4,0x79,
0xe7,0xc8,0x37,0x6d,0x8d,0xd5,0x4e,0xa9,0x6c,0x56,0xf4,0xea,0x65,0x7a,0xae,0x08,
0xba,0x78,0x25,0x2e,0x1c,0xa6,0xb4,0xc6,0xe8,0xdd,0x74,0x1f,0x4b,0xbd,0x8b,0x8a,
0x70,0x3e,0xb5,0x66,0x48,0x03,0xf6,0x0e,0x61,0x35,0x57,0xb9,0x86,0xc1,0x1d,0x9e,
0xe1,0xf8,0x98,0x11,0x69,0xd9,0x8e,0x94,0x9b,0x1e,0x87,0xe9,0xce,0x55,0x28,0xdf,
0x8c,0xa1,0x89,0x0d,0xbf,0xe6,0x42,0x68,0x41,0x99,0x2d,0x0f,0xb0,0x54,0xbb,0x16
};
const uint8_t isbox[256] =
{
0x52,0x09,0x6a,0xd5,0x30,0x36,0xa5,0x38,0xbf,0x40,0xa3,0x9e,0x81,0xf3,0xd7,0xfb,
0x7c,0xe3,0x39,0x82,0x9b,0x2f,0xff,0x87,0x34,0x8e,0x43,0x44,0xc4,0xde,0xe9,0xcb,
0x54,0x7b,0x94,0x32,0xa6,0xc2,0x23,0x3d,0xee,0x4c,0x95,0x0b,0x42,0xfa,0xc3,0x4e,
0x08,0x2e,0xa1,0x66,0x28,0xd9,0x24,0xb2,0x76,0x5b,0xa2,0x49,0x6d,0x8b,0xd1,0x25,
0x72,0xf8,0xf6,0x64,0x86,0x68,0x98,0x16,0xd4,0xa4,0x5c,0xcc,0x5d,0x65,0xb6,0x92,
0x6c,0x70,0x48,0x50,0xfd,0xed,0xb9,0xda,0x5e,0x15,0x46,0x57,0xa7,0x8d,0x9d,0x84,
0x90,0xd8,0xab,0x00,0x8c,0xbc,0xd3,0x0a,0xf7,0xe4,0x58,0x05,0xb8,0xb3,0x45,0x06,
0xd0,0x2c,0x1e,0x8f,0xca,0x3f,0x0f,0x02,0xc1,0xaf,0xbd,0x03,0x01,0x13,0x8a,0x6b,
0x3a,0x91,0x11,0x41,0x4f,0x67,0xdc,0xea,0x97,0xf2,0xcf,0xce,0xf0,0xb4,0xe6,0x73,
0x96,0xac,0x74,0x22,0xe7,0xad,0x35,0x85,0xe2,0xf9,0x37,0xe8,0x1c,0x75,0xdf,0x6e,
0x47,0xf1,0x1a,0x71,0x1d,0x29,0xc5,0x89,0x6f,0xb7,0x62,0x0e,0xaa,0x18,0xbe,0x1b,
0xfc,0x56,0x3e,0x4b,0xc6,0xd2,0x79,0x20,0x9a,0xdb,0xc0,0xfe,0x78,0xcd,0x5a,0xf4,
0x1f,0xdd,0xa8,0x33,0x88,0x07,0xc7,0x31,0xb1,0x12,0x10,0x59,0x27,0x80,0xec,0x5f,
0x60,0x51,0x7f,0xa9,0x19,0xb5,0x4a,0x0d,0x2d,0xe5,0x7a,0x9f,0x93,0xc9,0x9c,0xef,
0xa0,0xe0,0x3b,0x4d,0xae,0x2a,0xf5,0xb0,0xc8,0xeb,0xbb,0x3c,0x83,0x53,0x99,0x61,
0x17,0x2b,0x04,0x7e,0xba,0x77,0xd6,0x26,0xe1,0x69,0x14,0x63,0x55,0x21,0x0c,0x7d
};
//#define xtime(x) ( (x << 1) ^ (((x >> 7) & 1) * BPOLY) )
//#define xtime(x) ( (x << 1) ^ ((x & 0x80) ? BPOLY : 0) )
const uint8_t xtime[256] =
{
0x00,0x02,0x04,0x06,0x08,0x0a,0x0c,0x0e,0x10,0x12,0x14,0x16,0x18,0x1a,0x1c,0x1e,
0x20,0x22,0x24,0x26,0x28,0x2a,0x2c,0x2e,0x30,0x32,0x34,0x36,0x38,0x3a,0x3c,0x3e,
0x40,0x42,0x44,0x46,0x48,0x4a,0x4c,0x4e,0x50,0x52,0x54,0x56,0x58,0x5a,0x5c,0x5e,
0x60,0x62,0x64,0x66,0x68,0x6a,0x6c,0x6e,0x70,0x72,0x74,0x76,0x78,0x7a,0x7c,0x7e,
0x80,0x82,0x84,0x86,0x88,0x8a,0x8c,0x8e,0x90,0x92,0x94,0x96,0x98,0x9a,0x9c,0x9e,
0xa0,0xa2,0xa4,0xa6,0xa8,0xaa,0xac,0xae,0xb0,0xb2,0xb4,0xb6,0xb8,0xba,0xbc,0xbe,
0xc0,0xc2,0xc4,0xc6,0xc8,0xca,0xcc,0xce,0xd0,0xd2,0xd4,0xd6,0xd8,0xda,0xdc,0xde,
0xe0,0xe2,0xe4,0xe6,0xe8,0xea,0xec,0xee,0xf0,0xf2,0xf4,0xf6,0xf8,0xfa,0xfc,0xfe,
0x1b,0x19,0x1f,0x1d,0x13,0x11,0x17,0x15,0x0b,0x09,0x0f,0x0d,0x03,0x01,0x07,0x05,
0x3b,0x39,0x3f,0x3d,0x33,0x31,0x37,0x35,0x2b,0x29,0x2f,0x2d,0x23,0x21,0x27,0x25,
0x5b,0x59,0x5f,0x5d,0x53,0x51,0x57,0x55,0x4b,0x49,0x4f,0x4d,0x43,0x41,0x47,0x45,
0x7b,0x79,0x7f,0x7d,0x73,0x71,0x77,0x75,0x6b,0x69,0x6f,0x6d,0x63,0x61,0x67,0x65,
0x9b,0x99,0x9f,0x9d,0x93,0x91,0x97,0x95,0x8b,0x89,0x8f,0x8d,0x83,0x81,0x87,0x85,
0xbb,0xb9,0xbf,0xbd,0xb3,0xb1,0xb7,0xb5,0xab,0xa9,0xaf,0xad,0xa3,0xa1,0xa7,0xa5,
0xdb,0xd9,0xdf,0xdd,0xd3,0xd1,0xd7,0xd5,0xcb,0xc9,0xcf,0xcd,0xc3,0xc1,0xc7,0xc5,
0xfb,0xf9,0xff,0xfd,0xf3,0xf1,0xf7,0xf5,0xeb,0xe9,0xef,0xed,0xe3,0xe1,0xe7,0xe5
};
// ***********************************************************************************
/*
void createXTimeTable(void)
{
uint8_t i = 0;
do {
xtime[i] = (i << 1) ^ ((i & 0x80) ? BPOLY : 0);
} while (++i != 0);
}
*/
// ***********************************************************************************
/*
uint8_t powTable[256];
uint8_t logTable[256];
uint8_t sbox[256];
uint8_t isbox[256];
void createPowLogTables(void)
{
uint8_t i = 0;
uint8_t t = 1;
do {
powTable[i] = t;
logTable[t] = i;
i++;
t ^= (t << 1) ^ ((t & 0x80) ? BPOLY : 0);
} while (t != 1);
powTable[255] = powTable[0];
}
void createSubstitueBoxTable(void)
{
int i = 0;
do {
uint8_t temp;
if (i > 0)
temp = powTable[255 - logTable[i]];
else
temp = 0;
uint8_t sb = temp ^ 0x63;
for (int j = 0; j < 4; j++)
{
temp = (temp << 1) | (temp >> 7);
sb ^= temp;
}
sbox[i] = sb;
} while (++i != 0);
}
void createInverseSubstitueBoxTable(void)
{
uint8_t i = 0;
uint8_t j = 0;
do {
do {
if (sbox[j] == i)
{
isbox[i] = j;
j = 255;
}
} while (++j != 0);
} while (++i != 0);
}
*/
// ***********************************************************************************
void copy_block(void *d, void *s)
{
if (d == s) return;
register uint8_t *src = s;
register uint8_t *dest = d;
for (int i = N_BLOCK; i; --i)
*dest++ = *src++;
}
void xor_block(void *d, void *s)
{
register uint8_t *src = s;
register uint8_t *dest = d;
for (int i = N_BLOCK; i; --i)
*dest++ ^= *src++;
}
void xor_word(uint8_t *d, uint8_t *s)
{
*d++ ^= *s++;
*d++ ^= *s++;
*d++ ^= *s++;
*d++ ^= *s++;
}
void xor_sub_word(uint8_t *d, uint8_t *s)
{
*d++ ^= sbox[*s++];
*d++ ^= sbox[*s++];
*d++ ^= sbox[*s++];
*d++ ^= sbox[*s++];
}
void xor_sub_rot_word(uint8_t *d, uint8_t *s, uint8_t rc)
{
*d++ ^= sbox[s[1]] ^ rc;
*d++ ^= sbox[s[2]];
*d++ ^= sbox[s[3]];
*d++ ^= sbox[s[0]];
}
void mix_sub_column(uint8_t *a)
{
uint8_t a0 = a[0];
uint8_t a1 = a[1];
uint8_t a2 = a[2];
uint8_t a3 = a[3];
uint8_t tmp = a0 ^ a1 ^ a2 ^ a3;
a[0] = a0 ^ xtime[a0 ^ a1] ^ tmp;
a[1] = a1 ^ xtime[a1 ^ a2] ^ tmp;
a[2] = a2 ^ xtime[a2 ^ a3] ^ tmp;
a[3] = a3 ^ xtime[a3 ^ a0] ^ tmp;
}
void mix_sub_columns(void *a)
{
mix_sub_column((uint8_t*)a + 0);
mix_sub_column((uint8_t*)a + 4);
mix_sub_column((uint8_t*)a + 8);
mix_sub_column((uint8_t*)a + 12);
}
void inv_mix_sub_column(uint8_t *a)
{
uint8_t tmp;
tmp = xtime[xtime[a[0] ^ a[2]]];
a[0] ^= tmp;
a[2] ^= tmp;
tmp = xtime[xtime[a[1] ^ a[3]]];
a[1] ^= tmp;
a[3] ^= tmp;
}
void inv_mix_sub_columns(void *a)
{
inv_mix_sub_column((uint8_t*)a + 0);
inv_mix_sub_column((uint8_t*)a + 4);
inv_mix_sub_column((uint8_t*)a + 8);
inv_mix_sub_column((uint8_t*)a + 12);
mix_sub_columns(a);
}
void shift_sub_rows(uint8_t *a)
{
uint8_t tmp;
a[0] = sbox[a[0]];
a[4] = sbox[a[4]];
a[8] = sbox[a[8]];
a[12] = sbox[a[12]];
tmp = a[1];
a[1] = sbox[a[5]];
a[5] = sbox[a[9]];
a[9] = sbox[a[13]];
a[13] = sbox[tmp];
tmp = a[2];
a[2] = sbox[a[10]];
a[10] = sbox[tmp];
tmp = a[6];
a[6] = sbox[a[14]];
a[14] = sbox[tmp];
tmp = a[15];
a[15] = sbox[a[11]];
a[11] = sbox[a[7]];
a[7] = sbox[a[3]];
a[3] = sbox[tmp];
}
void inv_shift_sub_rows(uint8_t *a)
{
uint8_t tmp;
a[0] = isbox[a[0]];
a[4] = isbox[a[4]];
a[8] = isbox[a[8]];
a[12] = isbox[a[12]];
tmp = a[13];
a[13] = isbox[a[9]];
a[9] = isbox[a[5]];
a[5] = isbox[a[1]];
a[1] = isbox[tmp];
tmp = a[2];
a[2] = isbox[a[10]];
a[10] = isbox[tmp];
tmp = a[6];
a[6] = isbox[a[14]];
a[14] = isbox[tmp];
tmp = a[3];
a[3] = isbox[a[7]];
a[7] = isbox[a[11]];
a[11] = isbox[a[15]];
a[15] = isbox[tmp];
}
// ***********************************************************************************
// 'on the fly' encryption key update for 128 bit keys
void update_encrypt_key_128(uint8_t *k, uint8_t *rc)
{
xor_sub_rot_word(k + 0, k + 12, *rc);
*rc = (*rc << 1) ^ ((*rc & 0x80) ? BPOLY : 0);
for (int i = 4; i < 16; i += 4)
xor_word(k + i + 0, k + i - 4);
}
// Encrypt a single block of 16 bytes
void aes_encrypt_cbc_128(void *data, void *key, void *chain_block)
{
uint8_t rc = 1;
if (chain_block)
xor_block(data, chain_block);
for (int round = 10; round; --round)
{
xor_block(data, key); // add_round_key
update_encrypt_key_128((uint8_t *)key, &rc);
shift_sub_rows(data);
if (round <= 1) continue;
mix_sub_columns(data);
}
xor_block(data, key); // add_round_key
if (chain_block)
copy_block(chain_block, data);
}
// 'on the fly' decryption key update for 128 bit keys
void update_decrypt_key_128(uint8_t *k, uint8_t *rc)
{
for (int i = 12; i; i -= 4)
xor_word(k + i + 0, k + i - 4);
*rc = (*rc >> 1) ^ ((*rc & 1) ? DPOLY : 0);
xor_sub_rot_word(k + 0, k + 12, *rc);
}
// Decrypt a single block of 16 bytes
void aes_decrypt_cbc_128(void *data, void *key, void *chain_block)
{
uint8_t tmp_data[N_BLOCK];
uint8_t rc = 0x6c;
copy_block(tmp_data, data);
xor_block(data, key); // add_round_key
for (int round = 10; round; --round)
{
inv_shift_sub_rows(data);
update_decrypt_key_128(key, &rc);
xor_block(data, key); // add_round_key
if (round <= 1) continue;
inv_mix_sub_columns(data);
}
if (chain_block)
{
xor_block(data, chain_block);
copy_block(chain_block, tmp_data);
}
}
void aes_decrypt_key_128_create(void *enc_key, void *dec_key)
{
copy_block(dec_key, enc_key);
uint8_t rc = 1;
for (int i = 0; i < 10; i++)
update_encrypt_key_128(dec_key, &rc);
}
// ***********************************************************************************
// 'on the fly' encryption key update for 256 bit keys
void update_encrypt_key_256(uint8_t *k, uint8_t *rc)
{
xor_sub_rot_word(k + 0, k + 28, *rc);
*rc = (*rc << 1) ^ ((*rc & 0x80) ? BPOLY : 0);
for (int i = 4; i < 16; i += 4)
xor_word(k + i + 0, k + i - 4);
xor_sub_word(k + 16, k + 12);
for (int i = 20; i < 32; i += 4)
xor_word(k + i + 0, k + i - 4);
}
// Encrypt a single block of 16 bytes
void aes_encrypt_cbc_256(void *data, void *key, void *chain_block)
{
uint8_t rc = 1;
if (chain_block)
xor_block(data, chain_block);
for (int round = 7; round; --round)
{
// printf("key - ");
// uint8_t *p = key;
// for (int i = 0; i < 32; i++) printf("%0.2X ", *p++);
// printf("\r\n");
xor_block(data, key); // add_round_key
shift_sub_rows(data);
mix_sub_columns(data);
xor_block(data, (uint8_t*)key + 16); // add_round_key
update_encrypt_key_256(key, &rc);
shift_sub_rows(data);
if (round <= 1) continue;
mix_sub_columns(data);
}
xor_block(data, key); // add_round_key
if (chain_block)
copy_block(chain_block, data);
}
// 'on the fly' decryption key update for 256 bit keys
void update_decrypt_key_256(uint8_t *k, uint8_t *rc)
{
for (int i = 28; i >= 20; i -= 4)
xor_word(k + i + 0, k + i - 4);
xor_sub_word(k + 16, k + 12);
for (int i = 12; i; i -= 4)
xor_word(k + i + 0, k + i - 4);
*rc = (*rc >> 1) ^ ((*rc & 1) ? DPOLY : 0);
xor_sub_rot_word(k + 0, k + 28, *rc);
}
// Decrypt a single block of 16 bytes
void aes_decrypt_cbc_256(void *data, void *key, void *chain_block)
{
uint8_t tmp_data[N_BLOCK];
uint8_t rc = 0x80;
copy_block(tmp_data, data);
xor_block(data, key); // add_round_key
for (int round = 7; round; --round)
{
inv_shift_sub_rows(data);
update_decrypt_key_256(key, &rc);
xor_block(data, (uint8_t*)key + 16); // add_round_key
inv_mix_sub_columns(data);
inv_shift_sub_rows(data);
xor_block(data, key); // add_round_key
if (round <= 1) continue;
inv_mix_sub_columns(data);
}
if (chain_block)
{
xor_block(data, chain_block);
copy_block(chain_block, tmp_data);
}
}
void aes_decrypt_key_256_create(void *enc_key, void *dec_key)
{
if (dec_key != enc_key)
{
copy_block(dec_key, enc_key);
copy_block((uint8_t*)dec_key + 16, (uint8_t*)enc_key + 16);
}
uint8_t rc = 1;
for (int i = 7; i; --i)
update_encrypt_key_256(dec_key, &rc);
}
// ***********************************************************************************

View File

@ -1,3 +1,27 @@
/**
******************************************************************************
*
* @file crc.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief Serial communication port handling routines
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "crc.h" #include "crc.h"
@ -96,10 +120,11 @@ uint16_t UpdateCRC16(uint16_t crc, uint8_t b)
uint16_t UpdateCRC16Data(uint16_t crc, void *data, uint32_t len) uint16_t UpdateCRC16Data(uint16_t crc, void *data, uint32_t len)
{ {
register uint8_t *p = (uint8_t *)data; register uint8_t *p = (uint8_t *)data;
register uint16_t _crc = crc;
for (register uint32_t i = len; i > 0; i--) for (register uint32_t i = len; i > 0; i--)
crc = (crc >> 8) ^ CRC_Table16[(crc & 0xff) ^ *p++]; _crc = (_crc >> 8) ^ CRC_Table16[(_crc ^ *p++) & 0xff];
// crc = UpdateCRC16(crc, *p++); // _crc = UpdateCRC16(_crc, *p++);
return crc; return _crc;
} }
/* /*
// Generate the CRC table // Generate the CRC table
@ -134,10 +159,11 @@ uint32_t UpdateCRC32(uint32_t crc, uint8_t b)
uint32_t UpdateCRC32Data(uint32_t crc, void *data, uint32_t len) uint32_t UpdateCRC32Data(uint32_t crc, void *data, uint32_t len)
{ {
register uint8_t *p = (uint8_t *)data; register uint8_t *p = (uint8_t *)data;
register uint32_t _crc = crc;
for (register uint32_t i = len; i > 0; i--) for (register uint32_t i = len; i > 0; i--)
crc = (crc << 8) ^ CRC_Table32[(crc >> 24) ^ *p++]; _crc = (_crc << 8) ^ CRC_Table32[(_crc >> 24) ^ *p++];
// crc = UpdateCRC32(crc, *p++); // _crc = UpdateCRC32(_crc, *p++);
return crc; return _crc;
} }
/* /*
// Generate the CRC table // Generate the CRC table

View File

@ -0,0 +1,19 @@
#ifndef _AES_H_
#define _AES_H_
#include "stm32f10x.h"
#define N_ROW 4
#define N_COL 4
#define N_BLOCK (N_ROW * N_COL)
void aes_encrypt_cbc_128(void *data, void *key, void *chain_block);
void aes_decrypt_cbc_128(void *data, void *key, void *chain_block);
void aes_decrypt_key_128_create(void *enc_key, void *dec_key);
void aes_encrypt_cbc_256(void *data, void *key, void *chain_block);
void aes_decrypt_cbc_256(void *data, void *key, void *chain_block);
void aes_decrypt_key_256_create(void *enc_key, void *dec_key);
#endif

View File

@ -1,6 +1,30 @@
/**
******************************************************************************
*
* @file crc.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief Serial communication port handling routines
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef _crc_H #ifndef _CRC_H_
#define _crc_H #define _CRC_H_
#include "stm32f10x.h" #include "stm32f10x.h"

View File

@ -0,0 +1,63 @@
/**
******************************************************************************
*
* @file main.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief Main modem header.
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef __MAIN_H__
#define __MAIN_H__
#include <pios.h>
// *****************************************************************************
// firmware version
#define version_major 0 // 0 to 255
#define version_minor 1 // 0 to 255
// macro's for reading internal flash memory
#define mem8(addr) (*((volatile uint8_t *)(addr)))
#define mem16(addr) (*((volatile uint16_t *)(addr)))
#define mem32(addr) (*((volatile uint32_t *)(addr)))
enum {
freqBand_UNKNOWN = 0,
freqBand_434MHz,
freqBand_868MHz,
freqBand_915MHz
};
// *****************************************************************************
extern volatile uint32_t random32;
extern bool booting;
extern uint32_t flash_size;
extern char serial_number_str[25];
extern uint32_t serial_number_crc32;
// *****************************************************************************
#endif

View File

@ -0,0 +1,62 @@
/**
******************************************************************************
*
* @file packet_handler.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief Modem packet handling routines
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef __PACKET_HANDLER_H__
#define __PACKET_HANDLER_H__
#include "stdint.h"
// *****************************************************************************
#define PH_MAX_CONNECTIONS 1 // maximum number of remote connections
// *****************************************************************************
void ph_1ms_tick(void);
void ph_process(void);
bool ph_connected(const int connection_index);
uint16_t ph_putData_free(const int connection_index);
uint16_t ph_putData(const int connection_index, const void *data, uint16_t len);
uint16_t ph_getData_used(const int connection_index);
uint16_t ph_getData(const int connection_index, void *data, uint16_t len);
void ph_setDatarate(uint32_t datarate_bps);
uint32_t ph_getDatarate(void);
void ph_setTxPower(uint8_t tx_power);
uint8_t ph_getTxPower(void);
void ph_set_AES128_key(const void *key);
int ph_set_remote_serial_number(int connection_index, uint32_t sn);
void ph_init(uint32_t our_sn, uint32_t datarate_bps, uint8_t tx_power);
// *****************************************************************************
#endif

View File

@ -59,16 +59,36 @@ TIM8 | | | |
/* Channel 11 - */ /* Channel 11 - */
/* Channel 12 - */ /* Channel 12 - */
//------------------------
// BOOTLOADER_SETTINGS
//------------------------
#define FUNC_ID 3
#define HW_VERSION 21
#define BOOTLOADER_VERSION 0
#define MEM_SIZE 0x20000 //128K
#define SIZE_OF_DESCRIPTION 100
#define START_OF_USER_CODE (uint32_t)0x08002000
#define SIZE_OF_CODE (uint32_t)(MEM_SIZE-(START_OF_USER_CODE-0x08000000)-SIZE_OF_DESCRIPTION)
#ifdef STM32F10X_HD
#define HW_TYPE 0 //0=high_density 1=medium_density;
#elif STM32F10X_MD
#define HW_TYPE 1 //0=high_density 1=medium_density;
#endif
#define BOARD_READABLE TRUE
#define BOARD_WRITABLA TRUE
#define MAX_DEL_RETRYS 3
// ***************************************************************** // *****************************************************************
// System Settings // System Settings
#define PIOS_MASTER_CLOCK 72000000ul #define PIOS_MASTER_CLOCK 72000000ul
#define PIOS_PERIPHERAL_CLOCK (PIOS_MASTER_CLOCK / 2) #define PIOS_PERIPHERAL_CLOCK (PIOS_MASTER_CLOCK / 2)
#if defined(USE_BOOTLOADER) #if defined(USE_BOOTLOADER)
#define PIOS_NVIC_VECTTAB_FLASH ((uint32_t)0x08006000) #define PIOS_NVIC_VECTTAB_FLASH (START_OF_USER_CODE)
#else #else
#define PIOS_NVIC_VECTTAB_FLASH ((uint32_t)0x08000000) #define PIOS_NVIC_VECTTAB_FLASH ((uint32_t)0x08000000)
#endif #endif
// ***************************************************************** // *****************************************************************
@ -130,7 +150,7 @@ TIM8 | | | |
#define TIMER_INT_TIMER TIM3 #define TIMER_INT_TIMER TIM3
#define TIMER_INT_FUNC TIM3_IRQHandler #define TIMER_INT_FUNC TIM3_IRQHandler
#define TIMER_INT_PRIORITY 0 #define TIMER_INT_PRIORITY 2
// ***************************************************************** // *****************************************************************
// Stop watch timer // Stop watch timer
@ -142,23 +162,29 @@ TIM8 | | | |
// //
// See also pios_board.c // See also pios_board.c
#define PIOS_SPI_PORT 0 #define PIOS_SPI_PORT 0
// ***************************************************************** // *****************************************************************
// PIOS_USART // PIOS_USART
#define PIOS_USART_RX_BUFFER_SIZE 512 #define PIOS_USART_RX_BUFFER_SIZE 512
#define PIOS_USART_TX_BUFFER_SIZE 256 #define PIOS_USART_TX_BUFFER_SIZE 512
//#define PIOS_USART_BAUDRATE 57600 #define PIOS_COM_SERIAL 0
#define PIOS_USART_BAUDRATE 115200 //#define PIOS_COM_DEBUG PIOS_COM_SERIAL // comment this out if you don't want debug text sent out on the serial port
#define PIOS_COM_SERIAL 0 #define PIOS_USART_BAUDRATE 57600
//#define PIOS_USART_BAUDRATE 115200
#define PIOS_COM_DEBUG PIOS_COM_SERIAL // comment this out if you don't want debug text sent out on the serial port
#if defined(PIOS_INCLUDE_USB_HID) #if defined(PIOS_INCLUDE_USB_HID)
#define PIOS_COM_TELEM_USB 1 #define PIOS_COM_TELEM_USB 1
#endif
#if defined(PIOS_COM_DEBUG)
#define DEBUG_PRINTF(...) PIOS_COM_SendFormattedString(PIOS_COM_DEBUG, __VA_ARGS__)
// #define DEBUG_PRINTF(...) PIOS_COM_SendFormattedStringNonBlocking(PIOS_COM_DEBUG, __VA_ARGS__)
#else
#define DEBUG_PRINTF(...)
#endif #endif
// ***************************************************************** // *****************************************************************
@ -208,7 +234,7 @@ TIM8 | | | |
/* With an ADCCLK = 14 MHz and a sampling time of 293.5 cycles: */ /* With an ADCCLK = 14 MHz and a sampling time of 293.5 cycles: */
/* Tconv = 239.5 + 12.5 = 252 cycles = 18<31>s */ /* Tconv = 239.5 + 12.5 = 252 cycles = 18<31>s */
/* (1 / (ADCCLK / CYCLES)) = Sample Time (<28>S) */ /* (1 / (ADCCLK / CYCLES)) = Sample Time (<28>S) */
#define PIOS_ADC_IRQ_PRIO PIOS_IRQ_PRIO_HIGH #define PIOS_ADC_IRQ_PRIO 3
// ***************************************************************** // *****************************************************************
// GPIO output pins // GPIO output pins
@ -291,12 +317,12 @@ TIM8 | | | |
#define GPIO_IN_2_PIN GPIO_Pin_8 #define GPIO_IN_2_PIN GPIO_Pin_8
#define GPIO_IN_2_MODE GPIO_Mode_IN_FLOATING #define GPIO_IN_2_MODE GPIO_Mode_IN_FLOATING
// 868MHz JP // 868MHz jumper option
#define GPIO_IN_3_PORT GPIOB #define GPIO_IN_3_PORT GPIOB
#define GPIO_IN_3_PIN GPIO_Pin_8 #define GPIO_IN_3_PIN GPIO_Pin_8
#define GPIO_IN_3_MODE GPIO_Mode_IPU #define GPIO_IN_3_MODE GPIO_Mode_IPU
// 915MHz JP // 915MHz jumper option
#define GPIO_IN_4_PORT GPIOB #define GPIO_IN_4_PORT GPIOB
#define GPIO_IN_4_PIN GPIO_Pin_9 #define GPIO_IN_4_PIN GPIO_Pin_9
#define GPIO_IN_4_MODE GPIO_Mode_IPU #define GPIO_IN_4_MODE GPIO_Mode_IPU
@ -332,7 +358,25 @@ TIM8 | | | |
#define PIOS_USB_DETECT_GPIO_PORT GPIO_IN_2_PORT #define PIOS_USB_DETECT_GPIO_PORT GPIO_IN_2_PORT
#define PIOS_USB_DETECT_GPIO_PIN GPIO_IN_2_PIN #define PIOS_USB_DETECT_GPIO_PIN GPIO_IN_2_PIN
#define PIOS_USB_DETECT_EXTI_LINE EXTI_Line4 #define PIOS_USB_DETECT_EXTI_LINE EXTI_Line4
#define PIOS_IRQ_USB_PRIORITY PIOS_IRQ_PRIO_MID #define PIOS_IRQ_USB_PRIORITY 8
#endif
// *****************************************************************
// RFM22
//#define RFM22_EXT_INT_USE
#define RFM22_PIOS_SPI PIOS_SPI_PORT // SPIx
#if defined(RFM22_EXT_INT_USE)
#define RFM22_EXT_INT_PORT_SOURCE GPIO_PortSourceGPIOA
#define RFM22_EXT_INT_PIN_SOURCE GPIO_PinSource2
#define RFM22_EXT_INT_LINE EXTI_Line2
#define RFM22_EXT_INT_IRQn EXTI2_IRQn
#define RFM22_EXT_INT_FUNC EXTI2_IRQHandler
#define RFM22_EXT_INT_PRIORITY 1
#endif #endif
// ***************************************************************** // *****************************************************************

View File

@ -39,6 +39,6 @@
#define PIOS_INCLUDE_COM #define PIOS_INCLUDE_COM
#define PIOS_INCLUDE_GPIO #define PIOS_INCLUDE_GPIO
#define PIOS_INCLUDE_EXTI #define PIOS_INCLUDE_EXTI
//#define PIOS_INCLUDE_USB_HID #define PIOS_INCLUDE_USB_HID
#endif /* PIOS_CONFIG_H */ #endif /* PIOS_CONFIG_H */

View File

@ -38,20 +38,13 @@
#define PIOS_USB_VENDOR_ID 0x20A0 #define PIOS_USB_VENDOR_ID 0x20A0
#endif #endif
#ifndef PIOS_USB_VENDOR_STR
#define PIOS_USB_VENDOR_STR "openpilot.org"
#endif
#ifndef PIOS_USB_PRODUCT_STR
#define PIOS_USB_PRODUCT_STR "OpenPilot"
#endif
#ifndef PIOS_USB_PRODUCT_ID #ifndef PIOS_USB_PRODUCT_ID
#define PIOS_USB_PRODUCT_ID 0x4117 #define PIOS_USB_PRODUCT_ID 0x4117
#endif #endif
#ifndef PIOS_USB_VERSION_ID #ifndef PIOS_USB_VERSION_ID
#define PIOS_USB_VERSION_ID 0x0200 /* v2.00 */ #define PIOS_USB_VERSION_ID 0x1201 /* v2.00 */
#endif #endif
/* Internal defines which are used by PIOS USB HID (don't touch) */ /* Internal defines which are used by PIOS USB HID (don't touch) */

View File

@ -0,0 +1,612 @@
/**
******************************************************************************
*
* @file rfm22b.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief RF Module hardware layer
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef __RFM22B_H__
#define __RFM22B_H__
#include "stdint.h"
// ************************************
#define RFM22_DEVICE_VERSION_V2 0x02
#define RFM22_DEVICE_VERSION_A0 0x04
#define RFM22_DEVICE_VERSION_B1 0x06
// ************************************
#define rfm22_min_carrier_frequency_Hz 240000000ul
#define rfm22_max_carrier_frequency_Hz 930000000ul
// ************************************
enum { RX_WAIT_PREAMBLE_MODE = 0,
RX_WAIT_SYNC_MODE,
RX_DATA_MODE,
TX_DATA_MODE,
TX_CARRIER_MODE,
TX_PN_MODE};
// ************************************
#define bit0 (1u << 0)
#define bit1 (1u << 1)
#define bit2 (1u << 2)
#define bit3 (1u << 3)
#define bit4 (1u << 4)
#define bit5 (1u << 5)
#define bit6 (1u << 6)
#define bit7 (1u << 7)
// ************************************
#define rfm22_device_type 0x00 // R
#define rfm22_dt_mask 0x1F
#define rfm22_device_version 0x01 // R
#define rfm22_dv_mask 0x1F
#define rfm22_device_status 0x02 // R
#define rfm22_ds_cps_mask 0x03 // Chip Power State mask
#define rfm22_ds_cps_idle 0x00 // IDLE Chip Power State
#define rfm22_ds_cps_rx 0x01 // RX Chip Power State
#define rfm22_ds_cps_tx 0x02 // TX Chip Power State
//#define rfm22_ds_lockdet 0x04 //
//#define rfm22_ds_freqerr 0x08 //
#define rfm22_ds_headerr 0x10 // Header Error Status. Indicates if the received packet has a header check error
#define rfm22_ds_rxffem 0x20 // RX FIFO Empty Status
#define rfm22_ds_ffunfl 0x40 // RX/TX FIFO Underflow Status
#define rfm22_ds_ffovfl 0x80 // RX/TX FIFO Overflow Status
#define rfm22_interrupt_status1 0x03 // R
#define rfm22_is1_icrerror bit0 // CRC Error. When set to 1 the cyclic redundancy check is failed.
#define rfm22_is1_ipkvalid bit1 // Valid Packet Received.When set to 1 a valid packet has been received.
#define rfm22_is1_ipksent bit2 // Packet Sent Interrupt. When set to1 a valid packet has been transmitted.
#define rfm22_is1_iext bit3 // External Interrupt. When set to 1 an interrupt occurred on one of the GPIOs if it is programmed so. The status can be checked in register 0Eh. See GPIOx Configuration section for the details.
#define rfm22_is1_irxffafull bit4 // RX FIFO Almost Full.When set to 1 the RX FIFO has met its almost full threshold and needs to be read by the microcontroller.
#define rfm22_is1_ixtffaem bit5 // TX FIFO Almost Empty. When set to 1 the TX FIFO is almost empty and needs to be filled.
#define rfm22_is1_itxffafull bit6 // TX FIFO Almost Full. When set to 1 the TX FIFO has met its almost full threshold and needs to be transmitted.
#define rfm22_is1_ifferr bit7 // FIFO Underflow/Overflow Error. When set to 1 the TX or RX FIFO has overflowed or underflowed.
#define rfm22_interrupt_status2 0x04 // R
#define rfm22_is2_ipor bit0 // Power-on-Reset (POR). When the chip detects a Power on Reset above the desired setting this bit will be set to 1.
#define rfm22_is2_ichiprdy bit1 // Chip Ready (XTAL). When a chip ready event has been detected this bit will be set to 1.
#define rfm22_is2_ilbd bit2 // Low Battery Detect. When a low battery event is been detected this bit will be set to 1. This interrupt event is saved even if it is not enabled by the mask register bit and causes an interrupt after it is enabled.
#define rfm22_is2_iwut bit3 // Wake-Up-Timer. On the expiration of programmed wake-up timer this bit will be set to 1.
#define rfm22_is2_irssi bit4 // RSSI. When RSSI level exceeds the programmed threshold this bit will be set to 1.
#define rfm22_is2_ipreainval bit5 // Invalid Preamble Detected. When the preamble is not found within a period of time set by the invalid preamble detection threshold in Register 54h, this bit will be set to 1.
#define rfm22_is2_ipreaval bit6 // Valid Preamble Detected. When a preamble is detected this bit will be set to 1.
#define rfm22_is2_iswdet bit7 // Sync Word Detected. When a sync word is detected this bit will be set to 1.
#define rfm22_interrupt_enable1 0x05 // R/W
#define rfm22_ie1_encrcerror bit0 // Enable CRC Error. When set to 1 the CRC Error interrupt will be enabled.
#define rfm22_ie1_enpkvalid bit1 // Enable Valid Packet Received. When ipkvalid = 1 the Valid Packet Received Interrupt will be enabled.
#define rfm22_ie1_enpksent bit2 // Enable Packet Sent. When ipksent =1 the Packet Sense Interrupt will be enabled.
#define rfm22_ie1_enext bit3 // Enable External Interrupt. When set to 1 the External Interrupt will be enabled.
#define rfm22_ie1_enrxffafull bit4 // Enable RX FIFO Almost Full. When set to 1 the RX FIFO Almost Full interrupt will be enabled.
#define rfm22_ie1_entxffaem bit5 // Enable TX FIFO Almost Empty. When set to 1 the TX FIFO Almost Empty interrupt will be enabled.
#define rfm22_ie1_entxffafull bit6 // Enable TX FIFO Almost Full. When set to 1 the TX FIFO Almost Full interrupt will be enabled.
#define rfm22_ie1_enfferr bit7 // Enable FIFO Underflow/Overflow. When set to 1 the FIFO Underflow/Overflow interrupt will be enabled.
#define rfm22_interrupt_enable2 0x06 // R/W
#define rfm22_ie2_enpor bit0 // Enable POR. When set to 1 the POR interrupt will be enabled.
#define rfm22_ie2_enchiprdy bit1 // Enable Chip Ready (XTAL). When set to 1 the Chip Ready interrupt will be enabled.
#define rfm22_ie2_enlbd bit2 // Enable Low Battery Detect. When set to 1 the Low Battery Detect interrupt will be enabled.
#define rfm22_ie2_enwut bit3 // Enable Wake-Up Timer. When set to 1 the Wake-Up Timer interrupt will be enabled.
#define rfm22_ie2_enrssi bit4 // Enable RSSI. When set to 1 the RSSI Interrupt will be enabled.
#define rfm22_ie2_enpreainval bit5 // Enable Invalid Preamble Detected. When mpreadet =1 the Invalid Preamble Detected Interrupt will be enabled.
#define rfm22_ie2_enpreaval bit6 // Enable Valid Preamble Detected. When mpreadet =1 the Valid Preamble Detected Interrupt will be enabled.
#define rfm22_ie2_enswdet bit7 // Enable Sync Word Detected. When mpreadet =1 the Preamble Detected Interrupt will be enabled.
#define rfm22_op_and_func_ctrl1 0x07 // R/W
#define rfm22_opfc1_xton 0x01 // READY Mode (Xtal is ON).
#define rfm22_opfc1_pllon 0x02 // TUNE Mode (PLL is ON). When pllon = 1 the PLL will remain enabled in Idle State. This will for faster turn-around time at the cost of increased current consumption in Idle State.
#define rfm22_opfc1_rxon 0x04 // RX on in Manual Receiver Mode. Automatically cleared if Multiple Packets config. is disabled and a valid packet received.
#define rfm22_opfc1_txon 0x08 // TX on in Manual Transmit Mode. Automatically cleared in FIFO mode once the packet is sent. Transmission can be aborted during packet transmission, however, when no data has been sent yet, transmission can only be aborted after the device is programmed to “unmodulated carrier” ("Register 71h. Modulation Mode Control 2").
#define rfm22_opfc1_x32ksel 0x10 // 32,768 kHz Crystal Oscillator Select. 0: RC oscillator 1: 32 kHz crystal
#define rfm22_opfc1_enwt 0x20 // Enable Wake-Up-Timer. Enabled when enwt = 1. If the Wake-up-Timer function is enabled it will operate in any mode and notify the microcontroller through the GPIO interrupt when the timer expires.
#define rfm22_opfc1_enlbd 0x40 // Enable Low Battery Detect. When this bit is set to 1 the Low Battery Detector circuit and threshold comparison will be enabled.
#define rfm22_opfc1_swres 0x80 // Software Register Reset Bit. This bit may be used to reset all registers simultaneously to a DEFAULT state, without the need for sequentially writing to each individual register. The RESET is accomplished by setting swres = 1. This bit will be automatically cleared.
#define rfm22_op_and_func_ctrl2 0x08 // R/W
#define rfm22_opfc2_ffclrtx 0x01 // TX FIFO Reset/Clear. This has to be a two writes operation: Setting ffclrtx =1 followed by ffclrtx = 0 will clear the contents of the TX FIFO.
#define rfm22_opfc2_ffclrrx 0x02 // RX FIFO Reset/Clear. This has to be a two writes operation: Setting ffclrrx =1 followed by ffclrrx = 0 will clear the contents of the RX FIFO.
#define rfm22_opfc2_enldm 0x04 // Enable Low Duty Cycle Mode. If this bit is set to 1 then the chip turns on the RX regularly. The frequency should be set in the Wake-Up Timer Period register, while the minimum ON time should be set in the Low-Duty Cycle Mode Duration register. The FIFO mode should be enabled also.
#define rfm22_opfc2_autotx 0x08 // Automatic Transmission. When autotx = 1 the transceiver will enter automatically TX State when the FIFO is almost full. When the FIFO is empty it will automatically return to the Idle State.
#define rfm22_opfc2_rxmpk 0x10 // RX Multi Packet. When the chip is selected to use FIFO Mode (dtmod[1:0]) and RX Packet Handling (enpacrx) then it will fill up the FIFO with multiple valid packets if this bit is set, otherwise the transceiver will automatically leave the RX State after the first valid packet has been received.
#define rfm22_opfc2_antdiv_mask 0xE0 // Enable Antenna Diversity. The GPIO must be configured for Antenna Diversity for the algorithm to work properly.
#define rfm22_xtal_osc_load_cap 0x09 // R/W
#define rfm22_xolc_xlc_mask 0x7F // Tuning Capacitance for the 30 MHz XTAL.
#define rfm22_xolc_xtalshft 0x80 // Additional capacitance to course shift the frequency if xlc[6:0] is not sufficient. Not binary with xlc[6:0].
#define rfm22_cpu_output_clk 0x0A // R/W
#define rfm22_coc_30MHz 0x00
#define rfm22_coc_15MHz 0x01
#define rfm22_coc_10MHz 0x02
#define rfm22_coc_4MHz 0x03
#define rfm22_coc_3MHz 0x04
#define rfm22_coc_2MHz 0x05
#define rfm22_coc_1MHz 0x06
#define rfm22_coc_32768Hz 0x07
#define rfm22_coc_enlfc 0x08
#define rfm22_coc_0cycle 0x00
#define rfm22_coc_128cycles 0x10
#define rfm22_coc_256cycles 0x20
#define rfm22_coc_512cycles 0x30
#define rfm22_gpio0_config 0x0B // R/W
#define rfm22_gpio0_config_por 0x00 // Power-On-Reset (output)
#define rfm22_gpio0_config_wut 0x01 // Wake-Up Timer: 1 when WUT has expired (output)
#define rfm22_gpio0_config_lbd 0x02 // Low Battery Detect: 1 when battery is below threshold setting (output)
#define rfm22_gpio0_config_ddi 0x03 // Direct Digital Input
#define rfm22_gpio0_config_eife 0x04 // External Interrupt, falling edge (input)
#define rfm22_gpio0_config_eire 0x05 // External Interrupt, rising edge (input)
#define rfm22_gpio0_config_eisc 0x06 // External Interrupt, state change (input)
#define rfm22_gpio0_config_ai 0x07 // ADC Analog Input
#define rfm22_gpio0_config_atni 0x08 // Reserved (Analog Test N Input)
#define rfm22_gpio0_config_atpi 0x09 // Reserved (Analog Test P Input)
#define rfm22_gpio0_config_ddo 0x0A // Direct Digital Output
#define rfm22_gpio0_config_dto 0x0B // Reserved (Digital Test Output)
#define rfm22_gpio0_config_atno 0x0C // Reserved (Analog Test N Output)
#define rfm22_gpio0_config_atpo 0x0D // Reserved (Analog Test P Output)
#define rfm22_gpio0_config_rv 0xOE // Reference Voltage (output)
#define rfm22_gpio0_config_dclk 0x0F // TX/RX Data CLK output to be used in conjunction with TX/RX Data pin (output)
#define rfm22_gpio0_config_txd 0x10 // TX Data input for direct modulation (input)
#define rfm22_gpio0_config_err 0x11 // External Retransmission Request (input)
#define rfm22_gpio0_config_txstate 0x12 // TX State (output)
#define rfm22_gpio0_config_txfifoaf 0x13 // TX FIFO Almost Full (output)
#define rfm22_gpio0_config_rxd 0x14 // RX Data (output)
#define rfm22_gpio0_config_rxstate 0x15 // RX State (output)
#define rfm22_gpio0_config_rxfifoaf 0x16 // RX FIFO Almost Full (output)
#define rfm22_gpio0_config_antswt1 0x17 // Antenna 1 Switch used for antenna diversity (output)
#define rfm22_gpio0_config_antswt2 0x18 // Antenna 2 Switch used for antenna diversity (output)
#define rfm22_gpio0_config_vpd 0x19 // Valid Preamble Detected (output)
#define rfm22_gpio0_config_ipd 0x1A // Invalid Preamble Detected (output)
#define rfm22_gpio0_config_swd 0x1B // Sync Word Detected (output)
#define rfm22_gpio0_config_cca 0x1C // Clear Channel Assessment (output)
#define rfm22_gpio0_config_vdd 0x1D // VDD
#define rfm22_gpio0_config_pup 0x20
#define rfm22_gpio0_config_drv0 0x00 // output drive level
#define rfm22_gpio0_config_drv1 0x40 // output drive level
#define rfm22_gpio0_config_drv2 0x80 // output drive level
#define rfm22_gpio0_config_drv3 0xC0 // output drive level
#define rfm22_gpio1_config 0x0C // R/W
#define rfm22_gpio1_config_ipor 0x00 // Inverted Power-On-Reset (output)
#define rfm22_gpio1_config_wut 0x01 // Wake-Up Timer: 1 when WUT has expired (output)
#define rfm22_gpio1_config_lbd 0x02 // Low Battery Detect: 1 when battery is below threshold setting (output)
#define rfm22_gpio1_config_ddi 0x03 // Direct Digital Input
#define rfm22_gpio1_config_eife 0x04 // External Interrupt, falling edge (input)
#define rfm22_gpio1_config_eire 0x05 // External Interrupt, rising edge (input)
#define rfm22_gpio1_config_eisc 0x06 // External Interrupt, state change (input)
#define rfm22_gpio1_config_ai 0x07 // ADC Analog Input
#define rfm22_gpio1_config_atni 0x08 // Reserved (Analog Test N Input)
#define rfm22_gpio1_config_atpi 0x09 // Reserved (Analog Test P Input)
#define rfm22_gpio1_config_ddo 0x0A // Direct Digital Output
#define rfm22_gpio1_config_dto 0x0B // Reserved (Digital Test Output)
#define rfm22_gpio1_config_atno 0x0C // Reserved (Analog Test N Output)
#define rfm22_gpio1_config_atpo 0x0D // Reserved (Analog Test P Output)
#define rfm22_gpio1_config_rv 0xOE // Reference Voltage (output)
#define rfm22_gpio1_config_dclk 0x0F // TX/RX Data CLK output to be used in conjunction with TX/RX Data pin (output)
#define rfm22_gpio1_config_txd 0x10 // TX Data input for direct modulation (input)
#define rfm22_gpio1_config_err 0x11 // External Retransmission Request (input)
#define rfm22_gpio1_config_txstate 0x12 // TX State (output)
#define rfm22_gpio1_config_txfifoaf 0x13 // TX FIFO Almost Full (output)
#define rfm22_gpio1_config_rxd 0x14 // RX Data (output)
#define rfm22_gpio1_config_rxstate 0x15 // RX State (output)
#define rfm22_gpio1_config_rxfifoaf 0x16 // RX FIFO Almost Full (output)
#define rfm22_gpio1_config_antswt1 0x17 // Antenna 1 Switch used for antenna diversity (output)
#define rfm22_gpio1_config_antswt2 0x18 // Antenna 2 Switch used for antenna diversity (output)
#define rfm22_gpio1_config_vpd 0x19 // Valid Preamble Detected (output)
#define rfm22_gpio1_config_ipd 0x1A // Invalid Preamble Detected (output)
#define rfm22_gpio1_config_swd 0x1B // Sync Word Detected (output)
#define rfm22_gpio1_config_cca 0x1C // Clear Channel Assessment (output)
#define rfm22_gpio1_config_vdd 0x1D // VDD
#define rfm22_gpio1_config_pup 0x20
#define rfm22_gpio1_config_drv0 0x00 // output drive level
#define rfm22_gpio1_config_drv1 0x40 // output drive level
#define rfm22_gpio1_config_drv2 0x80 // output drive level
#define rfm22_gpio1_config_drv3 0xC0 // output drive level
#define rfm22_gpio2_config 0x0D // R/W
#define rfm22_gpio2_config_mc 0x00 // Microcontroller Clock (output)
#define rfm22_gpio2_config_wut 0x01 // Wake-Up Timer: 1 when WUT has expired (output)
#define rfm22_gpio2_config_lbd 0x02 // Low Battery Detect: 1 when battery is below threshold setting (output)
#define rfm22_gpio2_config_ddi 0x03 // Direct Digital Input
#define rfm22_gpio2_config_eife 0x04 // External Interrupt, falling edge (input)
#define rfm22_gpio2_config_eire 0x05 // External Interrupt, rising edge (input)
#define rfm22_gpio2_config_eisc 0x06 // External Interrupt, state change (input)
#define rfm22_gpio2_config_ai 0x07 // ADC Analog Input
#define rfm22_gpio2_config_atni 0x08 // Reserved (Analog Test N Input)
#define rfm22_gpio2_config_atpi 0x09 // Reserved (Analog Test P Input)
#define rfm22_gpio2_config_ddo 0x0A // Direct Digital Output
#define rfm22_gpio2_config_dto 0x0B // Reserved (Digital Test Output)
#define rfm22_gpio2_config_atno 0x0C // Reserved (Analog Test N Output)
#define rfm22_gpio2_config_atpo 0x0D // Reserved (Analog Test P Output)
#define rfm22_gpio2_config_rv 0xOE // Reference Voltage (output)
#define rfm22_gpio2_config_dclk 0x0F // TX/RX Data CLK output to be used in conjunction with TX/RX Data pin (output)
#define rfm22_gpio2_config_txd 0x10 // TX Data input for direct modulation (input)
#define rfm22_gpio2_config_err 0x11 // External Retransmission Request (input)
#define rfm22_gpio2_config_txstate 0x12 // TX State (output)
#define rfm22_gpio2_config_txfifoaf 0x13 // TX FIFO Almost Full (output)
#define rfm22_gpio2_config_rxd 0x14 // RX Data (output)
#define rfm22_gpio2_config_rxstate 0x15 // RX State (output)
#define rfm22_gpio2_config_rxfifoaf 0x16 // RX FIFO Almost Full (output)
#define rfm22_gpio2_config_antswt1 0x17 // Antenna 1 Switch used for antenna diversity (output)
#define rfm22_gpio2_config_antswt2 0x18 // Antenna 2 Switch used for antenna diversity (output)
#define rfm22_gpio2_config_vpd 0x19 // Valid Preamble Detected (output)
#define rfm22_gpio2_config_ipd 0x1A // Invalid Preamble Detected (output)
#define rfm22_gpio2_config_swd 0x1B // Sync Word Detected (output)
#define rfm22_gpio2_config_cca 0x1C // Clear Channel Assessment (output)
#define rfm22_gpio2_config_vdd 0x1D // VDD
#define rfm22_gpio2_config_pup 0x20
#define rfm22_gpio2_config_drv0 0x00 // output drive level
#define rfm22_gpio2_config_drv1 0x40 // output drive level
#define rfm22_gpio2_config_drv2 0x80 // output drive level
#define rfm22_gpio2_config_drv3 0xC0 // output drive level
#define rfm22_io_port_config 0x0E // R/W
#define rfm22_io_port_extitst2 0x40 // External Interrupt Status. If the GPIO2 is programmed to be external interrupt sources then the status can be read here.
#define rfm22_io_port_extitst1 0x20 // External Interrupt Status. If the GPIO1 is programmed to be external interrupt sources then the status can be read here.
#define rfm22_io_port_extitst0 0x10 // External Interrupt Status. If the GPIO0 is programmed to be external interrupt sources then the status can be read here.
#define rfm22_io_port_itsdo 0x08 // Interrupt Request Output on the SDO Pin. nIRQ output is present on the SDO pin if this bit is set and the nSEL input is inactive (high).
#define rfm22_io_port_dio2 0x04 // Direct I/O for GPIO2. If the GPIO2 is configured to be a direct output then the value on the GPIO pin can be set here. If the GPIO2 is configured to be a direct input then the value of the pin can be read here.
#define rfm22_io_port_dio1 0x02 // Direct I/O for GPIO1. If the GPIO1 is configured to be a direct output then the value on the GPIO pin can be set here. If the GPIO1 is configured to be a direct input then the value of the pin can be read here.
#define rfm22_io_port_dio0 0x01 // Direct I/O for GPIO0. If the GPIO0 is configured to be a direct output then the value on the GPIO pin can be set here. If the GPIO0 is configured to be a direct input then the value of the pin can be read here.
#define rfm22_io_port_default 0x00 // GPIO pins are default
#define rfm22_adc_config 0x0F // R/W
#define rfm22_ac_adcgain0 0x00
#define rfm22_ac_adcgain1 0x01
#define rfm22_ac_adcgain2 0x02
#define rfm22_ac_adcgain3 0x03
#define rfm22_ac_adcref_bg 0x00
#define rfm22_ac_adcref_vdd3 0x08
#define rfm22_ac_adcref_vdd2 0x0C
#define rfm22_ac_adcsel_temp_sensor 0x00
#define rfm22_ac_adcsel_gpio0 0x10
#define rfm22_ac_adcsel_gpio1 0x20
#define rfm22_ac_adcsel_gpio2 0x30
#define rfm22_ac_adcsel_gpio01 0x40
#define rfm22_ac_adcsel_gpio12 0x50
#define rfm22_ac_adcsel_gpio02 0x60
#define rfm22_ac_adcsel_gpio_gnd 0x70
#define rfm22_ac_adcstartbusy 0x80
#define rfm22_adc_sensor_amp_offset 0x10 // R/W
#define rfm22_asao_adcoffs_mask 0x0F // ADC Sensor Amplifier Offset. The offset can be calculated as Offset = adcoffs[2:0] x VDD/1000; MSB = adcoffs[3] = Sign bit.
#define rfm22_adc_value 0x11 // R .. Internal 8 bit ADC Output Value.
#define rfm22_temp_sensor_calib 0x12 // R/W
#define rfm22_tsc_tstrim_mask 0x0F // Temperature Sensor Trim Value.
#define rfm22_tsc_entstrim 0x10 // Temperature Sensor Trim Enable.
#define rfm22_tsc_entsoffs 0x20 // Temperature Sensor Offset to Convert from K to ºC.
#define rfm22_tsc_tsrange0 0x00 // Temperature Sensor Range Selection. 64C to +64C 0.5C resolution
#define rfm22_tsc_tsrange1 0x40 // -40 to +85C with 1.0C resolution
#define rfm22_tsc_tsrange2 0x80 // 0C to 85C with 0.5C resolution
#define rfm22_tsc_tsrange3 0xC0 // -40F to 216F with 1.0F resolution
#define rfm22_temp_value_offset 0x13 // R/W
#define rfm22_wakeup_timer_period1 0x14 // R/W
#define rfm22_wakeup_timer_period2 0x15 // R/W
#define rfm22_wakeup_timer_period3 0x16 // R/W
#define rfm22_wakeup_timer_value1 0x17 // R
#define rfm22_wakeup_timer_value2 0x18 // R
#define rfm22_low_dutycycle_mode_duration 0x19 // R/W
#define rfm22_low_battery_detector_threshold 0x1A // R/W
#define rfm22_battery_volateg_level 0x1B // R
#define rfm22_if_filter_bandwidth 0x1C // R/W
#define rfm22_iffbw_filset_mask 0x0F
#define rfm22_iffbw_ndec_exp_mask 0x70
#define rfm22_iffbw_dwn3_bypass 0x80
#define rfm22_afc_loop_gearshift_override 0x1D // R/W
#define rfm22_afc_lp_gs_ovrd_afcgearl_mask 0x07 // AFC Low Gear Setting.
#define rfm22_afc_lp_gs_ovrd_afcgearh_mask 0x38 // AFC High Gear Setting.
#define rfm22_afc_lp_gs_ovrd_enafc 0x40 // AFC Enable.
#define rfm22_afc_lp_gs_ovrd_afcbd 0x80 // If set, the tolerated AFC frequency error will be halved.
#define rfm22_afc_timing_control 0x1E // R/W
#define rfm22_clk_recovery_gearshift_override 0x1F // R/W
#define rfm22_clk_recovery_oversampling_ratio 0x20 // R/W
#define rfm22_clk_recovery_offset2 0x21 // R/W
#define rfm22_clk_recovery_offset1 0x22 // R/W
#define rfm22_clk_recovery_offset0 0x23 // R/W
#define rfm22_clk_recovery_timing_loop_gain1 0x24 // R/W
#define rfm22_clk_recovery_timing_loop_gain0 0x25 // R/W
#define rfm22_rssi 0x26 // R
#define rfm22_rssi_threshold_clear_chan_indicator 0x27 // R/W
#define rfm22_antenna_diversity_register1 0x28 // R
#define rfm22_antenna_diversity_register2 0x29 // R
#define rfm22_afc_limiter 0x2A // R/W .. AFC_pull_in_range = ±AFCLimiter[7:0] x (hbsel+1) x 625 Hz
#define rfm22_afc_correction_read 0x2B // R
#define rfm22_ook_counter_value1 0x2C // R/W
#define rfm22_ook_counter_value2 0x2D // R/W
#define rfm22_slicer_peak_hold 0x2E // R/W
#define rfm22_data_access_control 0x30 // R/W
#define rfm22_dac_crc_ccitt 0x00 //
#define rfm22_dac_crc_crc16 0x01 //
#define rfm22_dac_crc_iec16 0x02 //
#define rfm22_dac_crc_biacheva 0x03 //
#define rfm22_dac_encrc 0x04 // CRC Enable. Cyclic Redundancy Check generation is enabled if this bit is set.
#define rfm22_dac_enpactx 0x08 // Enable Packet TX Handling. If FIFO Mode (dtmod = 10) is being used automatic packet handling may be enabled. Setting enpactx = 1 will enable automatic packet handling in the TX path. Register 304D allow for various configurations of the packet structure. Setting enpactx = 0 will not do any packet handling in the TX path. It will only transmit what is loaded to the FIFO.
#define rfm22_dac_skip2ph 0x10 // Skip 2nd Phase of Preamble Detection. If set, we skip the second phase of the preamble detection (under certain conditions) if antenna diversity is enabled.
#define rfm22_dac_crcdonly 0x20 // CRC Data Only Enable. When this bit is set to 1 the CRC is calculated on and checked against the packet data fields only.
#define rfm22_dac_lsbfrst 0x40 // LSB First Enable. The LSB of the data will be transmitted/received first if this bit is set.
#define rfm22_dac_enpacrx 0x80 // Enable Packet RX Handling. If FIFO Mode (dtmod = 10) is being used automatic packet handling may be enabled. Setting enpacrx = 1 will enable automatic packet handling in the RX path. Register 304D allow for various configurations of the packet structure. Setting enpacrx = 0 will not do any packet handling in the RX path. It will only receive everything after the sync word and fill up the RX FIFO.
#define rfm22_ezmac_status 0x31 // R
#define rfm22_ezmac_status_pksent 0x01 // Packet Sent. A 1 a packet has been sent by the radio. (Same bit as in register 03, but reading it does not reset the IRQ)
#define rfm22_ezmac_status_pktx 0x02 // Packet Transmitting. When 1 the radio is currently transmitting a packet.
#define rfm22_ezmac_status_crcerror 0x04 // CRC Error. When 1 a Cyclic Redundancy Check error has been detected. (Same bit as in register 03, but reading it does not reset the IRQ)
#define rfm22_ezmac_status_pkvalid 0x08 // Valid Packet Received. When a 1 a valid packet has been received by the receiver. (Same bit as in register 03, but reading it does not reset the IRQ)
#define rfm22_ezmac_status_pkrx 0x10 // Packet Receiving. When 1 the radio is currently receiving a valid packet.
#define rfm22_ezmac_status_pksrch 0x20 // Packet Searching. When 1 the radio is searching for a valid packet.
#define rfm22_ezmac_status_rxcrc1 0x40 // If high, it indicates the last CRC received is all ones. May indicated Transmitter underflow in case of CRC error.
#define rfm22_header_control1 0x32 // R/W
#define rfm22_header_cntl1_bcen_none 0x00 // No broadcast address enable.
#define rfm22_header_cntl1_bcen_0 0x10 // Broadcast address enable for header byte 0.
#define rfm22_header_cntl1_bcen_1 0x20 // Broadcast address enable for header byte 1.
#define rfm22_header_cntl1_bcen_01 0x30 // Broadcast address enable for header bytes 0 & 1.
#define rfm22_header_cntl1_hdch_none 0x00 // No Received Header check
#define rfm22_header_cntl1_hdch_0 0x01 // Received Header check for byte 0.
#define rfm22_header_cntl1_hdch_1 0x02 // Received Header check for byte 1.
#define rfm22_header_cntl1_hdch_01 0x03 // Received Header check for bytes 0 & 1.
#define rfm22_header_control2 0x33 // R/W
#define rfm22_header_cntl2_hdlen_none 0x00 // no header
#define rfm22_header_cntl2_hdlen_3 0x10 // header 3
#define rfm22_header_cntl2_hdlen_32 0x20 // header 3 and 2
#define rfm22_header_cntl2_hdlen_321 0x30 // header 3 and 2 and 1
#define rfm22_header_cntl2_hdlen_3210 0x40 // header 3 and 2 and 1 and 0
#define rfm22_header_cntl2_fixpklen 0x08 // Fix Packet Length. When fixpklen = 1 the packet length (pklen[7:0]) is not included in the header. When fixpklen = 0 the packet length is included in the header.
#define rfm22_header_cntl2_synclen_3 0x00 // Synchronization Word 3
#define rfm22_header_cntl2_synclen_32 0x02 // Synchronization Word 3 followed by 2
#define rfm22_header_cntl2_synclen_321 0x04 // Synchronization Word 3 followed by 2 followed by 1
#define rfm22_header_cntl2_synclen_3210 0x06 // Synchronization Word 3 followed by 2 followed by 1 followed by 0
#define rfm22_header_cntl2_prealen 0x01 // MSB of Preamble Length. See register Preamble Length.
#define rfm22_preamble_length 0x34 // R/W
#define rfm22_preamble_detection_ctrl1 0x35 // R/W
#define rfm22_pre_det_ctrl1_preath_mask 0xF8 // Number of nibbles processed during detection.
#define rfm22_pre_det_ctrl1_rssi_offset_mask 0x07 // Value added as offset to RSSI calculation. Every increment in this register results in an increment of +4 dB in the RSSI.
#define rfm22_sync_word3 0x36 // R/W
#define rfm22_sync_word2 0x37 // R/W
#define rfm22_sync_word1 0x38 // R/W
#define rfm22_sync_word0 0x39 // R/W
#define rfm22_transmit_header3 0x3A // R/W
#define rfm22_transmit_header2 0x3B // R/W
#define rfm22_transmit_header1 0x3C // R/W
#define rfm22_transmit_header0 0x3D // R/W
#define rfm22_transmit_packet_length 0x3E // R/W
#define rfm22_check_header3 0x3F // R/W
#define rfm22_check_header2 0x40 // R/W
#define rfm22_check_header1 0x41 // R/W
#define rfm22_check_header0 0x42 // R/W
#define rfm22_header_enable3 0x43 // R/W
#define rfm22_header_enable2 0x44 // R/W
#define rfm22_header_enable1 0x45 // R/W
#define rfm22_header_enable0 0x46 // R/W
#define rfm22_received_header3 0x47 // R
#define rfm22_received_header2 0x48 // R
#define rfm22_received_header1 0x49 // R
#define rfm22_received_header0 0x4A // R
#define rfm22_received_packet_length 0x4B // R
#define rfm22_adc8_control 0x4F // R/W
/*
#define rfm22_analog_test_bus 0x50 // R/W
#define rfm22_digital_test_bus 0x51 // R/W
#define rfm22_tx_ramp_control 0x52 // R/W
#define rfm22_pll_tune_time 0x53 // R/W
#define rfm22_calibration_control 0x55 // R/W
#define rfm22_modem_test 0x56 // R/W
#define rfm22_chargepump_test 0x57 // R/W
#define rfm22_chargepump_current_trimming_override 0x58 // R/W
#define rfm22_divider_current_trimming 0x59 // R/W
#define rfm22_vco_current_trimming 0x5A // R/W
#define rfm22_vco_calibration_override 0x5B // R/W
#define rfm22_synthersizer_test 0x5C // R/W
#define rfm22_block_enable_override1 0x5D // R/W
#define rfm22_block_enable_override2 0x5E // R/W
#define rfm22_block_enable_override3 0x5F // R/W
*/
#define rfm22_channel_filter_coeff_addr 0x60 // R/W
#define rfm22_ch_fil_coeff_ad_inv_pre_th_mask 0xF0 //
#define rfm22_ch_fil_coeff_ad_chfiladd_mask 0x0F // Channel Filter Coefficient Look-up Table Address. The address for channel filter coefficients used in the RX path.
//#define rfm22_channel_filter_coeff_value 0x61 // R/W
#define rfm22_xtal_osc_por_ctrl 0x62 // R/W
#define rfm22_xtal_osc_por_ctrl_pwst_mask 0xE0 // Internal Power States of the Chip.
#define rfm22_xtal_osc_por_ctrl_clkhyst 0x10 // Clock Hysteresis Setting.
#define rfm22_xtal_osc_por_ctrl_enbias2x 0x08 // 2 Times Higher Bias Current Enable.
#define rfm22_xtal_osc_por_ctrl_enamp2x 0x04 // 2 Times Higher Amplification Enable.
#define rfm22_xtal_osc_por_ctrl_bufovr 0x02 // Output Buffer Enable Override.
#define rfm22_xtal_osc_por_ctrl_enbuf 0x01 // Output Buffer Enable.
/*
#define rfm22_rc_osc_coarse_calbration_override 0x63 // R/W
#define rfm22_rc_osc_fine_calbration_override 0x64 // R/W
#define rfm22_ldo_control_override 0x65 // R/W
#define rfm22_ldo_level_setting 0x66 // R/W
#define rfm22_deltasigma_adc_tuning1 0x67 // R/W
#define rfm22_deltasigma_adc_tuning2 0x68 // R/W
*/
#define rfm22_agc_override1 0x69 // R/W
#define rfm22_agc_ovr1_sgi 0x40 // AGC Loop, Set Gain Increase. If set to 0 then gain increasing will not be allowed. If set to 1 then gain increasing is allowed, default is 0.
#define rfm22_agc_ovr1_agcen 0x20 // Automatic Gain Control Enable. When this bit is set then the result of the control can be read out from bits [4:0], otherwise the gain can be controlled manually by writing into bits [4:0].
#define rfm22_agc_ovr1_lnagain 0x10 // LNA Gain Select. 0 = min gain = 5dB, 1 = max gain = 25 dB.
#define rfm22_agc_ovr1_pga_mask 0x0F // PGA Gain Override Value.
//#define rfm22_agc_override2 0x6A // R/W
//#define rfm22_gfsk_fir_coeff_addr 0x6B // R/W
//#define rfm22_gfsk_fir_coeff_value 0x6C // R/W
#define rfm22_tx_power 0x6D // R/W
#define rfm22_tx_pwr_txpow_0 0x00 // Lowest TX power
#define rfm22_tx_pwr_txpow_1 0x01 //
#define rfm22_tx_pwr_txpow_2 0x02 //
#define rfm22_tx_pwr_txpow_3 0x03 //
#define rfm22_tx_pwr_txpow_4 0x04 //
#define rfm22_tx_pwr_txpow_5 0x05 //
#define rfm22_tx_pwr_txpow_6 0x06 //
#define rfm22_tx_pwr_txpow_7 0x07 // Highest TX power
#define rfm22_tx_pwr_lna_sw 0x08 // LNA Switch Controller. If set, lna_sw control from the digital will go high during TX modes, and low during other times. If reset, the digital control signal is low at all times.
#define rfm22_tx_pwr_papeaklvl_0 0x10 // " "
#define rfm22_tx_pwr_papeaklvl_1 0x20 // PA Peak Detect Level (direct from register). 00 = 6.5, 01 = 7, 10 = 7.5, 11 = 8, 00 = default
#define rfm22_tx_pwr_papeaken 0x40 // PA Peak Detector Enable.
#define rfm22_tx_pwr_papeakval 0x80 // PA Peak Detector Value Read Register. Reading a 1 in this register when the papeaken=1 then the PA drain voltage is too high and the match network needs adjusting for optimal efficiency.
#define rfm22_tx_data_rate1 0x6E // R/W
#define rfm22_tx_data_rate0 0x6F // R/W
#define rfm22_modulation_mode_control1 0x70 // R/W
#define rfm22_mmc1_enwhite 0x01 // Data Whitening is Enabled if this bit is set.
#define rfm22_mmc1_enmanch 0x02 // Manchester Coding is Enabled if this bit is set.
#define rfm22_mmc1_enmaninv 0x04 // Manchester Data Inversion is Enabled if this bit is set.
#define rfm22_mmc1_manppol 0x08 // Manchester Preamble Polarity (will transmit a series of 1 if set, or series of 0 if reset).
#define rfm22_mmc1_enphpwdn 0x10 // If set, the Packet Handler will be powered down when chip is in low power mode.
#define rfm22_mmc1_txdtrtscale 0x20 // This bit should be set for Data Rates below 30 kbps.
#define rfm22_modulation_mode_control2 0x71 // R/W
#define rfm22_mmc2_modtyp_mask 0x03 // Modulation type.
#define rfm22_mmc2_modtyp_none 0x00 //
#define rfm22_mmc2_modtyp_ook 0x01 //
#define rfm22_mmc2_modtyp_fsk 0x02 //
#define rfm22_mmc2_modtyp_gfsk 0x03 //
#define rfm22_mmc2_fd 0x04 // MSB of Frequency Deviation Setting, see "Register 72h. Frequency Deviation".
#define rfm22_mmc2_eninv 0x08 // Invert TX and RX Data.
#define rfm22_mmc2_dtmod_mask 0x30 // Modulation source.
#define rfm22_mmc2_dtmod_dm_gpio 0x00 //
#define rfm22_mmc2_dtmod_dm_sdi 0x10 //
#define rfm22_mmc2_dtmod_fifo 0x20 //
#define rfm22_mmc2_dtmod_pn9 0x30 //
#define rfm22_mmc2_trclk_mask 0xC0 // TX Data Clock Configuration.
#define rfm22_mmc2_trclk_clk_none 0x00 //
#define rfm22_mmc2_trclk_clk_gpio 0x40 //
#define rfm22_mmc2_trclk_clk_sdo 0x80 //
#define rfm22_mmc2_trclk_clk_nirq 0xC0 //
#define rfm22_frequency_deviation 0x72 // R/W
#define rfm22_frequency_offset1 0x73 // R/W
#define rfm22_frequency_offset2 0x74 // R/W
#define rfm22_frequency_band_select 0x75 // R/W
#define rfm22_fb_mask 0x1F
#define rfm22_fbs_hbsel 0x20
#define rfm22_fbs_sbse 0x40
#define rfm22_nominal_carrier_frequency1 0x76 // R/W
#define rfm22_nominal_carrier_frequency0 0x77 // R/W
#define rfm22_frequency_hopping_channel_select 0x79 // R/W
#define rfm22_frequency_hopping_step_size 0x7A // R/W
#define rfm22_tx_fifo_control1 0x7C // R/W .. TX FIFO Almost Full Threshold (0 - 63)
#define rfm22_tx_fifo_control1_mask 0x3F
#define rfm22_tx_fifo_control2 0x7D // R/W .. TX FIFO Almost Empty Threshold (0 - 63)
#define rfm22_tx_fifo_control2_mask 0x3F
#define rfm22_rx_fifo_control 0x7E // R/W .. RX FIFO Almost Full Threshold (0 - 63)
#define rfm22_rx_fifo_control_mask 0x3F
#define rfm22_fifo_access 0x7F // R/W
// ************************************
void rfm22_setDatarate(uint32_t datarate_bps);
uint32_t rfm22_getDatarate(void);
void rfm22_setTxPower(uint8_t tx_pwr);
uint8_t rfm22_getTxPower(void);
void rfm22_setNominalCarrierFrequency(uint32_t frequency_hz);
uint32_t rfm22_getNominalCarrierFrequency(void);
void rfm22_setFreqHopChannel(uint8_t channel);
uint8_t rfm22_freqHopChannel(void);
int16_t rfm22_receivedRSSI(void);
int32_t rfm22_receivedAFCHz(void);
uint16_t rfm22_receivedLength(void);
uint8_t * rfm22_receivedPointer(void);
void rfm22_receivedDone(void);
int32_t rfm22_sendData(void *data, uint16_t length, bool send_immediately);
void rfm22_setTxCarrierMode(void);
void rfm22_setTxPNMode(void);
int8_t rfm22_currentMode(void);
bool rfm22_transmitting(void);
bool rfm22_channelIsClear(void);
bool rfm22_txReady(void);
void rfm22_1ms_tick(void);
void rfm22_process(void);
int rfm22_init(uint32_t min_frequency_hz, uint32_t max_frequency_hz, uint32_t freq_hop_step_size);
// ************************************
#endif

View File

@ -0,0 +1,76 @@
/**
******************************************************************************
*
* @file saved_settings.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief RF Module hardware layer
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef _SAVED_SETTINGS_H_
#define _SAVED_SETTINGS_H_
// *****************************************************************
#include "stm32f10x.h"
#include "stm32f10x_flash.h"
// *****************************************************************
typedef struct
{
uint32_t serial_baudrate; // serial uart baudrate
uint32_t destination_id;
uint32_t min_frequency_Hz;
uint32_t max_frequency_Hz;
uint32_t frequency_Hz;
uint32_t max_rf_bandwidth;
uint8_t max_tx_power;
uint8_t frequency_band;
uint8_t rf_xtal_cap;
bool aes_enable;
uint8_t aes_key[16];
uint8_t spare[32]; // allow for future unknown settings
uint32_t crc;
} __attribute__((__packed__)) t_saved_settings;
// *****************************************************************
// public variables
extern volatile t_saved_settings saved_settings __attribute__ ((aligned(4))); // a RAM copy of the settings stored in EEPROM
// *****************************************************************
// public functions
int32_t saved_settings_save(void);
void saved_settings_init(void);
// *****************************************************************
#endif

View File

@ -1,7 +1,7 @@
/** /**
****************************************************************************** ******************************************************************************
* *
* @file stopwatch.c * @file stopwatch.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief Stop watch function * @brief Stop watch function
* @see The GNU Public License (GPL) Version 3 * @see The GNU Public License (GPL) Version 3

View File

@ -0,0 +1,40 @@
/**
******************************************************************************
*
* @file transparent_comms.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief Serial communication port handling routines
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef __TRANSPARENT_COMMS_H__
#define __TRANSPARENT_COMMS_H__
#include "stdint.h"
// *****************************************************************************
void trans_1ms_tick(void);
void trans_process(void);
void trans_init(void);
// *****************************************************************************
#endif

View File

@ -0,0 +1,40 @@
/**
******************************************************************************
*
* @file uavtalk_comms.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief RF Module hardware layer
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef __UAVTALK_COMMS_H__
#define __UAVTALK_COMMS_H__
#include "stdint.h"
// *****************************************************************************
void uavtalk_1ms_tick(void);
void uavtalk_process(void);
void uavtalk_init(void);
// *****************************************************************************
#endif

1006
flight/PipXtreme/main.c Normal file
View File

@ -0,0 +1,1006 @@
/**
******************************************************************************
*
* @file main.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief Main modem functions
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
// *****************************************************************************
#define USE_WATCHDOG // comment this out if you don't want to use the watchdog
// *****************************************************************************
// OpenPilot Includes
#include <string.h>
#include "crc.h"
#include "aes.h"
#include "rfm22b.h"
#include "packet_handler.h"
#include "transparent_comms.h"
#include "uavtalk_comms.h"
#include "gpio_in.h"
#include "stopwatch.h"
#include "saved_settings.h"
#include "main.h"
// *****************************************************************************
// ADC data
#define ADC_REF 3.3f // ADC reference voltage
#define ADC_FULL_RANGE 4096 // 12 bit ADC
#define ADC_PSU_RESISTOR_TOP 10000.0f // 10k upper resistor
#define ADC_PSU_RESISTOR_BOTTOM 2700.0f // 2k7 lower resistor
#define ADC_PSU_RATIO (ADC_PSU_RESISTOR_BOTTOM / (ADC_PSU_RESISTOR_TOP + ADC_PSU_RESISTOR_BOTTOM))
#define ADC_PSU_mV_SCALE ((ADC_REF * 1000) / (ADC_FULL_RANGE * ADC_PSU_RATIO))
// *****************************************************************************
// Global Variables
uint32_t flash_size;
char serial_number_str[25];
uint32_t serial_number_crc32;
uint32_t reset_addr;
bool API_Mode;
bool booting;
volatile uint32_t random32;
// *****************************************************************************
// Local Variables
#if defined(USE_WATCHDOG)
volatile uint16_t watchdog_timer;
uint16_t watchdog_delay;
#endif
volatile bool inside_timer_int;
volatile uint32_t uptime_ms;
volatile uint16_t second_tick_timer;
volatile bool second_tick;
volatile int32_t temp_adc;
volatile int32_t psu_adc;
// *****************************************************************************
#if defined(USE_WATCHDOG)
void processWatchdog(void)
{
// random32 = UpdateCRC32(random32, IWDG->SR);
if (watchdog_timer < watchdog_delay)
return;
// the watchdog needs resetting
watchdog_timer = 0;
PIOS_WDG_Clear();
}
void enableWatchdog(void)
{ // enable a watchdog
watchdog_timer = 0;
watchdog_delay = PIOS_WDG_Init(1000); // 1 second watchdog timeout
}
#endif
// *****************************************************************************
/*
void WWDG_IRQHandler(void)
{
// Update WWDG counter
WWDG_SetCounter(0x7F);
// Clear EWI flag
WWDG_ClearFlag();
}
void enableWatchdog(void)
{
// Enable WWDG clock
RCC_APB1PeriphClockCmd(RCC_APB1Periph_WWDG, ENABLE);
// On Value line devices, WWDG clock counter = (PCLK1 (24MHz)/4096)/8 = 732 Hz (~1366 æs)
// On other devices, WWDG clock counter = (PCLK1(36MHz)/4096)/8 = 1099 Hz (~910 æs)
WWDG_SetPrescaler(WWDG_Prescaler_8);
// Set Window value to 65
WWDG_SetWindowValue(65);
// On Value line devices, Enable WWDG and set counter value to 127, WWDG timeout = ~1366 æs * 64 = 87.42 ms
// On other devices, Enable WWDG and set counter value to 127, WWDG timeout = ~910 æs * 64 = 58.25 ms
WWDG_Enable(127);
// Clear EWI flag
WWDG_ClearFlag();
// Enable EW interrupt
WWDG_EnableIT();
}
*/
// *****************************************************************************
void sequenceLEDs(void)
{
for (int i = 0; i < 2; i++)
{
USB_LED_ON;
PIOS_DELAY_WaitmS(80);
USB_LED_OFF;
LINK_LED_ON;
PIOS_DELAY_WaitmS(80);
LINK_LED_OFF;
RX_LED_ON;
PIOS_DELAY_WaitmS(80);
RX_LED_OFF;
TX_LED_ON;
PIOS_DELAY_WaitmS(80);
TX_LED_OFF;
#if defined(USE_WATCHDOG)
processWatchdog(); // process the watchdog
#endif
}
}
// *****************************************************************************
/*
void setup_SPI(void)
{
SPI_InitTypeDef SPI_InitStructure;
SPI_InitStructure.SPI_Mode = SPI_Mode_Master,
// SPI_InitStructure.SPI_Mode = SPI_Mode_Slave,
SPI_InitStructure.SPI_Direction = SPI_Direction_2Lines_FullDuplex,
// SPI_InitStructure.SPI_Direction = SPI_Direction_2Lines_RxOnly,
// SPI_InitStructure.SPI_Direction = SPI_Direction_1Line_Rx,
// SPI_InitStructure.SPI_Direction = SPI_Direction_1Line_Tx,
// SPI_InitStructure.SPI_DataSize = SPI_DataSize_16b,
SPI_InitStructure.SPI_DataSize = SPI_DataSize_8b,
SPI_InitStructure.SPI_NSS = SPI_NSS_Soft,
// SPI_InitStructure.SPI_NSS = SPI_NSS_Hard,
SPI_InitStructure.SPI_FirstBit = SPI_FirstBit_MSB,
// SPI_InitStructure.SPI_FirstBit = SPI_FirstBit_LSB,
SPI_InitStructure.SPI_CRCPolynomial = 7,
// SPI_InitStructure.SPI_CPOL = SPI_CPOL_Low,
SPI_InitStructure.SPI_CPOL = SPI_CPOL_High,
// SPI_InitStructure.SPI_CPHA = SPI_CPHA_1Edge,
SPI_InitStructure.SPI_CPHA = SPI_CPHA_2Edge,
// SPI_InitStructure.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_2, // fastest SCLK
// SPI_InitStructure.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_4,
// SPI_InitStructure.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8,
// SPI_InitStructure.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_16,
// SPI_InitStructure.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_32,
// SPI_InitStructure.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_64,
// SPI_InitStructure.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_128,
SPI_InitStructure.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_256, // slowest SCLK
SPI_Init(SPI1, &SPI_InitStructure);
SPI_Cmd(SPI1, ENABLE);
}
*/
// *****************************************************************************
// timer interrupt
void TIMER_INT_FUNC(void)
{
inside_timer_int = TRUE;
if (TIM_GetITStatus(TIMER_INT_TIMER, TIM_IT_Update) != RESET)
{
// Clear timer interrupt pending bit
TIM_ClearITPendingBit(TIMER_INT_TIMER, TIM_IT_Update);
// random32 = UpdateCRC32(random32, PIOS_DELAY_TIMER->CNT >> 8);
// random32 = UpdateCRC32(random32, PIOS_DELAY_TIMER->CNT);
uptime_ms++;
#if defined(USE_WATCHDOG)
watchdog_timer++;
#endif
// ***********
if (!booting)
{
// ***********
if (++second_tick_timer >= 1000)
{
second_tick_timer -= 1000;
second_tick = TRUE;
}
// ***********
// read the chip temperature
temp_adc = PIOS_ADC_PinGet(0);
// read the psu voltage
psu_adc = PIOS_ADC_PinGet(1);
// ***********
rfm22_1ms_tick(); // rf module tick
ph_1ms_tick(); // packet handler tick
if (!API_Mode)
trans_1ms_tick(); // transparent communications tick
else
uavtalk_1ms_tick(); // uavtalk communications tick
// ***********
}
}
inside_timer_int = FALSE;
}
void setup_TimerInt(uint16_t Hz)
{ // setup the timer interrupt
// enable timer clock
switch ((uint32_t)TIMER_INT_TIMER)
{
case (uint32_t)TIM1: RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM1, ENABLE); break;
case (uint32_t)TIM2: RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE); break;
case (uint32_t)TIM3: RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3, ENABLE); break;
case (uint32_t)TIM4: RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM4, ENABLE); break;
#ifdef STM32F10X_HD
case (uint32_t)TIM5: RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM5, ENABLE); break;
case (uint32_t)TIM6: RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM6, ENABLE); break;
case (uint32_t)TIM7: RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM7, ENABLE); break;
case (uint32_t)TIM8: RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM8, ENABLE); break;
#endif
}
// enable timer interrupt
NVIC_InitTypeDef NVIC_InitStructure;
switch ((uint32_t)TIMER_INT_TIMER)
{
// case (uint32_t)TIM1: NVIC_InitStructure.NVIC_IRQChannel = TIM1_IRQn; break;
case (uint32_t)TIM2: NVIC_InitStructure.NVIC_IRQChannel = TIM2_IRQn; break;
case (uint32_t)TIM3: NVIC_InitStructure.NVIC_IRQChannel = TIM3_IRQn; break;
case (uint32_t)TIM4: NVIC_InitStructure.NVIC_IRQChannel = TIM4_IRQn; break;
#ifdef STM32F10X_HD
case (uint32_t)TIM5: NVIC_InitStructure.NVIC_IRQChannel = TIM5_IRQn; break;
case (uint32_t)TIM6: NVIC_InitStructure.NVIC_IRQChannel = TIM6_IRQn; break;
case (uint32_t)TIM7: NVIC_InitStructure.NVIC_IRQChannel = TIM7_IRQn; break;
// case (uint32_t)TIM8: NVIC_InitStructure.NVIC_IRQChannel = TIM8_IRQn; break;
#endif
}
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = TIMER_INT_PRIORITY;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
// Time base configuration
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
TIM_TimeBaseStructure.TIM_Period = ((1000000 / Hz) - 1);
TIM_TimeBaseStructure.TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1; // For 1 uS accuracy
TIM_TimeBaseStructure.TIM_ClockDivision = TIM_CKD_DIV1;
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
TIM_TimeBaseInit(TIMER_INT_TIMER, &TIM_TimeBaseStructure);
// Enable the CC2 Interrupt Request
TIM_ITConfig(TIMER_INT_TIMER, TIM_IT_Update, ENABLE);
// Clear update pending flag
TIM_ClearFlag(TIMER_INT_TIMER, TIM_FLAG_Update);
// Enable counter
TIM_Cmd(TIMER_INT_TIMER, ENABLE);
}
// *****************************************************************************
// read the CPU's flash and ram sizes
void get_CPUDetails(void)
{
// read the flash size
flash_size = (uint32_t)mem16(0x1FFFF7E0) * 1024;
int j = 0;
// read the CPU electronic signature (12-bytes)
serial_number_str[j] = 0;
for (int i = 0; i < 12; i++)
{
uint8_t ms_nibble = mem8(0x1ffff7e8 + i) >> 4;
uint8_t ls_nibble = mem8(0x1ffff7e8 + i) & 0x0f;
if (j > sizeof(serial_number_str) - 3) break;
serial_number_str[j++] = ((ms_nibble > 9) ? ('A' - 10) : '0') + ms_nibble;
serial_number_str[j++] = ((ls_nibble > 9) ? ('A' - 10) : '0') + ls_nibble;
serial_number_str[j] = 0;
}
// create a 32-bit crc from the serial number hex string
serial_number_crc32 = UpdateCRC32Data(0xffffffff, serial_number_str, j);
serial_number_crc32 = UpdateCRC32(serial_number_crc32, j);
// reset_addr = (uint32_t)&Reset_Handler;
}
// *****************************************************************************
void init_RF_module(void)
{
int i = -100;
switch (saved_settings.frequency_band)
{
case freqBand_434MHz:
case freqBand_868MHz:
case freqBand_915MHz:
i = rfm22_init(saved_settings.min_frequency_Hz, saved_settings.max_frequency_Hz, 50000);
break;
default:
#if defined(PIOS_COM_DEBUG)
DEBUG_PRINTF("UNKNOWN BAND ERROR\r\n", i);
#endif
for (int j = 0; j < 8; j++)
{
USB_LED_ON;
LINK_LED_OFF;
RX_LED_ON;
TX_LED_OFF;
PIOS_DELAY_WaitmS(200);
USB_LED_OFF;
LINK_LED_ON;
RX_LED_OFF;
TX_LED_ON;
PIOS_DELAY_WaitmS(200);
#if defined(USE_WATCHDOG)
processWatchdog();
#endif
}
PIOS_DELAY_WaitmS(1000);
PIOS_SYS_Reset();
while (1);
break;
}
if (i < 0)
{ // RF module error .. flash the LED's
#if defined(PIOS_COM_DEBUG)
DEBUG_PRINTF("RF ERROR res: %d\r\n", i);
#endif
for (int j = 0; j < 6; j++)
{
USB_LED_ON;
LINK_LED_ON;
RX_LED_OFF;
TX_LED_OFF;
PIOS_DELAY_WaitmS(200);
USB_LED_OFF;
LINK_LED_OFF;
RX_LED_ON;
TX_LED_ON;
PIOS_DELAY_WaitmS(200);
#if defined(USE_WATCHDOG)
processWatchdog();
#endif
}
PIOS_DELAY_WaitmS(1000);
PIOS_SYS_Reset();
while (1);
}
// set carrier frequency
rfm22_setNominalCarrierFrequency(saved_settings.frequency_Hz);
ph_setDatarate(saved_settings.max_rf_bandwidth);
ph_setTxPower(saved_settings.max_tx_power);
}
// *****************************************************************************
// find out what caused our reset and act on it
void processReset(void)
{
if (RCC_GetFlagStatus(RCC_FLAG_IWDGRST) != RESET)
{ // Independant Watchdog Reset
#if defined(PIOS_COM_DEBUG)
DEBUG_PRINTF("\r\nINDEPENDANT WATCHDOG CAUSED A RESET\r\n");
#endif
// all led's ON
USB_LED_ON;
LINK_LED_ON;
RX_LED_ON;
TX_LED_ON;
PIOS_DELAY_WaitmS(500); // delay a bit
// all led's OFF
USB_LED_OFF;
LINK_LED_OFF;
RX_LED_OFF;
TX_LED_OFF;
}
/*
if (RCC_GetFlagStatus(RCC_FLAG_WWDGRST) != RESET)
{ // Window Watchdog Reset
DEBUG_PRINTF("\r\nWINDOW WATCHDOG CAUSED A REBOOT\r\n");
// all led's ON
USB_LED_ON;
LINK_LED_ON;
RX_LED_ON;
TX_LED_ON;
PIOS_DELAY_WaitmS(500); // delay a bit
// all led's OFF
USB_LED_OFF;
LINK_LED_OFF;
RX_LED_OFF;
TX_LED_OFF;
}
*/
if (RCC_GetFlagStatus(RCC_FLAG_PORRST) != RESET)
{ // Power-On Reset
#if defined(PIOS_COM_DEBUG)
DEBUG_PRINTF("\r\nPOWER-ON-RESET\r\n");
#endif
}
if (RCC_GetFlagStatus(RCC_FLAG_SFTRST) != RESET)
{ // Software Reset
#if defined(PIOS_COM_DEBUG)
DEBUG_PRINTF("\r\nSOFTWARE RESET\r\n");
#endif
}
if (RCC_GetFlagStatus(RCC_FLAG_LPWRRST) != RESET)
{ // Low-Power Reset
#if defined(PIOS_COM_DEBUG)
DEBUG_PRINTF("\r\nLOW POWER RESET\r\n");
#endif
}
if (RCC_GetFlagStatus(RCC_FLAG_PINRST) != RESET)
{ // Pin Reset
#if defined(PIOS_COM_DEBUG)
DEBUG_PRINTF("\r\nPIN RESET\r\n");
#endif
}
// Clear reset flags
RCC_ClearFlag();
}
// *****************************************************************************
// Main function
int main()
{
// *************
// init various variables
booting = TRUE;
inside_timer_int = FALSE;
uptime_ms = 0;
flash_size = 0;
serial_number_str[0] = 0;
serial_number_crc32 = 0;
reset_addr = 0;
temp_adc = -1;
psu_adc = -1;
API_Mode = FALSE;
// API_Mode = TRUE; // TEST ONLY
second_tick_timer = 0;
second_tick = FALSE;
saved_settings.frequency_band = freqBand_UNKNOWN;
// *************
// Bring up System using CMSIS functions, enables the LEDs.
PIOS_SYS_Init();
// turn all the leds on
USB_LED_ON;
LINK_LED_ON;
RX_LED_ON;
TX_LED_ON;
CRC_init();
// read the CPU details
get_CPUDetails();
// Delay system
PIOS_DELAY_Init();
// UART communication system
PIOS_COM_Init();
// ADC system
PIOS_ADC_Init();
// SPI link to master
PIOS_SPI_Init();
// setup the GPIO input pins
GPIO_IN_Init();
// *************
// set various GPIO pin states
// uart serial RTS line high
SERIAL_RTS_ENABLE;
SERIAL_RTS_SET;
// RF module chip-select line high
RF_CS_ENABLE;
RF_CS_HIGH;
// EEPROM chip-select line high
EE_CS_ENABLE;
EE_CS_HIGH;
// *************
random32 ^= serial_number_crc32; // try to randomize the random number
// random32 ^= serial_number_crc32 ^ CRC_IDR; // try to randomize the random number
ph_init(serial_number_crc32, 128000, 0); // initialise the packet handler
trans_init(); // initialise the tranparent communications module
uavtalk_init(); // initialise the UAVTalk communications module
setup_TimerInt(1000); // setup a 1kHz timer interrupt
#if defined(USE_WATCHDOG)
enableWatchdog(); // enable the watchdog
#endif
// *************
// do a simple LED flash test sequence so the user knows all the led's are working and that we have booted
PIOS_DELAY_WaitmS(100);
// turn all the leds off
USB_LED_OFF;
LINK_LED_OFF;
RX_LED_OFF;
TX_LED_OFF;
PIOS_DELAY_WaitmS(200);
sequenceLEDs();
// turn all the leds off
USB_LED_OFF;
LINK_LED_OFF;
RX_LED_OFF;
TX_LED_OFF;
// *************
// debug stuff
#if defined(PIOS_COM_DEBUG)
DEBUG_PRINTF("\r\n");
DEBUG_PRINTF("PipXtreme v%u.%u rebooted\r\n", version_major, version_minor);
#endif
// *************
// initialize the saved settings module
saved_settings_init();
// *************
// read the API mode pin
if (!GPIO_IN(API_MODE_PIN))
API_Mode = TRUE;
// *************
// read the 434/868/915 jumper options
if (!GPIO_IN(_868MHz_PIN) && !GPIO_IN(_915MHz_PIN)) saved_settings.frequency_band = freqBand_434MHz; // 434MHz band
else
if (!GPIO_IN(_868MHz_PIN) && GPIO_IN(_915MHz_PIN)) saved_settings.frequency_band = freqBand_868MHz; // 868MHz band
else
if ( GPIO_IN(_868MHz_PIN) && !GPIO_IN(_915MHz_PIN)) saved_settings.frequency_band = freqBand_915MHz; // 915MHz band
switch (saved_settings.frequency_band)
{
case freqBand_434MHz:
if (saved_settings.frequency_Hz == 0xffffffff)
{
saved_settings.frequency_Hz = 434000000;
saved_settings.min_frequency_Hz = 434000000 - 2000000;
saved_settings.max_frequency_Hz = 434000000 + 2000000;
}
if (saved_settings.max_rf_bandwidth == 0xffffffff)
{
// saved_settings.max_rf_bandwidth = 500;
// saved_settings.max_rf_bandwidth = 1000;
// saved_settings.max_rf_bandwidth = 2000;
// saved_settings.max_rf_bandwidth = 4000;
// saved_settings.max_rf_bandwidth = 8000;
// saved_settings.max_rf_bandwidth = 9600;
// saved_settings.max_rf_bandwidth = 16000;
// saved_settings.max_rf_bandwidth = 19200;
// saved_settings.max_rf_bandwidth = 24000;
// saved_settings.max_rf_bandwidth = 32000;
// saved_settings.max_rf_bandwidth = 64000;
saved_settings.max_rf_bandwidth = 128000;
// saved_settings.max_rf_bandwidth = 192000;
}
if (saved_settings.max_tx_power == 0xff)
{
// saved_settings.max_tx_power = 0; // +1dBm ... 1.25mW
// saved_settings.max_tx_power = 1; // +2dBm ... 1.6mW
// saved_settings.max_tx_power = 2; // +5dBm ... 3.16mW
// saved_settings.max_tx_power = 3; // +8dBm ... 6.3mW
saved_settings.max_tx_power = 4; // +11dBm .. 12.6mW
// saved_settings.max_tx_power = 5; // +14dBm .. 25mW
// saved_settings.max_tx_power = 6; // +17dBm .. 50mW
// saved_settings.max_tx_power = 7; // +20dBm .. 100mW
}
break;
case freqBand_868MHz:
if (saved_settings.frequency_Hz == 0xffffffff)
{
saved_settings.frequency_Hz = 868000000;
saved_settings.min_frequency_Hz = 868000000 - 10000000;
saved_settings.max_frequency_Hz = 868000000 + 10000000;
}
if (saved_settings.max_rf_bandwidth == 0xffffffff)
{
// saved_settings.max_rf_bandwidth = 500;
// saved_settings.max_rf_bandwidth = 1000;
// saved_settings.max_rf_bandwidth = 2000;
// saved_settings.max_rf_bandwidth = 4000;
// saved_settings.max_rf_bandwidth = 8000;
// saved_settings.max_rf_bandwidth = 9600;
// saved_settings.max_rf_bandwidth = 16000;
// saved_settings.max_rf_bandwidth = 19200;
// saved_settings.max_rf_bandwidth = 24000;
// saved_settings.max_rf_bandwidth = 32000;
// saved_settings.max_rf_bandwidth = 64000;
saved_settings.max_rf_bandwidth = 128000;
// saved_settings.max_rf_bandwidth = 192000;
}
if (saved_settings.max_tx_power == 0xff)
{
// saved_settings.max_tx_power = 0; // +1dBm ... 1.25mW
// saved_settings.max_tx_power = 1; // +2dBm ... 1.6mW
// saved_settings.max_tx_power = 2; // +5dBm ... 3.16mW
// saved_settings.max_tx_power = 3; // +8dBm ... 6.3mW
saved_settings.max_tx_power = 4; // +11dBm .. 12.6mW
// saved_settings.max_tx_power = 5; // +14dBm .. 25mW
// saved_settings.max_tx_power = 6; // +17dBm .. 50mW
// saved_settings.max_tx_power = 7; // +20dBm .. 100mW
}
break;
case freqBand_915MHz:
if (saved_settings.frequency_Hz == 0xffffffff)
{
saved_settings.frequency_Hz = 915000000;
saved_settings.min_frequency_Hz = 915000000 - 13000000;
saved_settings.max_frequency_Hz = 915000000 + 13000000;
}
if (saved_settings.max_rf_bandwidth == 0xffffffff)
{
// saved_settings.max_rf_bandwidth = 500;
// saved_settings.max_rf_bandwidth = 1000;
// saved_settings.max_rf_bandwidth = 2000;
// saved_settings.max_rf_bandwidth = 4000;
// saved_settings.max_rf_bandwidth = 8000;
// saved_settings.max_rf_bandwidth = 9600;
// saved_settings.max_rf_bandwidth = 16000;
// saved_settings.max_rf_bandwidth = 19200;
// saved_settings.max_rf_bandwidth = 24000;
// saved_settings.max_rf_bandwidth = 32000;
// saved_settings.max_rf_bandwidth = 64000;
saved_settings.max_rf_bandwidth = 128000;
// saved_settings.max_rf_bandwidth = 192000;
}
if (saved_settings.max_tx_power == 0xff)
{
// saved_settings.max_tx_power = 0; // +1dBm ... 1.25mW
// saved_settings.max_tx_power = 1; // +2dBm ... 1.6mW
// saved_settings.max_tx_power = 2; // +5dBm ... 3.16mW
// saved_settings.max_tx_power = 3; // +8dBm ... 6.3mW
saved_settings.max_tx_power = 4; // +11dBm .. 12.6mW
// saved_settings.max_tx_power = 5; // +14dBm .. 25mW
// saved_settings.max_tx_power = 6; // +17dBm .. 50mW
// saved_settings.max_tx_power = 7; // +20dBm .. 100mW
}
break;
default:
break;
}
if (serial_number_crc32 == 0x176C1EC6) saved_settings.destination_id = 0xA524A3B0; // modem 1, open a connection to modem 2
else
if (serial_number_crc32 == 0xA524A3B0) saved_settings.destination_id = 0x176C1EC6; // modem 2, open a connection to modem 1
// *************
processReset(); // Determine what caused the reset/reboot
// *************
// debug stuff
#if defined(PIOS_COM_DEBUG)
DEBUG_PRINTF("\r\n");
DEBUG_PRINTF("CPU flash size: %u\r\n", flash_size);
DEBUG_PRINTF("CPU serial number: %s %08X\r\n", serial_number_str, serial_number_crc32);
// DEBUG_PRINTF("Reset address: %08X\r\n", reset_addr);
if (!API_Mode)
DEBUG_PRINTF("TRANSPARENT mode\r\n");
else
DEBUG_PRINTF("API mode\r\n");
switch (saved_settings.frequency_band)
{
case freqBand_UNKNOWN: DEBUG_PRINTF("UNKNOWN band\r\n"); break;
case freqBand_434MHz: DEBUG_PRINTF("434MHz band\r\n"); break;
case freqBand_868MHz: DEBUG_PRINTF("868MHz band\r\n"); break;
case freqBand_915MHz: DEBUG_PRINTF("915MHz band\r\n"); break;
}
#endif
// *************
// initialize the RF module
init_RF_module();
// *************
// initialize the USB interface
#if defined(PIOS_INCLUDE_USB_HID)
// PIOS_USB_HID_Init(0); // this is not needed as it gets called by the com init routine .. thank you Ed!
#endif
// *************
saved_settings_save();
booting = FALSE;
// *************
ph_set_remote_serial_number(0, saved_settings.destination_id);
#if defined(PIOS_COM_DEBUG)
DEBUG_PRINTF("\r\n");
DEBUG_PRINTF("RF datarate: %dbps\r\n", ph_getDatarate());
DEBUG_PRINTF("RF frequency: %dHz\r\n", rfm22_getNominalCarrierFrequency());
DEBUG_PRINTF("RF TX power: %d\r\n", ph_getTxPower());
#endif
// *************
// Main executive loop
for (;;)
{
random32 = UpdateCRC32(random32, PIOS_DELAY_TIMER->CNT >> 8);
random32 = UpdateCRC32(random32, PIOS_DELAY_TIMER->CNT);
if (second_tick)
{
second_tick = FALSE;
// *************************
// display the up-time .. HH:MM:SS
// #if defined(PIOS_COM_DEBUG)
// int32_t _uptime_ms = uptime_ms;
// uint32_t _uptime_sec = _uptime_ms / 1000;
// DEBUG_PRINTF("Uptime: %02d:%02d:%02d.%03d\r\n", _uptime_sec / 3600, (_uptime_sec / 60) % 60, _uptime_sec % 60, _uptime_ms % 1000);
// #endif
// *************************
// process the Temperature
// if (temp_adc >= 0)
// {
// int32_t degress_C = temp_adc;
//
// #if defined(PIOS_COM_DEBUG)
// DEBUG_PRINTF("TEMP: %d %d\r\n", temp_adc, degress_C);
// #endif
// }
// *************************
// process the PSU voltage level
// if (psu_adc >= 0)
// {
// int32_t psu_mV = psu_adc * ADC_PSU_mV_SCALE;
//
// #if defined(PIOS_COM_DEBUG)
// DEBUG_PRINTF("PSU: %d, %dmV\r\n", psu_adc, psu_mV);
// #endif
// }
// *************************
// rfm22_setTxCarrierMode(); // TEST ONLY
}
rfm22_process(); // rf hardware layer processing
ph_process(); // packet handler processing
if (!API_Mode)
trans_process(); // tranparent local communication processing (serial port and usb port)
else
uavtalk_process(); // UAVTalk local communication processing (serial port and usb port)
// ******************
// TEST ONLY ... get/put data over the radio link .. speed testing .. comment out trans_process() and uavtalk_process() if testing with this
/*
int connection_index = 0;
if (ph_connected(connection_index))
{ // we have a connection to a remote modem
uint8_t buffer[128];
uint16_t num = ph_getData_used(connection_index); // number of bytes waiting for us to get
if (num > 0)
{ // their is data in the received buffer - fetch it
if (num > sizeof(buffer)) num = sizeof(buffer);
num = ph_getData(connection_index, buffer, num); // fetch the received data
}
// keep the tx buffer topped up
num = ph_putData_free(connection_index);
if (num > 0)
{ // their is space available in the transmit buffer - top it up
if (num > sizeof(buffer)) num = sizeof(buffer);
for (int16_t i = 0; i < num; i++) buffer[i] = i;
num = ph_putData(connection_index, buffer, num);
}
}
*/
// ******************
#if defined(USE_WATCHDOG)
processWatchdog(); // process the watchdog
#endif
}
// *************
// we should never arrive here
// disable all interrupts
PIOS_IRQ_Disable();
// turn off all leds
USB_LED_OFF;
LINK_LED_OFF;
RX_LED_OFF;
TX_LED_OFF;
PIOS_SYS_Reset();
while (1);
return 0;
}
// *****************************************************************************

View File

@ -0,0 +1,1579 @@
/**
******************************************************************************
*
* @file packet_handler.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief Modem packet handling routines
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
// ********
// We use 128-bit AES CBC encryption if encryption is enabled
// encrypted packet format
// 16-byte CBC .. 1st byte must not be zero
// 4-byte source id
// 4-byte destination id
// 1-byte packet type
// 1-byte tx sequence value
// 1-byte rx sequence value
// 1-byte data size
// 4-byte crc of entire packet not including CBC bytes
// unencrypted packet format
// 1-byte null byte .. set to zero to indicate packet is not encrypted
// 4-byte source id
// 4-byte destination id
// 1-byte packet type
// 1-byte tx sequence value
// 1-byte rx sequence value
// 1-byte data size
// 4-byte crc of entire packet not including the null byte
// ********
#include <string.h> // memmove
#include "main.h"
#include "rfm22b.h"
#include "fifo_buffer.h"
#include "aes.h"
#include "crc.h"
#include "saved_settings.h"
#include "packet_handler.h"
#if defined(PIOS_COM_DEBUG)
// #define PACKET_DEBUG
#endif
// *****************************************************************************
#define PH_FIFO_BUFFER_SIZE 2048 // FIFO buffer size
// *****************************************************************************
#define AES_BLOCK_SIZE 16 // AES encryption does it in 16-byte blocks ONLY
// default aes 128-bit encryption key
const uint8_t default_aes_key[AES_BLOCK_SIZE] = {0x65, 0x3b, 0x71, 0x89, 0x4a, 0xf4, 0xc8, 0xcb, 0x18, 0xd4, 0x9b, 0x4d, 0x4a, 0xbe, 0xc8, 0x37};
// *****************************************************************************
#define RETRY_RECONNECT_COUNT 60 // if transmission retries this many times then reset the link to the remote modem
#define PACKET_TYPE_DATA_COMP_BIT 0x80 // data compressed bit. if set then the data in the packet is compressed
#define PACKET_TYPE_MASK 0x7f // packet type mask
enum {
packet_type_none = 0,
packet_type_connect = 1, // for requesting a connection
packet_type_connect_ack = 2, // ack
packet_type_disconnect = 3, // to tell the other modem they cannot connect to us
packet_type_data = 4, // data packet (packet contains user data)
packet_type_data_ack = 5, // ack
packet_type_ready = 6, // tells the other modem we are ready to accept more data
packet_type_ready_ack = 7, // ack
packet_type_notready = 8, // tells the other modem we're not ready to accept more data - we can also send user data in this packet type
packet_type_notready_ack = 9, // ack
packet_type_datarate = 10, // for changing the RF data rate
packet_type_datarate_ack = 11, // ack
packet_type_ping = 12, // used to check link is still up
packet_type_pong = 13, // ack
packet_type_adjust_tx_pwr = 14, // used to ask the other modem to adjust it's tx power
packet_type_adjust_tx_pwr_ack = 15 // ack
};
#define BROADCAST_ADDR 0xffffffff
//#pragma pack(push)
//#pragma pack(1)
typedef struct
{
uint32_t source_id;
uint32_t destination_id;
uint8_t type;
uint8_t tx_seq;
uint8_t rx_seq;
uint8_t data_size;
uint32_t crc;
} __attribute__((__packed__)) t_packet_header;
// this structure must be a multiple of 'AES_BLOCK_SIZE' bytes in size and no more than 255 bytes in size
typedef struct
{
uint8_t cbc[AES_BLOCK_SIZE]; // AES encryption Cipher-Block-Chaining key .. 1st byte must not be zero - to indicate the packet is encrypted
t_packet_header header;
uint8_t data[240 - sizeof(t_packet_header) - AES_BLOCK_SIZE];
} __attribute__((__packed__)) t_encrypted_packet;
// this structure must be no more than 255 bytes in size (255 = the maximum packet size)
typedef struct
{
uint8_t null_byte; // this must be set to zero - to indicate the packet is unencrypted
t_packet_header header;
uint8_t data[255 - sizeof(t_packet_header) - 1];
} __attribute__((__packed__)) t_unencrypted_packet;
//#pragma pack(pop)
// *****************************************************************************
// link state for each remote connection
enum { link_disconnected = 0,
link_connecting,
link_connected
};
typedef struct
{
uint32_t serial_number; // their serial number
uint8_t tx_buffer[PH_FIFO_BUFFER_SIZE] __attribute__ ((aligned(4)));
t_fifo_buffer tx_fifo_buffer; // holds the data to be transmitted to the other modem
uint8_t rx_buffer[PH_FIFO_BUFFER_SIZE] __attribute__ ((aligned(4)));
t_fifo_buffer rx_fifo_buffer; // holds the data received from the other modem
uint8_t link_state; // holds our current RF link state
uint8_t tx_sequence; // incremented with each data packet transmitted, sent in every packet transmitted
uint8_t tx_sequence_data_size; // the size of data we sent in our last packet
uint8_t rx_sequence; // incremented with each data packet received contain data, sent in every packet transmitted
volatile uint16_t tx_packet_timer; // ms .. used for packet timing
uint16_t tx_retry_time_slots; // add's some random packet transmission timing - to try to prevent transmission collisions
uint16_t tx_retry_time_slot_len; // ms .. " " "
uint16_t tx_retry_time; // ms .. " " "
uint16_t tx_retry_counter; // incremented on each transmission, reset back to '0' when we receive an ack to our transmission
volatile uint16_t data_speed_timer; // used for calculating the transmit/receive data rate
volatile uint32_t tx_data_speed_count; // incremented with the number of data bits we send in our transmit packets
volatile uint32_t tx_data_speed; // holds the number of data bits we have sent each second
volatile uint32_t rx_data_speed_count; // incremented with the number of data bits we send in our transmit packets
volatile uint32_t rx_data_speed; // holds the number of data bits we have received each second
uint16_t ping_time; // ping timer
bool pinging; // TRUE if we are doing a ping test with the other modem - to check if it is still present
bool rx_not_ready_mode; // TRUE if we have told the other modem we cannot receive data (due to buffer filling up).
// we set it back to FALSE when our received buffer starts to empty
volatile int16_t ready_to_send_timer; // ms .. used to hold off packet transmission to wait a bit for data to mount up for transmission (improves data thru-put speed)
volatile int32_t not_ready_timer; // ms .. >= 0 while we have been asked not to send anymore data to the other modem, -1 when we are allowed to send data
bool send_encrypted; // TRUE if we are to AES encrypt in every packet we transmit
int16_t rx_rssi_dBm; // the strength of the received packet
int32_t rx_afc_Hz; // the frequency offset of the received packet
} t_connection;
// *****************************************************************************
uint32_t our_serial_number = 0; // our serial number
t_connection connection[PH_MAX_CONNECTIONS]; // holds each connection state
uint8_t aes_key[AES_BLOCK_SIZE] __attribute__ ((aligned(4))); // holds the aes encryption key - the same for ALL connections
uint8_t dec_aes_key[AES_BLOCK_SIZE] __attribute__ ((aligned(4))); // holds the pre-calculated decryption key
uint8_t enc_cbc[AES_BLOCK_SIZE] __attribute__ ((aligned(4))); // holds the tx aes cbc bytes
uint8_t ph_tx_buffer[256] __attribute__ ((aligned(4))); // holds the transmit packet
uint8_t ph_rx_buffer[256] __attribute__ ((aligned(4))); // holds the received packet
int16_t rx_rssi_dBm;
int16_t rx_afc_Hz;
// *****************************************************************************
// return TRUE if we are connected to the remote modem
bool ph_connected(const int connection_index)
{
if (connection_index < 0 || connection_index >= PH_MAX_CONNECTIONS)
return FALSE;
t_connection *conn = &connection[connection_index];
return (conn->link_state == link_connected);
}
// *****************************************************************************
// public tx buffer functions
uint16_t ph_putData_free(const int connection_index)
{ // return the free space size
if (connection_index < 0 || connection_index >= PH_MAX_CONNECTIONS)
return 0;
return fifoBuf_getFree(&connection[connection_index].tx_fifo_buffer);
}
uint16_t ph_putData(const int connection_index, const void *data, uint16_t len)
{ // add data to our tx buffer to be sent
if (connection_index < 0 || connection_index >= PH_MAX_CONNECTIONS)
return 0;
return fifoBuf_putData(&connection[connection_index].tx_fifo_buffer, data, len);
}
// *****************************************************************************
// public rx buffer functions
uint16_t ph_getData_used(const int connection_index)
{ // return the number of bytes available in the rx buffer
if (connection_index < 0 || connection_index >= PH_MAX_CONNECTIONS)
return 0;
return fifoBuf_getUsed(&connection[connection_index].rx_fifo_buffer);
}
uint16_t ph_getData(const int connection_index, void *data, uint16_t len)
{ // get data from our rx buffer
if (connection_index < 0 || connection_index >= PH_MAX_CONNECTIONS)
return 0;
return fifoBuf_getData(&connection[connection_index].rx_fifo_buffer, data, len);
}
// *****************************************************************************
// start a connection to another modem
int ph_startConnect(int connection_index, uint32_t sn)
{
random32 = UpdateCRC32(random32, 0xff);
if (connection_index < 0 || connection_index >= PH_MAX_CONNECTIONS)
return -1;
t_connection *conn = &connection[connection_index];
if (sn != 0 && sn == our_serial_number)
return -2; // same as our own
if (sn == BROADCAST_ADDR)
{
return -3;
}
LINK_LED_OFF;
conn->link_state = link_disconnected;
conn->serial_number = sn;
conn->tx_sequence = 0;
conn->tx_sequence_data_size = 0;
conn->rx_sequence = 0;
// fifoBuf_init(&conn->tx_fifo_buffer, conn->tx_buffer, PH_FIFO_BUFFER_SIZE);
// fifoBuf_init(&conn->rx_fifo_buffer, conn->rx_buffer, PH_FIFO_BUFFER_SIZE);
conn->tx_packet_timer = 0;
conn->tx_retry_time_slots = 5;
uint32_t ms = 1280000ul / rfm22_getDatarate();
if (ms < 10) ms = 10;
else
if (ms > 32000) ms = 32000;
conn->tx_retry_time_slot_len = ms;
conn->tx_retry_time = conn->tx_retry_time_slot_len * 4 + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len * 4;
conn->tx_retry_counter = 0;
conn->data_speed_timer = 0;
conn->tx_data_speed_count = 0;
conn->tx_data_speed = 0;
conn->rx_data_speed_count = 0;
conn->rx_data_speed = 0;
conn->ping_time = 7000 + (random32 % 100) * 10;
conn->pinging = false;
conn->rx_not_ready_mode = false;
conn->ready_to_send_timer = -1;
conn->not_ready_timer = -1;
// conn->send_encrypted = true;
conn->send_encrypted = false;
conn->rx_rssi_dBm = -200;
conn->rx_afc_Hz = 0;
conn->link_state = link_connecting;
return connection_index;
}
// *****************************************************************************
// transmit a packet
bool ph_sendPacket(int connection_index, bool encrypt, uint8_t packet_type, bool send_immediately)
{
uint8_t key[AES_BLOCK_SIZE];
t_connection *conn = NULL;
// ***********
t_encrypted_packet *encrypted_packet = (t_encrypted_packet*)&ph_tx_buffer; // point to the tx buffer
t_unencrypted_packet *unencrypted_packet = (t_unencrypted_packet*)&ph_tx_buffer; // point to the tx buffer
t_packet_header *header;
uint8_t *data;
uint16_t max_data_size;
if (encrypt)
{
header = (t_packet_header *)&encrypted_packet->header;
data = (uint8_t *)&encrypted_packet->data;
max_data_size = sizeof(encrypted_packet->data);
}
else
{
header = (t_packet_header *)&unencrypted_packet->header;
data = (uint8_t *)&unencrypted_packet->data;
max_data_size = sizeof(unencrypted_packet->data);
}
// ***********
if (!rfm22_txReady())
return false;
if ((packet_type & PACKET_TYPE_MASK) == packet_type_none)
return false;
if (connection_index >= PH_MAX_CONNECTIONS)
return false;
if (connection_index >= 0)
conn = (t_connection *)&connection[connection_index];
else
return false;
// ******************
// stuff
uint8_t pack_type = packet_type & PACKET_TYPE_MASK;
bool data_packet = (pack_type == packet_type_data || pack_type == packet_type_notready);
// ******************
// calculate how many user data bytes we are going to add to the packet
uint16_t data_size = 0;
if (data_packet && conn)
{ // we're adding user data to the packet
data_size = fifoBuf_getUsed(&connection[connection_index].tx_fifo_buffer); // the number of data bytes waiting to be sent
if (data_size > max_data_size)
data_size = max_data_size;
if (conn->tx_sequence_data_size > 0)
{ // we are re-sending data the same data
if (data_size > conn->tx_sequence_data_size)
data_size = conn->tx_sequence_data_size;
}
}
// ******************
// calculate the total packet size (including null data bytes if we have to add null data byte in AES encrypted packets)
uint32_t packet_size;
if (encrypt)
{
packet_size = AES_BLOCK_SIZE + sizeof(t_packet_header) + data_size;
// total packet size must be a multiple of 'AES_BLOCK_SIZE' bytes - aes encryption works on 16-byte blocks
packet_size = (packet_size + (AES_BLOCK_SIZE - 1)) & ~(AES_BLOCK_SIZE - 1);
}
else
{
packet_size = 1 + sizeof(t_packet_header) + data_size;
}
// ******************
// construct the packets entire header
if (encrypt)
{
memmove(key, aes_key, sizeof(key)); // fetch the encryption key
aes_encrypt_cbc_128(enc_cbc, key, NULL); // help randomize the CBC bytes
// ensure the 1st byte is not zero - to indicate this packet is encrypted
while (enc_cbc[0] == 0)
{
random32 = UpdateCRC32(random32, 0xff);
enc_cbc[0] ^= random32;
}
memmove(encrypted_packet->cbc, enc_cbc, AES_BLOCK_SIZE); // copy the AES CBC bytes into the packet
}
else
unencrypted_packet->null_byte = 0; // packet is not encrypted
header->source_id = our_serial_number; // our serial number
// header->destination_id = BROADCAST_ADDR; // broadcast packet
header->destination_id = conn->serial_number; // the other modems serial number
header->type = packet_type; // packet type
header->tx_seq = conn->tx_sequence; // our TX sequence number
header->rx_seq = conn->rx_sequence; // our RX sequence number
header->data_size = data_size; // the number of user data bytes in the packet
header->crc = 0; // the CRC of the header and user data bytes
// ******************
// add the user data to the packet
if (data_packet)
{ // we're adding user data to the packet
fifoBuf_getDataPeek(&connection[connection_index].tx_fifo_buffer, data, data_size);
if (encrypt)
{ // zero unused bytes
if (data_size < max_data_size)
memset(data + data_size, 0, max_data_size - data_size);
}
conn->tx_sequence_data_size = data_size; // remember how much data we are sending in this packet
}
// ******************
// complete the packet header by adding the CRC
if (encrypt)
header->crc = UpdateCRC32Data(0xffffffff, header, packet_size - AES_BLOCK_SIZE);
else
header->crc = UpdateCRC32Data(0xffffffff, header, packet_size - 1);
// ******************
// encrypt the packet
if (encrypt)
{ // encrypt the packet .. 'AES_BLOCK_SIZE' bytes at a time
uint8_t *p = (uint8_t *)encrypted_packet;
// encrypt the cbc
memmove(key, aes_key, sizeof(key)); // fetch the encryption key
aes_encrypt_cbc_128(p, key, NULL); // encrypt block of data (the CBC bytes)
p += AES_BLOCK_SIZE;
// encrypt the rest of the packet
for (uint16_t i = AES_BLOCK_SIZE; i < packet_size; i += AES_BLOCK_SIZE)
{
memmove(key, aes_key, sizeof(key)); // fetch the encryption key
aes_encrypt_cbc_128(p, key, enc_cbc); // encrypt block of data
p += AES_BLOCK_SIZE;
}
}
// ******************
// send the packet
int32_t res = rfm22_sendData(&ph_tx_buffer, packet_size, send_immediately);
// ******************
if (data_size > 0 && conn->tx_retry_counter == 0)
conn->tx_data_speed_count += data_size * 8; // + the number of data bits we just sent .. used for calculating the transmit data rate
// ******************
// debug stuff
#if defined(PACKET_DEBUG)
DEBUG_PRINTF("T-PACK ");
switch (pack_type)
{
case packet_type_none: DEBUG_PRINTF("none"); break;
case packet_type_connect: DEBUG_PRINTF("connect"); break;
case packet_type_connect_ack: DEBUG_PRINTF("connect_ack"); break;
case packet_type_disconnect: DEBUG_PRINTF("disconnect"); break;
case packet_type_data: DEBUG_PRINTF("data"); break;
case packet_type_data_ack: DEBUG_PRINTF("data_ack"); break;
case packet_type_ready: DEBUG_PRINTF("ready"); break;
case packet_type_ready_ack: DEBUG_PRINTF("ready_ack"); break;
case packet_type_notready: DEBUG_PRINTF("notready"); break;
case packet_type_notready_ack: DEBUG_PRINTF("notready_ack"); break;
case packet_type_datarate: DEBUG_PRINTF("datarate"); break;
case packet_type_datarate_ack: DEBUG_PRINTF("datarate_ack"); break;
case packet_type_ping: DEBUG_PRINTF("ping"); break;
case packet_type_pong: DEBUG_PRINTF("pong"); break;
case packet_type_adjust_tx_pwr: DEBUG_PRINTF("packet_type_adjust_tx_pwr"); break;
case packet_type_adjust_tx_pwr_ack: DEBUG_PRINTF("packet_type_adjust_tx_pwr_ack"); break;
default: DEBUG_PRINTF("UNKNOWN [%d]", pack_type); break;
}
DEBUG_PRINTF(" tseq:%d rseq:%d", conn->tx_sequence, conn->rx_sequence);
DEBUG_PRINTF(" drate:%dbps", conn->tx_data_speed);
if (data_size > 0) DEBUG_PRINTF(" data_size:%d", data_size);
if (conn->tx_retry_counter > 0) DEBUG_PRINTF(" retry:%d", conn->tx_retry_counter);
DEBUG_PRINTF("\r\n");
#endif
// ******************
switch (pack_type)
{
case packet_type_connect:
case packet_type_disconnect:
case packet_type_data:
case packet_type_ready:
case packet_type_notready:
case packet_type_datarate:
case packet_type_ping:
case packet_type_adjust_tx_pwr:
if (conn->tx_retry_counter < 0xffff)
conn->tx_retry_counter++;
break;
case packet_type_connect_ack:
case packet_type_data_ack:
case packet_type_ready_ack:
case packet_type_notready_ack:
case packet_type_datarate_ack:
case packet_type_pong:
case packet_type_adjust_tx_pwr_ack:
break;
case packet_type_none:
break;
}
return (res >= packet_size);
}
// *****************************************************************************
void ph_processPacket2(bool was_encrypted, t_packet_header *header, uint8_t *data)
{ // process the received decrypted error-free packet
USB_LED_TOGGLE; // TEST ONLY
// ***********
// fetch the data compressed bit
bool compressed_data = (header->type & PACKET_TYPE_DATA_COMP_BIT) != 0;
// fetch the packet type
uint8_t packet_type = header->type & PACKET_TYPE_MASK;
// fetch the number of data bytes in the packet
uint16_t data_size = header->data_size;
// update the ramdon number
random32 = UpdateCRC32(random32, 0xff);
// *********************
// debug stuff
/*
#if defined(PACKET_DEBUG)
if (data_size > 0)
{
DEBUG_PRINTF("rx packet:");
for (uint16_t i = 0; i < data_size; i++)
DEBUG_PRINTF(" %u", data[i]);
DEBUG_PRINTF("\r\n");
}
#endif
*/
// ***********
// debug stuff
#if defined(PACKET_DEBUG)
DEBUG_PRINTF("R-PACK ");
switch (packet_type)
{
case packet_type_none: DEBUG_PRINTF("none"); break;
case packet_type_connect: DEBUG_PRINTF("connect"); break;
case packet_type_connect_ack: DEBUG_PRINTF("connect_ack"); break;
case packet_type_disconnect: DEBUG_PRINTF("disconnect"); break;
case packet_type_data: DEBUG_PRINTF("data"); break;
case packet_type_data_ack: DEBUG_PRINTF("data_ack"); break;
case packet_type_ready: DEBUG_PRINTF("ready"); break;
case packet_type_ready_ack: DEBUG_PRINTF("ready_ack"); break;
case packet_type_notready: DEBUG_PRINTF("notready"); break;
case packet_type_notready_ack: DEBUG_PRINTF("notready_ack"); break;
case packet_type_datarate: DEBUG_PRINTF("datarate"); break;
case packet_type_datarate_ack: DEBUG_PRINTF("datarate_ack"); break;
case packet_type_ping: DEBUG_PRINTF("ping"); break;
case packet_type_pong: DEBUG_PRINTF("pong"); break;
case packet_type_adjust_tx_pwr: DEBUG_PRINTF("packet_type_adjust_tx_pwr"); break;
case packet_type_adjust_tx_pwr_ack: DEBUG_PRINTF("packet_type_adjust_tx_pwr_ack"); break;
default: DEBUG_PRINTF("UNKNOWN [%d]", packet_type); break;
}
DEBUG_PRINTF(" tseq-%d rseq-%d", header->tx_seq, header->rx_seq);
// DEBUG_PRINTF(" drate:%dbps", conn->rx_data_speed);
if (data_size > 0) DEBUG_PRINTF(" data_size:%d", data_size);
DEBUG_PRINTF(" %ddBm", rx_rssi_dBm);
DEBUG_PRINTF(" %dHz", rx_afc_Hz);
DEBUG_PRINTF("\r\n");
#endif
// *********************
if (header->source_id == our_serial_number)
return; // it's our own packet .. ignore it
if (header->destination_id == BROADCAST_ADDR)
{ // it's a broadcast packet
// todo:
return;
}
if (header->destination_id != our_serial_number)
return; // the packet is not meant for us
// *********************
// find out which remote connection this packet is from
int connection_index = 0;
while (connection_index < PH_MAX_CONNECTIONS)
{
uint32_t sn = connection[connection_index].serial_number;
if (sn != 0)
{ // connection used
if (header->source_id == sn)
break; // found it
}
connection_index++;
}
if (connection_index >= PH_MAX_CONNECTIONS)
{ // the packet is from an unknown source ID (unknown modem)
if (packet_type != packet_type_none)
{ // send a disconnect packet back to them
// ph_sendPacket(-1, was_encrypted, packet_type_disconnect, true);
}
return;
}
t_connection *conn = &connection[connection_index];
// ***********
conn->rx_rssi_dBm = rx_rssi_dBm; // remember the packets signal strength
conn->rx_afc_Hz = rx_afc_Hz; // remember the packets frequency offset
// ***********
// decompress the data
if (compressed_data && data_size > 0)
{
// todo:
}
// ***********
if (packet_type == packet_type_none)
return;
if (packet_type == packet_type_disconnect)
{
conn->link_state = link_disconnected;
LINK_LED_OFF;
return;
}
if (packet_type == packet_type_connect)
{
LINK_LED_ON;
// fifoBuf_init(&conn->tx_fifo_buffer, conn->tx_buffer, PH_FIFO_BUFFER_SIZE);
// fifoBuf_init(&conn->rx_fifo_buffer, conn->rx_buffer, PH_FIFO_BUFFER_SIZE);
conn->tx_packet_timer = 0;
conn->tx_retry_counter = 0;
conn->tx_retry_time = conn->tx_retry_time_slot_len + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len;
conn->rx_sequence = header->tx_seq;
conn->tx_sequence = 0;
conn->tx_sequence_data_size = 0;
conn->data_speed_timer = 0;
conn->tx_data_speed_count = 0;
conn->tx_data_speed = 0;
conn->rx_data_speed_count = 0;
conn->rx_data_speed = 0;
conn->ping_time = 7000 + (random32 % 100) * 10;
conn->pinging = false;
conn->rx_not_ready_mode = false;
conn->ready_to_send_timer = -1;
conn->not_ready_timer = -1;
conn->link_state = link_connected;
// send an ack back
if (ph_sendPacket(connection_index, conn->send_encrypted, packet_type_connect_ack, true))
{
conn->tx_packet_timer = 0;
}
return;
}
if (packet_type == packet_type_connect_ack)
{
LINK_LED_ON;
if (conn->link_state != link_connecting)
{ // reset the link
ph_set_remote_serial_number(connection_index, conn->serial_number);
return;
}
conn->tx_packet_timer = 0;
conn->tx_retry_counter = 0;
conn->tx_retry_time = conn->tx_retry_time_slot_len + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len;
conn->rx_sequence = header->tx_seq;
conn->tx_sequence = 0;
conn->tx_sequence_data_size = 0;
conn->data_speed_timer = 0;
conn->tx_data_speed_count = 0;
conn->tx_data_speed = 0;
conn->rx_data_speed_count = 0;
conn->rx_data_speed = 0;
conn->ping_time = 7000 + (random32 % 100) * 10;
conn->pinging = false;
conn->rx_not_ready_mode = false;
conn->ready_to_send_timer = -1;
conn->not_ready_timer = -1;
conn->link_state = link_connected;
return;
}
if (conn->link_state == link_connecting)
{ // we are trying to connect to them .. reply with a connect request packet
if (ph_sendPacket(connection_index, conn->send_encrypted, packet_type_connect, true))
{
conn->tx_packet_timer = 0;
conn->tx_retry_time = conn->tx_retry_time_slot_len * 4 + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len * 4;
}
return;
}
if (conn->link_state != link_connected)
{ // they have sent us a packet when we are not in a connected state - start a connection
ph_startConnect(connection_index, conn->serial_number);
return;
}
// check to make sure it's a wanted packet type
switch (packet_type)
{
case packet_type_data:
case packet_type_data_ack:
case packet_type_ready:
case packet_type_ready_ack:
case packet_type_notready:
case packet_type_notready_ack:
case packet_type_datarate:
case packet_type_datarate_ack:
case packet_type_ping:
case packet_type_pong:
case packet_type_adjust_tx_pwr:
case packet_type_adjust_tx_pwr_ack:
break;
default:
return;
}
if ((conn->tx_sequence_data_size > 0) && (header->rx_seq == (uint8_t)(conn->tx_sequence + 1)))
{ // they received our last data packet
// remove the data we have sent and they have acked
fifoBuf_removeData(&conn->tx_fifo_buffer, conn->tx_sequence_data_size);
conn->tx_sequence++;
conn->tx_retry_counter = 0;
conn->tx_sequence_data_size = 0;
conn->not_ready_timer = -1; // stop timer
}
uint16_t size = fifoBuf_getUsed(&conn->tx_fifo_buffer); // the size of data waiting to be sent
if (packet_type == packet_type_data || packet_type == packet_type_data_ack)
{
if (packet_type == packet_type_data && header->tx_seq == conn->rx_sequence)
{ // the packet number is what we expected
if (data_size > 0)
{ // save the data
conn->rx_data_speed_count += data_size * 8; // + the number of data bits we just received
uint16_t num = fifoBuf_getFree(&conn->rx_fifo_buffer);
if (num < data_size)
{ // error .. we don't have enough space left in our fifo buffer to save the data .. discard it and tell them to hold off a sec
// conn->rx_not_ready_mode = true;
}
else
{ // save the received data into our fifo buffer
fifoBuf_putData(&conn->rx_fifo_buffer, data, data_size);
conn->rx_sequence++;
conn->rx_not_ready_mode = false;
}
}
}
if (size >= 200 || (conn->ready_to_send_timer >= 10 && size > 0) || (conn->tx_sequence_data_size > 0 && size > 0))
{ // send data
uint8_t pack_type = packet_type_data;
if (conn->rx_not_ready_mode)
pack_type = packet_type_notready;
if (ph_sendPacket(connection_index, conn->send_encrypted, pack_type, true))
{
conn->tx_packet_timer = 0;
conn->tx_retry_time = conn->tx_retry_time_slot_len + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len;
return;
}
}
if (packet_type == packet_type_data)
{ // send an ack back
uint8_t pack_type = packet_type_data_ack;
if (conn->rx_not_ready_mode)
pack_type = packet_type_notready_ack;
if (ph_sendPacket(connection_index, conn->send_encrypted, pack_type, true))
{
conn->tx_packet_timer = 0;
conn->tx_retry_time = conn->tx_retry_time_slot_len + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len;
return;
}
}
return;
}
if (packet_type == packet_type_ready)
{
conn->not_ready_timer = -1; // stop timer
// send an ack back
if (ph_sendPacket(connection_index, conn->send_encrypted, packet_type_ready_ack, true))
{
conn->tx_packet_timer = 0;
conn->tx_retry_time = conn->tx_retry_time_slot_len * 4 + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len * 4;
return;
}
return;
}
if (packet_type == packet_type_ready_ack)
{
conn->rx_not_ready_mode = false;
return;
}
if (packet_type == packet_type_notready)
{
// conn->not_ready_timer = 0; // start timer
if (header->tx_seq == conn->rx_sequence)
{ // the packet number is what we expected
if (data_size > 0)
{ // save the data
conn->rx_data_speed_count += data_size * 8; // + the number of data bits we just received
uint16_t num = fifoBuf_getFree(&conn->rx_fifo_buffer);
if (num < data_size)
{ // error .. we don't have enough space left in our fifo buffer to save the data .. discard it and tell them to hold off a sec
// conn->rx_not_ready_mode = true;
}
else
{ // save the received data into our fifo buffer
fifoBuf_putData(&conn->rx_fifo_buffer, data, data_size);
conn->rx_sequence++;
conn->rx_not_ready_mode = false;
}
}
}
// send an ack back
if (ph_sendPacket(connection_index, conn->send_encrypted, packet_type_notready_ack, true))
{
conn->tx_packet_timer = 0;
conn->tx_retry_time = conn->tx_retry_time_slot_len * 4 + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len * 4;
return;
}
return;
}
if (packet_type == packet_type_notready_ack)
{
return;
}
if (packet_type == packet_type_ping)
{ // send a pong back
if (ph_sendPacket(connection_index, conn->send_encrypted, packet_type_pong, true))
{
conn->tx_packet_timer = 0;
conn->tx_retry_time = conn->tx_retry_time_slot_len + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len;
}
return;
}
if (packet_type == packet_type_pong)
{
if (conn->pinging)
{
conn->pinging = false;
conn->tx_retry_counter = 0;
}
return;
}
if (packet_type == packet_type_datarate)
{
// send an ack back
if (ph_sendPacket(connection_index, conn->send_encrypted, packet_type_datarate_ack, true))
{
conn->tx_packet_timer = 0;
conn->tx_retry_time = conn->tx_retry_time_slot_len + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len;
}
return;
}
if (packet_type == packet_type_datarate_ack)
{
return;
}
if (packet_type == packet_type_adjust_tx_pwr)
{
// send an ack back
if (ph_sendPacket(connection_index, conn->send_encrypted, packet_type_adjust_tx_pwr_ack, true))
{
conn->tx_packet_timer = 0;
conn->tx_retry_time = conn->tx_retry_time_slot_len + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len;
}
return;
}
if (packet_type == packet_type_adjust_tx_pwr_ack)
{
return;
}
// *********************
}
void ph_processRxPacket(void)
{
uint32_t crc1, crc2;
uint8_t key[AES_BLOCK_SIZE];
register uint8_t *p;
// ***********
// fetch the received packet
uint16_t packet_size = rfm22_receivedLength();
if (packet_size == 0)
return; // nothing received
if (packet_size > sizeof(ph_rx_buffer))
{ // packet too big .. discard it
rfm22_receivedDone();
return;
}
rx_rssi_dBm = rfm22_receivedRSSI(); // fetch the packets signal stength
rx_afc_Hz = rfm22_receivedAFCHz(); // fetch the packets frequency offset
// copy the received packet into our own buffer
memmove(ph_rx_buffer, rfm22_receivedPointer(), packet_size);
rfm22_receivedDone(); // the received packet has been saved
// *********************
// if the 1st byte in the packet is not zero, then the packet is encrypted
bool encrypted = (ph_rx_buffer[0] != 0);
// ***********
t_encrypted_packet *encrypted_packet = (t_encrypted_packet *)&ph_rx_buffer; // point to the rx buffer
t_unencrypted_packet *unencrypted_packet = (t_unencrypted_packet *)&ph_rx_buffer; // point to the rx buffer
t_packet_header *header;
uint8_t *data;
uint16_t min_packet_size;
uint16_t max_data_size;
if (encrypted)
{
header = (t_packet_header *)&encrypted_packet->header;
data = (uint8_t *)&encrypted_packet->data;
min_packet_size = AES_BLOCK_SIZE + sizeof(t_packet_header);
max_data_size = sizeof(encrypted_packet->data);
}
else
{
header = (t_packet_header *)&unencrypted_packet->header;
data = (uint8_t *)&unencrypted_packet->data;
min_packet_size = 1 + sizeof(t_packet_header);
max_data_size = sizeof(unencrypted_packet->data);
}
if (packet_size < min_packet_size)
{ // packet too small .. discard it
return;
}
random32 = UpdateCRC32(random32 ^ header->crc, 0xff); // help randomize the random number
// *********************
// help to randomize the tx aes cbc bytes by using the received packet
p = (uint8_t *)&ph_rx_buffer;
for (uint16_t i = 0; i < packet_size; i += AES_BLOCK_SIZE)
{
for (int j = AES_BLOCK_SIZE - 1; j >= 0; j--)
enc_cbc[j] ^= *p++;
}
// *********************
// check the packet size
if (encrypted)
{
if ((packet_size & (AES_BLOCK_SIZE - 1)) != 0)
return; // packet must be a multiple of 'AES_BLOCK_SIZE' bytes in length - for the aes decryption
}
// *********************
// decrypt the packet
if (encrypted)
{
p = (uint8_t *)encrypted_packet; // point to the received packet
// decrypt the cbc
memmove(key, (void *)dec_aes_key, sizeof(key)); // fetch the decryption key
aes_decrypt_cbc_128(p, key, NULL); // decrypt the cbc bytes
p += AES_BLOCK_SIZE;
// decrypt the rest of the packet
for (uint16_t i = AES_BLOCK_SIZE; i < packet_size; i += AES_BLOCK_SIZE)
{
memmove(key, (void *)dec_aes_key, sizeof(key)); // fetch the decryption key
aes_decrypt_cbc_128(p, key, (void *)encrypted_packet->cbc);
p += AES_BLOCK_SIZE;
}
}
// *********************
#if defined(PACKET_DEBUG)
DEBUG_PRINTF("rx packet: ");
DEBUG_PRINTF("%s", encrypted ? "encrypted " : "unencrypted");
if (encrypted)
{
for (int i = 0; i < AES_BLOCK_SIZE; i++)
DEBUG_PRINTF("%02X", encrypted_packet->cbc[i]);
}
DEBUG_PRINTF(" %08X %08X %u %u %u %u %08X\r\n",
header->source_id,
header->destination_id,
header->type,
header->tx_seq,
header->rx_seq,
header->data_size,
header->crc);
if (header->data_size > 0)
{
DEBUG_PRINTF("rx packet [%u]: ", header->data_size);
for (int i = 0; i < header->data_size; i++)
DEBUG_PRINTF("%02X", data[i]);
DEBUG_PRINTF("\r\n");
}
#endif
// *********************
uint32_t data_size = header->data_size;
if (packet_size < (min_packet_size + data_size))
return; // packet too small
#if defined(PACKET_DEBUG)
// DEBUG_PRINTF("rx packet size: %d\r\n", packet_size);
#endif
// *********************
// check the packet is error free
crc1 = header->crc;
header->crc = 0;
if (encrypted)
crc2 = UpdateCRC32Data(0xffffffff, header, packet_size - AES_BLOCK_SIZE);
else
crc2 = UpdateCRC32Data(0xffffffff, header, packet_size - 1);
if (crc1 != crc2)
{ // corrupt packet
#if defined(PACKET_DEBUG)
if (encrypted)
DEBUG_PRINTF("ENC-R-PACK corrupt %08X %08X\r\n", crc1, crc2);
else
DEBUG_PRINTF("R-PACK corrupt %08X %08X\r\n", crc1, crc2);
#endif
return;
}
// *********************
// process the data
ph_processPacket2(encrypted, header, data);
// *********************
}
// *****************************************************************************
// do all the link/packet handling stuff - request connection/disconnection, send data, acks etc
void ph_processLinks(int connection_index)
{
if (connection_index < 0 || connection_index >= PH_MAX_CONNECTIONS)
return;
random32 = UpdateCRC32(random32, 0xff);
t_connection *conn = &connection[connection_index];
bool canTx = (!rfm22_transmitting() && rfm22_channelIsClear());// TRUE is we are can transmit
bool timeToRetry = (rfm22_txReady() && conn->tx_packet_timer >= conn->tx_retry_time);
bool tomanyRetries = (conn->tx_retry_counter >= RETRY_RECONNECT_COUNT);
switch (conn->link_state)
{
case link_disconnected:
if (!canTx)
{
conn->tx_packet_timer = 0;
break;
}
if (!rfm22_txReady() || conn->tx_packet_timer < 60000)
break;
if (our_serial_number != 0 && conn->serial_number != 0)
{ // try to reconnect with the remote modem
ph_startConnect(connection_index, conn->serial_number);
break;
}
break;
case link_connecting:
if (!canTx)
{
conn->tx_packet_timer = 0;
break;
}
if (!timeToRetry)
break;
if (ph_sendPacket(connection_index, conn->send_encrypted, packet_type_connect, false))
{
conn->tx_packet_timer = 0;
conn->tx_retry_time = conn->tx_retry_time_slot_len * 4 + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len * 4;
break;
}
break;
case link_connected:
if (!canTx)
{
conn->tx_packet_timer = 0;
break;
}
if (!timeToRetry)
break;
if (tomanyRetries)
{ // reset the link if we have sent tomany retries
ph_startConnect(connection_index, conn->serial_number);
break;
}
if (conn->pinging)
{ // we are trying to ping them
if (ph_sendPacket(connection_index, conn->send_encrypted, packet_type_ping, false))
{
conn->tx_packet_timer = 0;
conn->tx_retry_time = conn->tx_retry_time_slot_len * 4 + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len * 4;
}
break;
}
if (conn->tx_packet_timer >= conn->ping_time)
{ // start pinging
if (ph_sendPacket(connection_index, conn->send_encrypted, packet_type_ping, false))
{
conn->ping_time = 8000 + (random32 % 100) * 10;
conn->tx_packet_timer = 0;
conn->tx_retry_time = conn->tx_retry_time_slot_len * 4 + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len * 4;
conn->pinging = true;
}
break;
}
// ***********
// exit rx not ready mode if we have space in our rx buffer for more data
/*
if (conn->rx_not_ready_mode)
{
uint16_t size = fifoBuf_getFree(&conn->rx_fifo_buffer);
if (size >= conn->rx_fifo_buffer.buf_size / 6)
{ // leave 'rx not ready' mode
if (ph_sendPacket(connection_index, conn->send_encrypted, packet_type_ready, false))
{
conn->tx_packet_timer = 0;
conn->tx_retry_time = conn->tx_retry_time_slot_len + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len;
break;
}
}
}
*/
// ***********
// send data packets
// if (conn->not_ready_timer < 0)
{
uint16_t size = fifoBuf_getUsed(&conn->tx_fifo_buffer);
if (size == 0)
conn->ready_to_send_timer = -1; // no data to send
else
if (conn->ready_to_send_timer < 0)
conn->ready_to_send_timer = 0; // start timer
if (size >= 200 || (conn->ready_to_send_timer >= 10 && size > 0) || (conn->tx_sequence_data_size > 0 && size > 0))
{ // send data
uint8_t pack_type = packet_type_data;
if (conn->rx_not_ready_mode)
pack_type = packet_type_notready;
if (ph_sendPacket(connection_index, conn->send_encrypted, pack_type, false))
{
conn->tx_packet_timer = 0;
conn->tx_retry_time = conn->tx_retry_time_slot_len + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len;
}
break;
}
}
// ***********
break;
default: // we should never end up here - maybe we should do a reboot?
conn->link_state = link_disconnected;
/*
// disable all interrupts
PIOS_IRQ_Disable();
// turn off all leds
USB_LED_OFF;
LINK_LED_OFF;
RX_LED_OFF;
TX_LED_OFF;
PIOS_SYS_Reset();
while (1);
*/
break;
}
}
// *****************************************************************************
// set/get the RF datarate
void ph_setDatarate(uint32_t datarate_bps)
{
rfm22_setDatarate(datarate_bps);
uint32_t ms = 1280000ul / rfm22_getDatarate();
if (ms < 10) ms = 10;
else
if (ms > 32000) ms = 32000;
for (int i = 0; i < PH_MAX_CONNECTIONS; i++)
connection[i].tx_retry_time_slot_len = ms;
}
uint32_t ph_getDatarate(void)
{
return rfm22_getDatarate();
}
// *****************************************************************************
void ph_setTxPower(uint8_t tx_power)
{
rfm22_setTxPower(tx_power);
}
uint8_t ph_getTxPower(void)
{
return rfm22_getTxPower();
}
// *****************************************************************************
// set the AES encryption key
void ph_set_AES128_key(const void *key)
{
memmove(aes_key, key, sizeof(aes_key));
// create the AES decryption key
aes_decrypt_key_128_create(aes_key, (void *)&dec_aes_key);
}
// *****************************************************************************
int ph_set_remote_serial_number(int connection_index, uint32_t sn)
{
random32 = UpdateCRC32(random32, 0xff);
if (ph_startConnect(connection_index, sn) >= 0)
{
t_connection *conn = &connection[connection_index];
// wipe any user data present in the buffers
fifoBuf_init(&conn->tx_fifo_buffer, conn->tx_buffer, PH_FIFO_BUFFER_SIZE);
fifoBuf_init(&conn->rx_fifo_buffer, conn->rx_buffer, PH_FIFO_BUFFER_SIZE);
return connection_index;
}
return -4;
}
// *****************************************************************************
// can be called from an interrupt if you wish
void ph_1ms_tick(void)
{ // call this once every ms
// help randomize the encrypter cbc bytes
register uint32_t *cbc = (uint32_t *)&enc_cbc;
for (int i = 0; i < sizeof(enc_cbc) / 4; i++)
{
random32 = UpdateCRC32(random32, 0xff);
*cbc++ ^= random32;
}
for (int i = 0; i < PH_MAX_CONNECTIONS; i++)
{
t_connection *conn = &connection[i];
if (conn->tx_packet_timer < 0xffff)
conn->tx_packet_timer++;
if (conn->link_state == link_connected)
{ // we are connected
if (conn->ready_to_send_timer >= 0 && conn->ready_to_send_timer < 0x7fff)
conn->ready_to_send_timer++;
if (conn->not_ready_timer >= 0 && conn->not_ready_timer < 0x7fffffff)
conn->not_ready_timer++;
if (conn->data_speed_timer < 0xffff)
{
if (++conn->data_speed_timer >= 1000)
{ // 1 second gone by
conn->data_speed_timer = 0;
conn->tx_data_speed = (conn->tx_data_speed + conn->tx_data_speed_count) >> 1;
conn->tx_data_speed_count = 0;
conn->rx_data_speed = (conn->rx_data_speed + conn->rx_data_speed_count) >> 1;
conn->rx_data_speed_count = 0;
}
}
}
else
{ // we are not connected
if (conn->data_speed_timer) conn->data_speed_timer = 0;
if (conn->tx_data_speed_count) conn->tx_data_speed_count = 0;
if (conn->tx_data_speed) conn->tx_data_speed = 0;
if (conn->rx_data_speed_count) conn->rx_data_speed_count = 0;
if (conn->rx_data_speed) conn->rx_data_speed = 0;
}
}
}
// *****************************************************************************
// call this as often as possible - not from an interrupt
void ph_process(void)
{
ph_processRxPacket();
for (int i = 0; i < PH_MAX_CONNECTIONS; i++)
ph_processLinks(i);
}
// *****************************************************************************
void ph_init(uint32_t our_sn, uint32_t datarate_bps, uint8_t tx_power)
{
our_serial_number = our_sn; // remember our own serial number
for (int i = 0; i < PH_MAX_CONNECTIONS; i++)
{
random32 = UpdateCRC32(random32, 0xff);
t_connection *conn = &connection[i];
conn->serial_number = 0;
conn->tx_sequence = 0;
conn->tx_sequence_data_size = 0;
conn->rx_sequence = 0;
fifoBuf_init(&conn->tx_fifo_buffer, conn->tx_buffer, PH_FIFO_BUFFER_SIZE);
fifoBuf_init(&conn->rx_fifo_buffer, conn->rx_buffer, PH_FIFO_BUFFER_SIZE);
conn->link_state = link_disconnected;
conn->tx_packet_timer = 0;
conn->tx_retry_time_slots = 5;
conn->tx_retry_time_slot_len = 40;
conn->tx_retry_time = conn->tx_retry_time_slot_len * 4 + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len * 4;
conn->tx_retry_counter = 0;
conn->data_speed_timer = 0;
conn->tx_data_speed_count = 0;
conn->tx_data_speed = 0;
conn->rx_data_speed_count = 0;
conn->rx_data_speed = 0;
conn->ping_time = 8000 + (random32 % 100) * 10;
conn->pinging = false;
conn->rx_not_ready_mode = false;
conn->ready_to_send_timer = -1;
conn->not_ready_timer = -1;
conn->send_encrypted = true;
conn->rx_rssi_dBm = -200;
conn->rx_afc_Hz = 0;
}
ph_setDatarate(datarate_bps);
ph_setTxPower(tx_power);
// set the AES encryption key using the default AES key
ph_set_AES128_key(default_aes_key);
// try too randomize the tx AES CBC bytes
for (uint32_t j = 0, k = 0; j < 123 + (random32 & 1023); j++)
{
random32 = UpdateCRC32(random32, 0xff);
enc_cbc[k] ^= random32 >> 3;
if (++k >= sizeof(enc_cbc)) k = 0;
}
}
// *****************************************************************************

View File

@ -25,6 +25,9 @@
#include <pios.h> #include <pios.h>
// ***********************************************************************************
// SPI
#if defined(PIOS_INCLUDE_SPI) #if defined(PIOS_INCLUDE_SPI)
#include <pios_spi_priv.h> #include <pios_spi_priv.h>
@ -34,72 +37,99 @@
* NOTE: Leave this declared as const data so that it ends up in the * NOTE: Leave this declared as const data so that it ends up in the
* .rodata section (ie. Flash) rather than in the .bss section (RAM). * .rodata section (ie. Flash) rather than in the .bss section (RAM).
*/ */
void PIOS_SPI_perif_irq_handler(void); void PIOS_SPI_port_irq_handler(void);
void DMA1_Channel5_IRQHandler() __attribute__ ((alias ("PIOS_SPI_perif_irq_handler"))); void DMA1_Channel5_IRQHandler() __attribute__ ((alias ("PIOS_SPI_port_irq_handler")));
void DMA1_Channel4_IRQHandler() __attribute__ ((alias ("PIOS_SPI_perif_irq_handler"))); void DMA1_Channel4_IRQHandler() __attribute__ ((alias ("PIOS_SPI_port_irq_handler")));
static const struct pios_spi_cfg pios_spi_perif_cfg =
static const struct pios_spi_cfg pios_spi_port_cfg =
{ {
.regs = SPI1, .regs = SPI1,
// .regs = SPI2,
// .regs = SPI3,
.init = .init =
{ {
.SPI_Mode = SPI_Mode_Master, .SPI_Mode = SPI_Mode_Master,
// .SPI_Mode = SPI_Mode_Slave,
.SPI_Direction = SPI_Direction_2Lines_FullDuplex, .SPI_Direction = SPI_Direction_2Lines_FullDuplex,
// .SPI_Direction = SPI_Direction_2Lines_RxOnly,
// .SPI_Direction = SPI_Direction_1Line_Rx,
// .SPI_Direction = SPI_Direction_1Line_Tx,
// .SPI_DataSize = SPI_DataSize_16b,
.SPI_DataSize = SPI_DataSize_8b, .SPI_DataSize = SPI_DataSize_8b,
.SPI_NSS = SPI_NSS_Soft, .SPI_NSS = SPI_NSS_Soft,
// .SPI_NSS = SPI_NSS_Hard,
.SPI_FirstBit = SPI_FirstBit_MSB, .SPI_FirstBit = SPI_FirstBit_MSB,
.SPI_CRCPolynomial = 7, // .SPI_FirstBit = SPI_FirstBit_LSB,
.SPI_CPOL = SPI_CPOL_High,
.SPI_CPHA = SPI_CPHA_2Edge, .SPI_CRCPolynomial = 0,
.SPI_BaudRatePrescaler = 7 << 3, /* Maximum divider (ie. slowest clock rate) */
.SPI_CPOL = SPI_CPOL_Low,
// .SPI_CPOL = SPI_CPOL_High,
.SPI_CPHA = SPI_CPHA_1Edge,
// .SPI_CPHA = SPI_CPHA_2Edge,
// .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_2, // fastest SCLK
// .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_4,
// .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8,
// .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_16,
// .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_32,
// .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_64,
// .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_128,
.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_256, // slowest SCLK
}, },
.use_crc = FALSE,
.dma = .dma =
{ {
.ahb_clk = RCC_AHBPeriph_DMA1, .ahb_clk = RCC_AHBPeriph_DMA1,
.irq = .irq =
{ {
.handler = PIOS_SPI_perif_irq_handler, .handler = PIOS_SPI_port_irq_handler,
.flags = (DMA1_FLAG_TC4 | DMA1_FLAG_TE4 | DMA1_FLAG_HT4 | DMA1_FLAG_GL4), .flags = (DMA1_FLAG_TC2 | DMA1_FLAG_TE2 | DMA1_FLAG_HT2 | DMA1_FLAG_GL2),
.init = .init = {
{ .NVIC_IRQChannel = DMA1_Channel2_IRQn,
.NVIC_IRQChannel = DMA1_Channel4_IRQn, .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, .NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelSubPriority = 0, .NVIC_IRQChannelCmd = ENABLE,
.NVIC_IRQChannelCmd = ENABLE, },
}, },
},
.rx = .rx = {
{ .channel = DMA1_Channel2,
.channel = DMA1_Channel4, .init = {
.init = .DMA_PeripheralBaseAddr = (uint32_t)&(SPI1->DR),
{ .DMA_DIR = DMA_DIR_PeripheralSRC,
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI1->DR), .DMA_PeripheralInc = DMA_PeripheralInc_Disable,
.DMA_DIR = DMA_DIR_PeripheralSRC, .DMA_MemoryInc = DMA_MemoryInc_Enable,
.DMA_PeripheralInc = DMA_PeripheralInc_Disable, .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
.DMA_MemoryInc = DMA_MemoryInc_Enable, .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, .DMA_Mode = DMA_Mode_Normal,
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, .DMA_Priority = DMA_Priority_Medium,
.DMA_Mode = DMA_Mode_Normal, .DMA_M2M = DMA_M2M_Disable,
.DMA_Priority = DMA_Priority_Medium, },
.DMA_M2M = DMA_M2M_Disable, },
}, .tx = {
}, .channel = DMA1_Channel3,
.tx = .init = {
{ .DMA_PeripheralBaseAddr = (uint32_t)&(SPI1->DR),
.channel = DMA1_Channel5, .DMA_DIR = DMA_DIR_PeripheralDST,
.init = .DMA_PeripheralInc = DMA_PeripheralInc_Disable,
{ .DMA_MemoryInc = DMA_MemoryInc_Enable,
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI1->DR), .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
.DMA_DIR = DMA_DIR_PeripheralDST, .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
.DMA_PeripheralInc = DMA_PeripheralInc_Disable, .DMA_Mode = DMA_Mode_Normal,
.DMA_MemoryInc = DMA_MemoryInc_Enable, .DMA_Priority = DMA_Priority_Medium,
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, .DMA_M2M = DMA_M2M_Disable,
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, },
.DMA_Mode = DMA_Mode_Normal, },
.DMA_Priority = DMA_Priority_Medium,
.DMA_M2M = DMA_M2M_Disable,
},
},
}, },
.ssel = .ssel =
{ {
.gpio = GPIOA, .gpio = GPIOA,
@ -107,7 +137,7 @@ static const struct pios_spi_cfg pios_spi_perif_cfg =
{ {
.GPIO_Pin = GPIO_Pin_4, .GPIO_Pin = GPIO_Pin_4,
.GPIO_Speed = GPIO_Speed_10MHz, .GPIO_Speed = GPIO_Speed_10MHz,
.GPIO_Mode = GPIO_Mode_IN_FLOATING, .GPIO_Mode = GPIO_Mode_Out_PP,
}, },
}, },
.sclk = .sclk =
@ -117,7 +147,7 @@ static const struct pios_spi_cfg pios_spi_perif_cfg =
{ {
.GPIO_Pin = GPIO_Pin_5, .GPIO_Pin = GPIO_Pin_5,
.GPIO_Speed = GPIO_Speed_10MHz, .GPIO_Speed = GPIO_Speed_10MHz,
.GPIO_Mode = GPIO_Mode_IN_FLOATING, .GPIO_Mode = GPIO_Mode_AF_PP,
}, },
}, },
.miso = .miso =
@ -127,7 +157,8 @@ static const struct pios_spi_cfg pios_spi_perif_cfg =
{ {
.GPIO_Pin = GPIO_Pin_6, .GPIO_Pin = GPIO_Pin_6,
.GPIO_Speed = GPIO_Speed_10MHz, .GPIO_Speed = GPIO_Speed_10MHz,
.GPIO_Mode = GPIO_Mode_AF_PP, .GPIO_Mode = GPIO_Mode_IN_FLOATING,
// .GPIO_Mode = GPIO_Mode_IPU,
}, },
}, },
.mosi = .mosi =
@ -137,7 +168,7 @@ static const struct pios_spi_cfg pios_spi_perif_cfg =
{ {
.GPIO_Pin = GPIO_Pin_7, .GPIO_Pin = GPIO_Pin_7,
.GPIO_Speed = GPIO_Speed_10MHz, .GPIO_Speed = GPIO_Speed_10MHz,
.GPIO_Mode = GPIO_Mode_IN_FLOATING, .GPIO_Mode = GPIO_Mode_AF_PP,
}, },
}, },
}; };
@ -148,20 +179,23 @@ static const struct pios_spi_cfg pios_spi_perif_cfg =
struct pios_spi_dev pios_spi_devs[] = struct pios_spi_dev pios_spi_devs[] =
{ {
{ {
.cfg = &pios_spi_perif_cfg, .cfg = &pios_spi_port_cfg,
}, },
}; };
uint8_t pios_spi_num_devices = NELEMENTS(pios_spi_devs); uint8_t pios_spi_num_devices = NELEMENTS(pios_spi_devs);
void PIOS_SPI_perif_irq_handler(void) void PIOS_SPI_port_irq_handler(void)
{ {
/* Call into the generic code to handle the IRQ for this specific device */ /* Call into the generic code to handle the IRQ for this specific device */
PIOS_SPI_IRQ_Handler(PIOS_SPI_PERIF); PIOS_SPI_IRQ_Handler(PIOS_SPI_PORT);
} }
#endif /* PIOS_INCLUDE_SPI */ #endif /* PIOS_INCLUDE_SPI */
// ***********************************************************************************
// USART
#if defined(PIOS_INCLUDE_USART) #if defined(PIOS_INCLUDE_USART)
#include <pios_usart_priv.h> #include <pios_usart_priv.h>
@ -176,7 +210,11 @@ const struct pios_usart_cfg pios_usart_serial_cfg =
.regs = USART1, .regs = USART1,
.init = .init =
{ {
.USART_BaudRate = 57600, #if defined(PIOS_USART_BAUDRATE)
.USART_BaudRate = PIOS_USART_BAUDRATE,
#else
.USART_BaudRate = 57600,
#endif
.USART_WordLength = USART_WordLength_8b, .USART_WordLength = USART_WordLength_8b,
.USART_Parity = USART_Parity_No, .USART_Parity = USART_Parity_No,
.USART_StopBits = USART_StopBits_1, .USART_StopBits = USART_StopBits_1,
@ -221,7 +259,7 @@ const struct pios_usart_cfg pios_usart_serial_cfg =
*/ */
struct pios_usart_dev pios_usart_devs[] = struct pios_usart_dev pios_usart_devs[] =
{ {
#define PIOS_USART_SERIAL 0 #define PIOS_USART_SERIAL 0
{ {
.cfg = &pios_usart_serial_cfg, .cfg = &pios_usart_serial_cfg,
}, },
@ -236,6 +274,8 @@ void PIOS_USART_serial_irq_handler(void)
#endif /* PIOS_INCLUDE_USART */ #endif /* PIOS_INCLUDE_USART */
// ***********************************************************************************
#if defined(PIOS_INCLUDE_COM) #if defined(PIOS_INCLUDE_COM)
#include <pios_com_priv.h> #include <pios_com_priv.h>
@ -247,6 +287,9 @@ void PIOS_USART_serial_irq_handler(void)
* Board specific number of devices. * Board specific number of devices.
*/ */
extern const struct pios_com_driver pios_usart_com_driver; extern const struct pios_com_driver pios_usart_com_driver;
#if defined(PIOS_INCLUDE_USB_HID)
extern const struct pios_com_driver pios_usb_com_driver;
#endif
struct pios_com_dev pios_com_devs[] = struct pios_com_dev pios_com_devs[] =
{ {
@ -254,9 +297,16 @@ struct pios_com_dev pios_com_devs[] =
.id = PIOS_USART_SERIAL, .id = PIOS_USART_SERIAL,
.driver = &pios_usart_com_driver, .driver = &pios_usart_com_driver,
}, },
#if defined(PIOS_INCLUDE_USB_HID)
{
.id = 0,
.driver = &pios_usb_com_driver,
},
#endif
}; };
const uint8_t pios_com_num_devices = NELEMENTS(pios_com_devs); const uint8_t pios_com_num_devices = NELEMENTS(pios_com_devs);
#endif /* PIOS_INCLUDE_COM */ #endif /* PIOS_INCLUDE_COM */
// ***********************************************************************************

View File

@ -93,7 +93,7 @@ const uint8_t PIOS_HID_ConfigDescriptor[PIOS_HID_SIZ_CONFIG_DESC] =
0x03, // bmAttributes: Interrupt endpoint 0x03, // bmAttributes: Interrupt endpoint
0x40, // wMaxPacketSize: 2 Bytes max 0x40, // wMaxPacketSize: 2 Bytes max
0x00, 0x00,
1, // bInterval: Polling Interval in ms 0x04, // bInterval: Polling Interval in ms
// 34 // 34
0x07, // bLength: Endpoint Descriptor size 0x07, // bLength: Endpoint Descriptor size
@ -104,7 +104,7 @@ const uint8_t PIOS_HID_ConfigDescriptor[PIOS_HID_SIZ_CONFIG_DESC] =
0x03, // bmAttributes: Interrupt endpoint 0x03, // bmAttributes: Interrupt endpoint
0x40, // wMaxPacketSize: 2 Bytes max 0x40, // wMaxPacketSize: 2 Bytes max
0x00, 0x00,
1, // bInterval: Polling Interval in ms 0x04, // bInterval: Polling Interval in ms
// 41 // 41
}; };
@ -175,15 +175,15 @@ const uint8_t PIOS_HID_StringProduct[PIOS_HID_SIZ_STRING_PRODUCT] =
{ {
PIOS_HID_SIZ_STRING_PRODUCT, // bLength PIOS_HID_SIZ_STRING_PRODUCT, // bLength
USB_STRING_DESCRIPTOR_TYPE, // bDescriptorType USB_STRING_DESCRIPTOR_TYPE, // bDescriptorType
'O', 0,
'p', 0,
'e', 0,
'n', 0,
'P', 0, 'P', 0,
'i', 0, 'i', 0,
'l', 0, 'p', 0,
'o', 0, 'X', 0,
't', 0 't', 0,
'r', 0,
'e', 0,
'm', 0,
'e', 0
}; };
uint8_t PIOS_HID_StringSerial[PIOS_HID_SIZ_STRING_SERIAL] = uint8_t PIOS_HID_StringSerial[PIOS_HID_SIZ_STRING_SERIAL] =

1905
flight/PipXtreme/rfm22b.c Normal file
View File

@ -0,0 +1,1905 @@
/**
******************************************************************************
*
* @file rfm22b.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief RF Module hardware layer
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
// *****************************************************************
// RFM22B hardware layer
//
// This module uses the RFM22B's internal packet handling hardware to encapsulate our own packet data.
//
// The RFM22B internal hardware packet handler configuration is as follows ..
//
// 4-byte (32-bit) preamble .. alternating 0's & 1's
// 4-byte (32-bit) sync
// 1-byte packet length (number of data bytes to follow)
// 0 to 255 user data bytes
//
// Our own packet data will also contain it's own header and 32-bit CRC as a single 16-bit CRC is not sufficient for wireless comms.
//
// *****************************************************************
#include <string.h> // memmove
#include "stm32f10x.h"
#include "main.h"
#include "stopwatch.h"
#include "gpio_in.h"
#include "rfm22b.h"
#if defined(PIOS_COM_DEBUG)
// #define RFM22_DEBUG
// #define RFM22_INT_TIMEOUT_DEBUG
#endif
// *****************************************************************
// forward delarations
#if defined(RFM22_EXT_INT_USE)
void rfm22_processInt(void);
#endif
// ************************************
// this is too adjust the RF module so that it is on frequency
#define OSC_LOAD_CAP 0x7F // cap = 12.5pf .. default
#define OSC_LOAD_CAP_1 0x7D // board 1
#define OSC_LOAD_CAP_2 0x7B // board 2
#define OSC_LOAD_CAP_3 0x7E // board 3
#define OSC_LOAD_CAP_4 0x7F // board 4
// ************************************
#define TX_TEST_MODE_TIMELIMIT_MS 30000 // TX test modes time limit (in ms)
#define TX_PREAMBLE_NIBBLES 8 // 7 to 511 (number of nibbles)
#define RX_PREAMBLE_NIBBLES 5 // 5 to 31 (number of nibbles)
#define FIFO_SIZE 64 // the size of the rf modules internal FIFO buffers
#define TX_FIFO_HI_WATERMARK 62 // 0-63
#define TX_FIFO_LO_WATERMARK 32 // 0-63
#define RX_FIFO_HI_WATERMARK 32 // 0-63
#define SYNC_BYTE_1 0x2D // RF sync bytes (32-bit in all)
#define SYNC_BYTE_2 0xD4 //
#define SYNC_BYTE_3 0x4B //
#define SYNC_BYTE_4 0x59 //
// ************************************
// the default TX power level
#define RFM22_DEFAULT_RF_POWER rfm22_tx_pwr_txpow_0 // +1dBm ... 1.25mW
//#define RFM22_DEFAULT_RF_POWER rfm22_tx_pwr_txpow_1 // +2dBm ... 1.6mW
//#define RFM22_DEFAULT_RF_POWER rfm22_tx_pwr_txpow_2 // +5dBm ... 3.16mW
//#define RFM22_DEFAULT_RF_POWER rfm22_tx_pwr_txpow_3 // +8dBm ... 6.3mW
//#define RFM22_DEFAULT_RF_POWER rfm22_tx_pwr_txpow_4 // +11dBm .. 12.6mW
//#define RFM22_DEFAULT_RF_POWER rfm22_tx_pwr_txpow_5 // +14dBm .. 25mW
//#define RFM22_DEFAULT_RF_POWER rfm22_tx_pwr_txpow_6 // +17dBm .. 50mW
//#define RFM22_DEFAULT_RF_POWER rfm22_tx_pwr_txpow_7 // +20dBm .. 100mW
// ************************************
// the default RF datarate
//#define RFM22_DEFAULT_RF_DATARATE 500 // 500 bits per sec
//#define RFM22_DEFAULT_RF_DATARATE 1000 // 1k bits per sec
//#define RFM22_DEFAULT_RF_DATARATE 2000 // 2k bits per sec
//#define RFM22_DEFAULT_RF_DATARATE 4000 // 4k bits per sec
//#define RFM22_DEFAULT_RF_DATARATE 8000 // 8k bits per sec
//#define RFM22_DEFAULT_RF_DATARATE 9600 // 9.6k bits per sec
//#define RFM22_DEFAULT_RF_DATARATE 16000 // 16k bits per sec
//#define RFM22_DEFAULT_RF_DATARATE 19200 // 19k2 bits per sec
//#define RFM22_DEFAULT_RF_DATARATE 24000 // 24k bits per sec
//#define RFM22_DEFAULT_RF_DATARATE 32000 // 32k bits per sec
//#define RFM22_DEFAULT_RF_DATARATE 64000 // 64k bits per sec
#define RFM22_DEFAULT_RF_DATARATE 128000 // 128k bits per sec
//#define RFM22_DEFAULT_RF_DATARATE 192000 // 192k bits per sec
//#define RFM22_DEFAULT_RF_DATARATE 256000 // 256k bits per sec .. NOT YET WORKING
// ************************************
// GFSK modulation
// no manchester encoding
// data whitening
// FIFO mode
// 5-nibble rx preamble length detection
// 10-nibble tx preamble length
#define LOOKUP_SIZE 14
/*
// xtal 20 ppm
*/
// xtal 10 ppm, 434MHz
uint32_t data_rate[LOOKUP_SIZE] = { 500, 1000, 2000, 4000, 8000, 9600, 16000, 19200, 24000, 32000, 64000, 128000, 192000, 256000};
uint8_t modulation_index[LOOKUP_SIZE] = { 16, 8, 4, 2, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1};
uint32_t freq_deviation[LOOKUP_SIZE] = { 4000, 4000, 4000, 4000, 4000, 4800, 8000, 9600, 12000, 16000, 32000, 64000, 96000, 128000};
uint32_t rx_bandwidth[LOOKUP_SIZE] = { 17500, 17500, 17500, 17500, 17500, 19400, 32200, 38600, 51200, 64100, 137900, 269300, 420200, 518800};
int8_t est_rx_sens_dBm[LOOKUP_SIZE] = { -118, -118, -117, -116, -115, -115, -112, -112, -110, -109, -106, -103, -101, -100}; // estimated receiver sensitivity for BER = 1E-3
uint8_t reg_1C[LOOKUP_SIZE] = { 0x3A, 0x3A, 0x3A, 0x3A, 0x3A, 0x3B, 0x26, 0x2B, 0x2E, 0x16, 0x07, 0x83, 0x8A, 0x8C}; // rfm22_if_filter_bandwidth
uint8_t reg_1D[LOOKUP_SIZE] = { 0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40}; // rfm22_afc_loop_gearshift_override
uint8_t reg_20[LOOKUP_SIZE] = { 0xE8, 0xF4, 0xFA, 0x7D, 0x3F, 0x34, 0x3F, 0x34, 0x2A, 0x3F, 0x3F, 0x5E, 0x3F, 0x2F}; // rfm22_clk_recovery_oversampling_ratio
uint8_t reg_21[LOOKUP_SIZE] = { 0x60, 0x20, 0x00, 0x01, 0x02, 0x02, 0x02, 0x02, 0x03, 0x02, 0x02, 0x01, 0x02, 0x02}; // rfm22_clk_recovery_offset2
uint8_t reg_22[LOOKUP_SIZE] = { 0x20, 0x41, 0x83, 0x06, 0x0C, 0x75, 0x0C, 0x75, 0x12, 0x0C, 0x0C, 0x5D, 0x0C, 0xBB}; // rfm22_clk_recovery_offset1
uint8_t reg_23[LOOKUP_SIZE] = { 0xC5, 0x89, 0x12, 0x25, 0x4A, 0x25, 0x4A, 0x25, 0x6F, 0x4A, 0x4A, 0x86, 0x4A, 0x0D}; // rfm22_clk_recovery_offset0
uint8_t reg_24[LOOKUP_SIZE] = { 0x00, 0x00, 0x00, 0x02, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x02, 0x04, 0x05}; // rfm22_clk_recovery_timing_loop_gain1
uint8_t reg_25[LOOKUP_SIZE] = { 0x0A, 0x23, 0x85, 0x0E, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xBB, 0x12, 0x74}; // rfm22_clk_recovery_timing_loop_gain0
uint8_t reg_2A[LOOKUP_SIZE] = { 0x0E, 0x0E, 0x0E, 0x0E, 0x0E, 0x0D, 0x0D, 0x0E, 0x12, 0x17, 0x31, 0x50, 0x50, 0x50}; // rfm22_afc_limiter .. AFC_pull_in_range = ±AFCLimiter[7:0] x (hbsel+1) x 625 Hz
uint8_t reg_6E[LOOKUP_SIZE] = { 0x04, 0x08, 0x10, 0x20, 0x41, 0x4E, 0x83, 0x9D, 0xC4, 0x08, 0x10, 0x20, 0x31, 0x41}; // rfm22_tx_data_rate1
uint8_t reg_6F[LOOKUP_SIZE] = { 0x19, 0x31, 0x62, 0xC5, 0x89, 0xA5, 0x12, 0x49, 0x9C, 0x31, 0x62, 0xC5, 0x27, 0x89}; // rfm22_tx_data_rate0
uint8_t reg_70[LOOKUP_SIZE] = { 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x0D, 0x0D, 0x0D, 0x0D, 0x0D}; // rfm22_modulation_mode_control1
uint8_t reg_71[LOOKUP_SIZE] = { 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23}; // rfm22_modulation_mode_control2
uint8_t reg_72[LOOKUP_SIZE] = { 0x06, 0x06, 0x06, 0x06, 0x06, 0x08, 0x0D, 0x0F, 0x13, 0x1A, 0x33, 0x66, 0x9A, 0xCD}; // rfm22_frequency_deviation
// ************************************
volatile bool initialized = false;
#if defined(RFM22_EXT_INT_USE)
volatile bool exec_using_spi; // set this if you want to access the SPI bus outside of the interrupt
volatile bool inside_ext_int; // this is set whenever we are inside the interrupt
#endif
uint8_t device_type; // the RF chips device ID number
uint8_t device_version; // the RF chips revision number
volatile uint8_t rf_mode; // holds our current RF mode
uint32_t lower_carrier_frequency_limit_Hz; // the minimum RF frequency we can use
uint32_t upper_carrier_frequency_limit_Hz; // the maximum RF frequency we can use
uint32_t carrier_frequency_hz; // the current RF frequency we are on
uint32_t carrier_datarate_bps; // the RF data rate we are using
uint8_t hbsel; // holds the hbsel (1 or 2)
float frequency_step_size; //
uint8_t frequency_hop_channel; // current frequency hop channel
uint8_t frequency_hop_step_size_reg; //
uint8_t adc_config; // holds the adc config reg value
volatile uint8_t device_status; // device status register
volatile uint8_t int_status1; // interrupt status register 1
volatile uint8_t int_status2; // interrupt status register 2
volatile uint8_t ezmac_status; // ezmac status register
volatile int16_t afc_correction; // afc correction reading
volatile int32_t afc_correction_Hz; // afc correction reading (in Hz)
volatile int16_t temperature_reg; // the temperature sensor reading
#if defined(RFM22_DEBUG)
volatile uint8_t prev_device_status; // just for debugging
volatile uint8_t prev_int_status1; // " "
volatile uint8_t prev_int_status2; // " "
volatile uint8_t prev_ezmac_status; // " "
bool debug_outputted;
#endif
volatile uint8_t rssi; // the current RSSI (register value)
volatile int16_t rssi_dBm; // dBm value
uint8_t tx_power; // the transmit power to use for data transmissions
volatile uint8_t tx_pwr; // the tx power register read back
volatile uint8_t rx_buffer_current; // the current receive buffer in use (double buffer)
volatile uint8_t rx_buffer[256] __attribute__ ((aligned(4))); // the receive buffer .. received packet data is saved here
volatile uint16_t rx_buffer_wr; // the receive buffer write index
volatile uint8_t rx_packet_buf[256] __attribute__ ((aligned(4))); // the received packet
volatile uint16_t rx_packet_wr; // the receive packet write index
volatile int16_t rx_packet_rssi_dBm; // the receive packet signal strength
volatile int32_t rx_packet_afc_Hz; // the receive packet frequency offset
volatile uint8_t *tx_data_addr; // the address of the data we send in the transmitted packets
volatile uint16_t tx_data_rd; // the tx data read index
volatile uint16_t tx_data_wr; // the tx data write index
int lookup_index;
volatile bool power_on_reset; // set if the RF module has reset itself
volatile uint16_t rfm22_int_timer; // used to detect if the RF module stops responding. thus act accordingly if it does stop responding.
volatile uint16_t rfm22_int_time_outs; // counter
volatile uint16_t prev_rfm22_int_time_outs; //
uint32_t clear_channel_count = (TX_PREAMBLE_NIBBLES + 4) * 2; // minimum clear channel time before allowing transmit
uint16_t timeout_ms = 20000; //
uint16_t timeout_sync_ms = 3; //
uint16_t timeout_data_ms = 20; //
// ************************************
// SPI read/write
void rfm22_startBurstWrite(uint8_t addr)
{
// wait 1us .. so we don't toggle the CS line to quickly
PIOS_DELAY_WaituS(1);
// chip select line LOW
PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0);
PIOS_SPI_TransferByte(RFM22_PIOS_SPI, 0x80 | addr);
}
inline void rfm22_burstWrite(uint8_t data)
{
PIOS_SPI_TransferByte(RFM22_PIOS_SPI, data);
}
void rfm22_endBurstWrite(void)
{
// chip select line HIGH
PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 1);
}
void rfm22_write(uint8_t addr, uint8_t data)
{
// wait 1us .. so we don't toggle the CS line to quickly
PIOS_DELAY_WaituS(1);
// chip select line LOW
PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0);
PIOS_SPI_TransferByte(RFM22_PIOS_SPI, 0x80 | addr);
PIOS_SPI_TransferByte(RFM22_PIOS_SPI, data);
// chip select line HIGH
PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 1);
}
void rfm22_startBurstRead(uint8_t addr)
{
// wait 1us .. so we don't toggle the CS line to quickly
PIOS_DELAY_WaituS(1);
// chip select line LOW
PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0);
PIOS_SPI_TransferByte(RFM22_PIOS_SPI, addr & 0x7f);
}
inline uint8_t rfm22_burstRead(void)
{
return PIOS_SPI_TransferByte(RFM22_PIOS_SPI, 0xff);
}
void rfm22_endBurstRead(void)
{
// chip select line HIGH
PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 1);
}
uint8_t rfm22_read(uint8_t addr)
{
uint8_t rdata;
// wait 1us .. so we don't toggle the CS line to quickly
PIOS_DELAY_WaituS(1);
// chip select line LOW
PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0);
PIOS_SPI_TransferByte(RFM22_PIOS_SPI, addr & 0x7f);
rdata = PIOS_SPI_TransferByte(RFM22_PIOS_SPI, 0xff);
// chip select line HIGH
PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 1);
return rdata;
}
// ************************************
// external interrupt
#if defined(RFM22_EXT_INT_USE)
void RFM22_EXT_INT_FUNC(void)
{
inside_ext_int = TRUE;
if (EXTI_GetITStatus(RFM22_EXT_INT_LINE) != RESET)
{
// Clear the EXTI line pending bit
EXTI_ClearITPendingBit(RFM22_EXT_INT_LINE);
// USB_LED_TOGGLE; // TEST ONLY
if (!booting && !exec_using_spi)
{
// while (!GPIO_IN(RF_INT_PIN) && !exec_using_spi)
{ // stay here until the interrupt line returns HIGH
rfm22_processInt();
}
}
}
inside_ext_int = FALSE;
}
void rfm22_disableExtInt(void)
{
// Configure the external interrupt
GPIO_EXTILineConfig(RFM22_EXT_INT_PORT_SOURCE, RFM22_EXT_INT_PIN_SOURCE);
EXTI_InitTypeDef EXTI_InitStructure;
EXTI_InitStructure.EXTI_Line = RFM22_EXT_INT_LINE;
EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt;
EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Falling;
EXTI_InitStructure.EXTI_LineCmd = DISABLE;
EXTI_Init(&EXTI_InitStructure);
EXTI_ClearFlag(RFM22_EXT_INT_LINE);
}
void rfm22_enableExtInt(void)
{
// Configure the external interrupt
GPIO_EXTILineConfig(RFM22_EXT_INT_PORT_SOURCE, RFM22_EXT_INT_PIN_SOURCE);
EXTI_InitTypeDef EXTI_InitStructure;
EXTI_InitStructure.EXTI_Line = RFM22_EXT_INT_LINE;
EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt;
EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Falling;
EXTI_InitStructure.EXTI_LineCmd = ENABLE;
EXTI_Init(&EXTI_InitStructure);
EXTI_ClearFlag(RFM22_EXT_INT_LINE);
// Enable and set the external interrupt
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_InitStructure.NVIC_IRQChannel = RFM22_EXT_INT_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = RFM22_EXT_INT_PRIORITY;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
}
#endif
// ************************************
// radio datarate about 19200 Baud
// radio frequency deviation 45kHz
// radio receiver bandwidth 67kHz.
//
// Carson's rule:
// The signal bandwidth is about 2(Delta-f + fm) ..
//
// Delta-f = frequency deviation
// fm = maximum frequency of the signal
//
// This gives 2(45 + 9.6) = 109.2kHz.
void rfm22_setDatarate(uint32_t datarate_bps)
{
#if defined(RFM22_EXT_INT_USE)
exec_using_spi = TRUE;
#endif
// *******
lookup_index = 0;
while (lookup_index < (LOOKUP_SIZE - 1) && data_rate[lookup_index] < datarate_bps)
lookup_index++;
carrier_datarate_bps = datarate_bps = data_rate[lookup_index];
// ********************************
#if defined(RFM22_DEBUG)
uint32_t frequency_deviation = freq_deviation[lookup_index]; // Hz
uint32_t modulation_bandwidth = datarate_bps + (2 * frequency_deviation);
#endif
rfm22_write(0x1C, reg_1C[lookup_index]); // rfm22_if_filter_bandwidth
rfm22_write(0x1D, reg_1D[lookup_index]); // rfm22_afc_loop_gearshift_override
rfm22_write(0x20, reg_20[lookup_index]); // rfm22_clk_recovery_oversampling_ratio
rfm22_write(0x21, reg_21[lookup_index]); // rfm22_clk_recovery_offset2
rfm22_write(0x22, reg_22[lookup_index]); // rfm22_clk_recovery_offset1
rfm22_write(0x23, reg_23[lookup_index]); // rfm22_clk_recovery_offset0
rfm22_write(0x24, reg_24[lookup_index]); // rfm22_clk_recovery_timing_loop_gain1
rfm22_write(0x25, reg_25[lookup_index]); // rfm22_clk_recovery_timing_loop_gain0
rfm22_write(0x2A, reg_2A[lookup_index]); // rfm22_afc_limiter
if (carrier_datarate_bps < 100000)
rfm22_write(0x58, 0x80); // rfm22_chargepump_current_trimming_override
else
rfm22_write(0x58, 0xC0); // rfm22_chargepump_current_trimming_override
rfm22_write(0x6E, reg_6E[lookup_index]); // rfm22_tx_data_rate1
rfm22_write(0x6F, reg_6F[lookup_index]); // rfm22_tx_data_rate0
rfm22_write(0x70, reg_70[lookup_index]); // rfm22_modulation_mode_control1
rfm22_write(0x71, reg_71[lookup_index]); // rfm22_modulation_mode_control2
rfm22_write(0x72, reg_72[lookup_index]); // rfm22_frequency_deviation
rfm22_write(rfm22_ook_counter_value1, 0x00);
rfm22_write(rfm22_ook_counter_value2, 0x00);
// ********************************
// calculate the TX register values
/*
uint16_t fd = frequency_deviation / 625;
uint8_t mmc1 = rfm22_mmc1_enphpwdn | rfm22_mmc1_manppol;
uint16_t txdr;
if (datarate_bps < 30000)
{
txdr = (datarate_bps * 20972) / 10000;
mmc1 |= rfm22_mmc1_txdtrtscale;
}
else
txdr = (datarate_bps * 6553) / 100000;
uint8_t mmc2 = rfm22_mmc2_dtmod_fifo | rfm22_mmc2_modtyp_gfsk; // FIFO mode, GFSK
// uint8_t mmc2 = rfm22_mmc2_dtmod_pn9 | rfm22_mmc2_modtyp_gfsk; // PN9 mode, GFSK .. TX TEST MODE
if (fd & 0x100) mmc2 |= rfm22_mmc2_fd;
rfm22_write(rfm22_frequency_deviation, fd); // set the TX peak frequency deviation
rfm22_write(rfm22_modulation_mode_control1, mmc1);
rfm22_write(rfm22_modulation_mode_control2, mmc2);
rfm22_write(rfm22_tx_data_rate1, txdr >> 8); // set the TX data rate
rfm22_write(rfm22_tx_data_rate0, txdr); // " "
*/
// ********************************
// determine a clear channel time
// initialise the stopwatch with a suitable resolution for the datarate
STOPWATCH_init(4000000ul / carrier_datarate_bps); // set resolution to the time for 1 nibble (4-bits) at rf datarate
// ********************************
// determine suitable time-out periods
timeout_sync_ms = (8000ul * 16) / carrier_datarate_bps; // milliseconds
if (timeout_sync_ms < 3)
timeout_sync_ms = 3; // because out timer resolution is only 1ms
timeout_data_ms = (8000ul * 100) / carrier_datarate_bps; // milliseconds
if (timeout_data_ms < 3)
timeout_data_ms = 3; // because out timer resolution is only 1ms
// ********************************
#if defined(RFM22_DEBUG)
DEBUG_PRINTF("rf datarate_bps: %d\r\n", datarate_bps);
DEBUG_PRINTF("rf frequency_deviation: %d\r\n", frequency_deviation);
DEBUG_PRINTF("rf modulation_bandwidth: %u\r\n", modulation_bandwidth);
DEBUG_PRINTF("rf_rx_bandwidth[%u]: %u\r\n", lookup_index, rx_bandwidth[lookup_index]);
DEBUG_PRINTF("rf est rx sensitivity[%u]: %ddBm\r\n", lookup_index, est_rx_sens_dBm[lookup_index]);
#endif
// *******
#if defined(RFM22_EXT_INT_USE)
exec_using_spi = FALSE;
#endif
}
uint32_t rfm22_getDatarate(void)
{
return carrier_datarate_bps;
}
// ************************************
// set/get the current tx power setting
void rfm22_setTxPower(uint8_t tx_pwr)
{
switch (tx_pwr)
{
case 0: tx_power = rfm22_tx_pwr_txpow_0; break; // +1dBm ... 1.25mW
case 1: tx_power = rfm22_tx_pwr_txpow_1; break; // +2dBm ... 1.6mW
case 2: tx_power = rfm22_tx_pwr_txpow_2; break; // +5dBm ... 3.16mW
case 3: tx_power = rfm22_tx_pwr_txpow_3; break; // +8dBm ... 6.3mW
case 4: tx_power = rfm22_tx_pwr_txpow_4; break; // +11dBm .. 12.6mW
case 5: tx_power = rfm22_tx_pwr_txpow_5; break; // +14dBm .. 25mW
case 6: tx_power = rfm22_tx_pwr_txpow_6; break; // +17dBm .. 50mW
case 7: tx_power = rfm22_tx_pwr_txpow_7; break; // +20dBm .. 100mW
default: break;
}
}
uint8_t rfm22_getTxPower(void)
{
return tx_power;
}
// ************************************
void rfm22_setNominalCarrierFrequency(uint32_t frequency_hz)
{
#if defined(RFM22_EXT_INT_USE)
exec_using_spi = TRUE;
#endif
// *******
if (frequency_hz < lower_carrier_frequency_limit_Hz) frequency_hz = lower_carrier_frequency_limit_Hz;
else
if (frequency_hz > upper_carrier_frequency_limit_Hz) frequency_hz = upper_carrier_frequency_limit_Hz;
carrier_frequency_hz = frequency_hz;
if (frequency_hz < 480000000ul)
hbsel = 1;
else
hbsel = 2;
uint8_t fb = frequency_hz / (10000000ul * hbsel);
uint32_t fc = frequency_hz - (10000000ul * hbsel * fb);
fc = (fc * 64u) / (10000ul * hbsel);
fb -= 24;
if (hbsel > 1)
fb |= rfm22_fbs_hbsel;
fb |= rfm22_fbs_sbse; // is this the RX LO polarity?
frequency_step_size = 156.25f * hbsel;
rfm22_write(rfm22_frequency_hopping_channel_select, frequency_hop_channel); // frequency hoppping channel (0-255)
rfm22_write(rfm22_frequency_offset1, 0); // no frequency offset
rfm22_write(rfm22_frequency_offset2, 0); // no frequency offset
rfm22_write(rfm22_frequency_band_select, fb); // set the carrier frequency
rfm22_write(rfm22_nominal_carrier_frequency1, fc >> 8); // " "
rfm22_write(rfm22_nominal_carrier_frequency0, fc & 0xff); // " "
// *******
#if defined(RFM22_DEBUG)
DEBUG_PRINTF("rf setFreq: %u\r\n", carrier_frequency_hz);
#endif
#if defined(RFM22_EXT_INT_USE)
exec_using_spi = FALSE;
#endif
}
uint32_t rfm22_getNominalCarrierFrequency(void)
{
return carrier_frequency_hz;
}
void rfm22_setFreqHopChannel(uint8_t channel)
{ // set the frequency hopping channel
frequency_hop_channel = channel;
rfm22_write(rfm22_frequency_hopping_channel_select, frequency_hop_channel);
}
uint8_t rfm22_freqHopChannel(void)
{ // return the current frequency hopping channel
return frequency_hop_channel;
}
// ************************************
void rfm22_reenableRx(void)
{
#if defined(RFM22_EXT_INT_USE)
exec_using_spi = TRUE;
#endif
RX_LED_OFF;
// disable the receiver
// rfm22_write(rfm22_op_and_func_ctrl1, rfm22_opfc1_xton); // READY mode
rfm22_write(rfm22_op_and_func_ctrl1, rfm22_opfc1_pllon); // TUNE mode
// clear FIFOs
rfm22_write(rfm22_op_and_func_ctrl2, rfm22_opfc2_ffclrrx | rfm22_opfc2_ffclrtx);
rfm22_write(rfm22_op_and_func_ctrl2, 0x00);
rx_buffer_wr = 0; // empty the rx buffer
afc_correction = 0; // reset the afc correction reading
afc_correction_Hz = 0; // " "
rfm22_int_timer = 0; // reset the timer
STOPWATCH_reset(); // reset clear channel detect timer
rf_mode = RX_WAIT_PREAMBLE_MODE;
// enable the receiver
// rfm22_write(rfm22_op_and_func_ctrl1, rfm22_opfc1_xton | rfm22_opfc1_rxon);
rfm22_write(rfm22_op_and_func_ctrl1, rfm22_opfc1_pllon | rfm22_opfc1_rxon);
#if defined(RFM22_EXT_INT_USE)
exec_using_spi = FALSE;
#endif
}
void rfm22_setRxMode(void)
{
#if defined(RFM22_EXT_INT_USE)
exec_using_spi = TRUE;
#endif
// disable interrupts
rfm22_write(rfm22_interrupt_enable1, 0x00);
rfm22_write(rfm22_interrupt_enable2, 0x00);
// disable the receiver and transmitter
// rfm22_write(rfm22_op_and_func_ctrl1, rfm22_opfc1_xton); // READY mode
rfm22_write(rfm22_op_and_func_ctrl1, rfm22_opfc1_pllon); // TUNE mode
RX_LED_OFF;
TX_LED_OFF;
// rfm22_write(rfm22_rx_fifo_control, RX_FIFO_HI_WATERMARK); // RX FIFO Almost Full Threshold (0 - 63)
if (rf_mode == TX_CARRIER_MODE || rf_mode == TX_PN_MODE)
{ // FIFO mode, GFSK modulation
uint8_t fd_bit = rfm22_read(rfm22_modulation_mode_control2) & rfm22_mmc2_fd;
rfm22_write(rfm22_modulation_mode_control2, fd_bit | rfm22_mmc2_dtmod_fifo | rfm22_mmc2_modtyp_gfsk);
}
rx_buffer_wr = 0; // empty the rx buffer
afc_correction = 0; // reset the afc correction reading
afc_correction_Hz = 0; // " "
rfm22_int_timer = 0; // reset the timer
STOPWATCH_reset(); // reset clear channel detect timer
rf_mode = RX_WAIT_PREAMBLE_MODE;
// enable RX interrupts
rfm22_write(rfm22_interrupt_enable1, rfm22_ie1_encrcerror | rfm22_ie1_enpkvalid | rfm22_ie1_enrxffafull | rfm22_ie1_enfferr);
rfm22_write(rfm22_interrupt_enable2, rfm22_ie2_enpreainval | rfm22_ie2_enpreaval | rfm22_ie2_enswdet);
// read interrupt status - clear interrupts
rfm22_read(rfm22_interrupt_status1);
rfm22_read(rfm22_interrupt_status2);
// clear FIFOs
rfm22_write(rfm22_op_and_func_ctrl2, rfm22_opfc2_ffclrrx | rfm22_opfc2_ffclrtx);
rfm22_write(rfm22_op_and_func_ctrl2, 0x00);
// enable the receiver
// rfm22_write(rfm22_op_and_func_ctrl1, rfm22_opfc1_xton | rfm22_opfc1_rxon);
rfm22_write(rfm22_op_and_func_ctrl1, rfm22_opfc1_pllon | rfm22_opfc1_rxon);
#if defined(RFM22_EXT_INT_USE)
exec_using_spi = FALSE;
#endif
#if defined(RFM22_DEBUG)
DEBUG_PRINTF(" RX Mode\r\n");
#endif
}
// ************************************
void rfm22_setTxMode(uint8_t mode)
{
if (mode != TX_DATA_MODE && mode != TX_CARRIER_MODE && rf_mode != TX_PN_MODE)
return; // invalid mode
#if defined(RFM22_EXT_INT_USE)
exec_using_spi = TRUE;
#endif
// *******************
// disable interrupts
rfm22_write(rfm22_interrupt_enable1, 0x00);
rfm22_write(rfm22_interrupt_enable2, 0x00);
// rfm22_write(rfm22_op_and_func_ctrl1, rfm22_opfc1_xton); // READY mode
rfm22_write(rfm22_op_and_func_ctrl1, rfm22_opfc1_pllon); // TUNE mode
RX_LED_OFF;
uint8_t fd_bit = rfm22_read(rfm22_modulation_mode_control2) & rfm22_mmc2_fd;
if (mode == TX_CARRIER_MODE)
{ // blank carrier mode - for testing
rfm22_write(rfm22_tx_power, rfm22_tx_pwr_papeaken | rfm22_tx_pwr_papeaklvl_0 | rfm22_tx_pwr_lna_sw | rfm22_tx_pwr_txpow_0); // tx power +1dBm ... 1.25mW
rfm22_write(rfm22_modulation_mode_control2, fd_bit | rfm22_mmc2_dtmod_pn9 | rfm22_mmc2_modtyp_none); // FIFO mode, Blank carrier
}
else
if (mode == TX_PN_MODE)
{ // psuedo random data carrier mode - for testing
rfm22_write(rfm22_tx_power, rfm22_tx_pwr_papeaken | rfm22_tx_pwr_papeaklvl_0 | rfm22_tx_pwr_lna_sw | rfm22_tx_pwr_txpow_0); // tx power +1dBm ... 1.25mW
rfm22_write(rfm22_modulation_mode_control2, fd_bit | rfm22_mmc2_dtmod_pn9 | rfm22_mmc2_modtyp_gfsk); // FIFO mode, PN9 carrier
}
else
{ // data transmission
// rfm22_write(rfm22_tx_power, rfm22_tx_pwr_lna_sw | tx_power); // set the tx power
rfm22_write(rfm22_tx_power, rfm22_tx_pwr_papeaken | rfm22_tx_pwr_papeaklvl_0 | rfm22_tx_pwr_lna_sw | tx_power); // set the tx power
rfm22_write(rfm22_modulation_mode_control2, fd_bit | rfm22_mmc2_dtmod_fifo | rfm22_mmc2_modtyp_gfsk); // FIFO mode, GFSK modulation
}
// rfm22_write(0x72, reg_72[lookup_index]); // rfm22_frequency_deviation
// clear FIFOs
rfm22_write(rfm22_op_and_func_ctrl2, rfm22_opfc2_ffclrrx | rfm22_opfc2_ffclrtx);
rfm22_write(rfm22_op_and_func_ctrl2, 0x00);
// *******************
// add some data to the chips TX FIFO before enabling the transmitter
if (mode == TX_DATA_MODE)
{
tx_data_rd = 0;
register uint16_t rd = tx_data_rd;
// set the total number of data bytes we are going to transmit
rfm22_write(rfm22_transmit_packet_length, tx_data_wr);
register uint16_t num = tx_data_wr - rd;
if (num > (FIFO_SIZE - 1)) num = FIFO_SIZE - 1;
// add some data
rfm22_startBurstWrite(rfm22_fifo_access);
for (register uint16_t i = num; i > 0; i--)
rfm22_burstWrite(tx_data_addr[rd++]);
rfm22_endBurstWrite();
tx_data_rd += num;
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
// DEBUG_PRINTF(" added_%d_bytes", num);
// debug_outputted = true;
#endif
}
// *******************
rfm22_int_timer = 0; // reset the timer
rf_mode = mode;
// enable TX interrupts
// rfm22_write(rfm22_interrupt_enable1, rfm22_ie1_enpksent | rfm22_ie1_entxffaem | rfm22_ie1_enfferr);
rfm22_write(rfm22_interrupt_enable1, rfm22_ie1_enpksent | rfm22_ie1_entxffaem);
// read interrupt status - clear interrupts
rfm22_read(rfm22_interrupt_status1);
rfm22_read(rfm22_interrupt_status2);
// enable the transmitter
// rfm22_write(rfm22_op_and_func_ctrl1, rfm22_opfc1_xton | rfm22_opfc1_txon);
rfm22_write(rfm22_op_and_func_ctrl1, rfm22_opfc1_pllon | rfm22_opfc1_txon);
TX_LED_ON;
// *******************
// create new slightly random clear channel detector count value
uint32_t ccc = (TX_PREAMBLE_NIBBLES + 8) + 4; // minimum clear channel time before allowing transmit
clear_channel_count = ccc + (random32 % (ccc * 2)); // plus a some randomness
// *******************
#if defined(RFM22_EXT_INT_USE)
exec_using_spi = FALSE;
#endif
#if defined(RFM22_DEBUG)
if (rf_mode == TX_DATA_MODE) DEBUG_PRINTF(" TX_Data_Mode\r\n");
else
if (rf_mode == TX_CARRIER_MODE) DEBUG_PRINTF(" TX_Carrier_Mode\r\n");
else
if (rf_mode == TX_PN_MODE) DEBUG_PRINTF(" TX_PN_Mode\r\n");
#endif
}
// ************************************
// external interrupt line triggered (or polled) from the rf chip
void rfm22_processRxInt(void)
{
register uint8_t int_stat1 = int_status1;
register uint8_t int_stat2 = int_status2;
if (int_stat2 & rfm22_is2_ipreaval)
{ // Valid preamble detected
if (rf_mode == RX_WAIT_PREAMBLE_MODE)
{
rfm22_int_timer = 0; // reset the timer
rf_mode = RX_WAIT_SYNC_MODE;
RX_LED_ON;
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
DEBUG_PRINTF(" pream_det");
debug_outputted = true;
#endif
}
}
/* else
if (int_stat2 & rfm22_is2_ipreainval)
{ // Invalid preamble detected
if (rf_mode == RX_WAIT_SYNC_MODE)
{
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
DEBUG_PRINTF(" invalid_preamble");
debug_outputted = true;
#endif
// rfm22_reenableRx(); // re-enable the receiver
rfm22_setRxMode();
return;
}
else
{
}
}
*/
if (int_stat2 & rfm22_is2_iswdet)
{ // Sync word detected
STOPWATCH_reset(); // reset timer
if (rf_mode == RX_WAIT_PREAMBLE_MODE || rf_mode == RX_WAIT_SYNC_MODE)
{
rfm22_int_timer = 0; // reset the timer
rf_mode = RX_DATA_MODE;
RX_LED_ON;
// read the 10-bit signed afc correction value
afc_correction = (uint16_t)rfm22_read(rfm22_afc_correction_read) << 8; // bits 9 to 2
afc_correction |= (uint16_t)rfm22_read(rfm22_ook_counter_value1) & 0x00c0; // bits 1 & 0
afc_correction >>= 6;
// convert the afc value to Hz
afc_correction_Hz = (int32_t)(frequency_step_size * afc_correction + 0.5f);
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
DEBUG_PRINTF(" sync_det");
DEBUG_PRINTF(" AFC_%d_%dHz", afc_correction, afc_correction_Hz);
debug_outputted = true;
#endif
}
}
if (int_stat1 & rfm22_is1_irxffafull)
{ // RX FIFO almost full, it needs emptying
if (rf_mode == RX_DATA_MODE)
{ // read data from the rf chips FIFO buffer
rfm22_int_timer = 0; // reset the timer
register uint16_t len = rfm22_read(rfm22_received_packet_length); // read the total length of the packet data
register uint16_t wr = rx_buffer_wr;
if ((wr + RX_FIFO_HI_WATERMARK) > len)
{ // some kind of error in the RF module
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
DEBUG_PRINTF(" r_size_error1");
debug_outputted = true;
#endif
// rfm22_reenableRx(); // re-enable the receiver
rfm22_setRxMode();
return;
}
if (((wr + RX_FIFO_HI_WATERMARK) >= len) && !(int_stat1 & rfm22_is1_ipkvalid))
{ // some kind of error in the RF module
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
DEBUG_PRINTF(" r_size_error2");
debug_outputted = true;
#endif
// rfm22_reenableRx(); // re-enable the receiver
rfm22_setRxMode();
return;
}
// fetch the rx'ed data from the rf chips RX FIFO
rfm22_startBurstRead(rfm22_fifo_access);
for (register uint16_t i = RX_FIFO_HI_WATERMARK; i > 0; i--)
{
register uint8_t b = rfm22_burstRead(); // read a byte from the rf modules RX FIFO buffer
if (wr < sizeof(rx_buffer))
rx_buffer[wr++] = b; // save the byte into our rx buffer
}
rfm22_endBurstRead();
rx_buffer_wr = wr;
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
// DEBUG_PRINTF(" r_data_%u/%u", rx_buffer_wr, len);
// debug_outputted = true;
#endif
}
else
{ // just clear the RX FIFO
rfm22_startBurstRead(rfm22_fifo_access);
for (register uint16_t i = RX_FIFO_HI_WATERMARK; i > 0; i--)
rfm22_burstRead(); // read a byte from the rf modules RX FIFO buffer
rfm22_endBurstRead();
}
}
if (int_stat1 & rfm22_is1_icrerror)
{ // CRC error .. discard the received data
if (rf_mode == RX_DATA_MODE)
{
rfm22_int_timer = 0; // reset the timer
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
DEBUG_PRINTF(" CRC_ERR");
debug_outputted = true;
#endif
// rfm22_reenableRx(); // re-enable the receiver
rfm22_setRxMode(); // reset the receiver
return;
}
}
// if (int_stat2 & rfm22_is2_irssi)
// { // RSSI level is >= the set threshold
// }
// if (device_status & rfm22_ds_rxffem)
// { // RX FIFO empty
// }
// if (device_status & rfm22_ds_headerr)
// { // Header check error
// }
if (int_stat1 & rfm22_is1_ipkvalid)
{ // Valid packet received
if (rf_mode == RX_DATA_MODE)
{
rfm22_int_timer = 0; // reset the timer
// disable the receiver
// rfm22_write(rfm22_op_and_func_ctrl1, rfm22_opfc1_xton); // READY mode
rfm22_write(rfm22_op_and_func_ctrl1, rfm22_opfc1_pllon); // TUNE mode
register uint16_t len = rfm22_read(rfm22_received_packet_length); // read the total length of the packet data
register uint16_t wr = rx_buffer_wr;
if (wr < len)
{ // their must still be data in the RX FIFO we need to get
rfm22_startBurstRead(rfm22_fifo_access);
while (wr < len)
{
if (wr >= sizeof(rx_buffer)) break;
rx_buffer[wr++] = rfm22_burstRead();
}
rfm22_endBurstRead();
rx_buffer_wr = wr;
}
// rfm22_reenableRx(); // re-enable the receiver
rfm22_setRxMode(); // reset the receiver
if (wr != len)
{ // we have a packet length error .. discard the packet
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
DEBUG_PRINTF(" r_pack_len_error_%u_%u", len, wr);
debug_outputted = true;
#endif
return;
}
// we have a valid received packet
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
DEBUG_PRINTF(" VALID_R_PACKET_%u", wr);
debug_outputted = true;
#endif
if (rx_packet_wr == 0)
{ // save the received packet for further processing
rx_packet_rssi_dBm = rssi_dBm; // remember the rssi for this packet
rx_packet_afc_Hz = afc_correction_Hz; // remember the afc offset for this packet
memmove((void *)rx_packet_buf, (void *)rx_buffer, wr); // copy the packet data
rx_packet_wr = wr; // save the length of the data
}
else
{ // the save buffer is still in use .. nothing we can do but to drop the packet
}
// return;
}
else
{
//// rfm22_reenableRx(); // re-enable the receiver
// rfm22_setRxMode(); // reset the receiver
// return;
}
}
}
void rfm22_processTxInt(void)
{
register uint8_t int_stat1 = int_status1;
// register uint8_t int_stat2 = int_status2;
/*
if (int_stat1 & rfm22_is1_ifferr)
{ // FIFO underflow/overflow error
rfm22_setRxMode();
tx_data_addr = NULL;
tx_data_rd = tx_data_wr = 0;
return;
}
*/
if (int_stat1 & rfm22_is1_ixtffaem)
{ // TX FIFO almost empty, it needs filling up
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
// DEBUG_PRINTF(" T_FIFO_AE");
// debug_outputted = true;
#endif
if (rf_mode == TX_DATA_MODE)
{
if ((tx_data_wr > 0) && (tx_data_rd < tx_data_wr))
{ // we have more data to send
rfm22_int_timer = 0; // reset the timer
register uint16_t rd = tx_data_rd;
register uint16_t num = tx_data_wr - rd;
if (num > (FIFO_SIZE - TX_FIFO_LO_WATERMARK - 1))
num = FIFO_SIZE - TX_FIFO_LO_WATERMARK - 1;
// top-up the rf chips TX FIFO buffer
rfm22_startBurstWrite(rfm22_fifo_access);
for (register uint16_t i = num; i > 0; i--)
rfm22_burstWrite(tx_data_addr[rd++]);
rfm22_endBurstWrite();
tx_data_rd = rd;
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
// DEBUG_PRINTF(" added_%d_bytes", num);
// debug_outputted = true;
#endif
}
// return;
}
}
if (int_stat1 & rfm22_is1_ipksent)
{ // Packet has been sent
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
DEBUG_PRINTF(" T_Sent");
debug_outputted = true;
#endif
if (rf_mode == TX_DATA_MODE)
{
rfm22_setRxMode(); // back to receive mode
tx_data_addr = NULL;
tx_data_rd = tx_data_wr = 0;
return;
}
}
// if (int_stat1 & rfm22_is1_itxffafull)
// { // TX FIFO almost full, it needs to be transmitted
// }
}
void rfm22_processInt(void)
{ // this is called from the external interrupt handler
#if !defined(RFM22_EXT_INT_USE)
if (GPIO_IN(RF_INT_PIN))
return; // the external int line is high (no signalled interrupt)
#endif
if (!initialized || power_on_reset)
return; // we haven't yet been initialized
#if defined(RFM22_DEBUG)
debug_outputted = false;
#endif
// ********************************
// read the RF modules current status registers
// read device status register
device_status = rfm22_read(rfm22_device_status);
// read ezmac status register
ezmac_status = rfm22_read(rfm22_ezmac_status);
// read interrupt status registers - clears the interrupt line
int_status1 = rfm22_read(rfm22_interrupt_status1);
int_status2 = rfm22_read(rfm22_interrupt_status2);
if (rf_mode != TX_DATA_MODE && rf_mode != TX_CARRIER_MODE && rf_mode != TX_PN_MODE)
{
rssi = rfm22_read(rfm22_rssi); // read rx signal strength .. 45 = -100dBm, 205 = -20dBm
rssi_dBm = ((int16_t)rssi / 2) - 122; // convert to dBm
}
else
{
tx_pwr = rfm22_read(rfm22_tx_power); // read the tx power register
}
if (int_status2 & rfm22_is2_ipor)
{ // the RF module has gone and done a reset - we need to re-initialize the rf module
initialized = FALSE;
power_on_reset = TRUE;
return;
}
// ********************************
// debug stuff
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
if (prev_device_status != device_status || prev_int_status1 != int_status1 || prev_int_status2 != int_status2 || prev_ezmac_status != ezmac_status)
{
DEBUG_PRINTF("%02x %02x %02x %02x %dC", device_status, int_status1, int_status2, ezmac_status, temperature_reg);
if ((device_status & rfm22_ds_cps_mask) == rfm22_ds_cps_rx)
DEBUG_PRINTF(" %ddBm", rssi_dBm); // rx mode
else
if ((device_status & rfm22_ds_cps_mask) == rfm22_ds_cps_tx)
DEBUG_PRINTF(" %s", (tx_pwr & rfm22_tx_pwr_papeakval) ? "ANT_MISMATCH" : "ant_ok"); // tx mode
debug_outputted = true;
prev_device_status = device_status;
prev_int_status1 = int_status1;
prev_int_status2 = int_status2;
prev_ezmac_status = ezmac_status;
}
#endif
// ********************************
// read the ADC - temperature sensor .. this can only be used in IDLE mode
/*
if (!(rfm22_read(rfm22_adc_config) & rfm22_ac_adcstartbusy))
{ // the ADC has completed it's conversion
// read the ADC sample
temperature_reg = (int16_t)rfm22_read(rfm22_adc_value) * 0.5f - 64;
// start a new ADC conversion
rfm22_write(rfm22_adc_config, adc_config | rfm22_ac_adcstartbusy);
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
DEBUG_PRINTF(", %dC", temperature_reg);
debug_outputted = true;
#endif
}
*/
// ********************************
register uint16_t timer_ms = rfm22_int_timer;
switch (rf_mode)
{
case RX_WAIT_PREAMBLE_MODE:
case RX_WAIT_SYNC_MODE:
case RX_DATA_MODE:
if (device_status & (rfm22_ds_ffunfl | rfm22_ds_ffovfl))
{ // FIFO under/over flow error
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
DEBUG_PRINTF(" R_UNDER/OVERRUN");
debug_outputted = true;
#endif
rfm22_setRxMode(); // reset the receiver
tx_data_rd = tx_data_wr = 0; // wipe TX buffer
break;
}
if (rf_mode == RX_WAIT_SYNC_MODE && timer_ms >= timeout_sync_ms)
{
rfm22_int_time_outs++;
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
DEBUG_PRINTF(" R_SYNC_TIMEOUT");
debug_outputted = true;
#endif
rfm22_setRxMode(); // reset the receiver
tx_data_rd = tx_data_wr = 0; // wipe TX buffer
break;
}
if (rf_mode == RX_DATA_MODE && timer_ms >= timeout_data_ms)
{ // missing interrupts
rfm22_int_time_outs++;
rfm22_setRxMode(); // reset the receiver
tx_data_rd = tx_data_wr = 0; // wipe TX buffer
break;
}
if ((device_status & rfm22_ds_cps_mask) != rfm22_ds_cps_rx)
{ // the rf module is not in rx mode
if (timer_ms >= 100)
{
rfm22_int_time_outs++;
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
DEBUG_PRINTF(" R_TIMEOUT");
debug_outputted = true;
#endif
rfm22_setRxMode(); // reset the receiver
tx_data_rd = tx_data_wr = 0; // wipe TX buffer
break;
}
}
rfm22_processRxInt(); // process the interrupt
break;
case TX_DATA_MODE:
if (device_status & (rfm22_ds_ffunfl | rfm22_ds_ffovfl))
{ // FIFO under/over flow error
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
DEBUG_PRINTF(" T_UNDER/OVERRUN");
debug_outputted = true;
#endif
rfm22_setRxMode(); // back to rx mode
tx_data_rd = tx_data_wr = 0; // wipe TX buffer
break;
}
if (timer_ms >= timeout_data_ms)
{
rfm22_int_time_outs++;
rfm22_setRxMode(); // back to rx mode
tx_data_rd = tx_data_wr = 0; // wipe TX buffer
break;
}
if ((device_status & rfm22_ds_cps_mask) != rfm22_ds_cps_tx)
{ // the rf module is not in tx mode
if (timer_ms >= 100)
{
rfm22_int_time_outs++;
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
DEBUG_PRINTF(" T_TIMEOUT");
debug_outputted = true;
#endif
rfm22_setRxMode(); // back to rx mode
tx_data_rd = tx_data_wr = 0; // wipe TX buffer
break;
}
}
rfm22_processTxInt(); // process the interrupt
break;
case TX_CARRIER_MODE:
case TX_PN_MODE:
if (timer_ms >= TX_TEST_MODE_TIMELIMIT_MS) // 'nn'ms limit
{
rfm22_setRxMode(); // back to rx mode
tx_data_rd = tx_data_wr = 0; // wipe TX buffer
break;
}
break;
default: // unknown mode - this should NEVER happen, maybe we should do a complete CPU reset here
rfm22_setRxMode(); // to rx mode
tx_data_rd = tx_data_wr = 0; // wipe TX buffer
break;
}
// ********************************
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
if (debug_outputted)
{
switch (rf_mode)
{
case RX_WAIT_PREAMBLE_MODE:
DEBUG_PRINTF(" R_WAIT_PREAMBLE\r\n");
break;
case RX_WAIT_SYNC_MODE:
DEBUG_PRINTF(" R_WAIT_SYNC\r\n");
break;
case RX_DATA_MODE:
DEBUG_PRINTF(" R_DATA\r\n");
break;
case TX_DATA_MODE:
DEBUG_PRINTF(" T_DATA\r\n");
break;
case TX_CARRIER_MODE:
DEBUG_PRINTF(" T_CARRIER\r\n");
break;
case TX_PN_MODE:
DEBUG_PRINTF(" T_PN\r\n");
break;
default:
DEBUG_PRINTF(" UNKNOWN_MODE\r\n");
break;
}
}
#endif
// ********************************
}
// ************************************
int16_t rfm22_receivedRSSI(void)
{ // return the packets signal strength
if (!initialized)
return -200;
else
return rx_packet_rssi_dBm;
}
int32_t rfm22_receivedAFCHz(void)
{ // return the packets offset frequency
if (!initialized)
return 0;
else
return rx_packet_afc_Hz;
}
uint16_t rfm22_receivedLength(void)
{ // return the size of the data received
if (!initialized)
return 0;
else
return rx_packet_wr;
}
uint8_t * rfm22_receivedPointer(void)
{ // return the address of the data
return (uint8_t *)&rx_packet_buf;
}
void rfm22_receivedDone(void)
{ // empty the rx packet buffer
rx_packet_wr = 0;
}
// ************************************
int32_t rfm22_sendData(void *data, uint16_t length, bool send_immediately)
{
if (!initialized)
return -1; // we are not yet initialized
if (length == 0)
return -2; // no data to send
if (length > 255)
return -3; // too much data
if (tx_data_wr > 0)
return -4; // already have data to be sent
if (rf_mode == TX_DATA_MODE || rf_mode == TX_CARRIER_MODE || rf_mode == TX_PN_MODE)
return -5; // we are currently transmitting
tx_data_addr = data;
tx_data_rd = 0;
tx_data_wr = length;
#if defined(RFM22_DEBUG)
DEBUG_PRINTF("rf sendData(0x%08x %u)\r\n", (uint32_t)tx_data_addr, tx_data_wr);
#endif
if (send_immediately || rfm22_channelIsClear()) // is the channel clear to transmit on?
rfm22_setTxMode(TX_DATA_MODE); // transmit NOW
return tx_data_wr;
}
// ************************************
// enable a blank tx carrier (for frequency alignment)
void rfm22_setTxCarrierMode(void)
{
if (!initialized)
return;
if (rf_mode != TX_CARRIER_MODE)
rfm22_setTxMode(TX_CARRIER_MODE);
}
// enable a psuedo random data tx carrier (for spectrum inspection)
void rfm22_setTxPNMode(void)
{
if (!initialized)
return;
if (rf_mode != TX_PN_MODE)
rfm22_setTxMode(TX_PN_MODE);
}
// ************************************
// return the current mode
int8_t rfm22_currentMode(void)
{
return rf_mode;
}
// return TRUE if we are transmitting
bool rfm22_transmitting(void)
{
return (rf_mode == TX_DATA_MODE || rf_mode == TX_CARRIER_MODE || rf_mode == TX_PN_MODE);
}
// return TRUE if the channel is clear to transmit on
bool rfm22_channelIsClear(void)
{
if (!initialized)
return FALSE; // we haven't yet been initialized
if (rf_mode != RX_WAIT_PREAMBLE_MODE && rf_mode != RX_WAIT_SYNC_MODE)
return FALSE; // we are receiving something or we are transmitting
return TRUE;
// return (STOPWATCH_get_count() > clear_channel_count);
}
// return TRUE if the transmiter is ready for use
bool rfm22_txReady(void)
{
if (!initialized)
return FALSE; // we haven't yet been initialized
return (tx_data_rd == 0 && tx_data_wr == 0 && rf_mode != TX_DATA_MODE && rf_mode != TX_CARRIER_MODE && rf_mode != TX_PN_MODE);
}
// ************************************
// can be called from an interrupt if you wish
void rfm22_1ms_tick(void)
{ // call this once every ms
if (!initialized)
return; // we haven't yet been initialized
if (rfm22_int_timer < 0xffff)
rfm22_int_timer++;
}
// *****************************************************************************
// call this as often as possible - not from an interrupt
void rfm22_process(void)
{
if (!initialized)
return; // we haven't yet been initialized
#if !defined(RFM22_EXT_INT_USE)
rfm22_processInt(); // manually poll the interrupt line routine
#endif
if (power_on_reset)
{ // we need to re-initialize the RF module - it told us it's reset itself
uint32_t current_freq = carrier_frequency_hz; // fetch current rf nominal frequency
uint32_t freq_hop_step_size = (uint32_t)frequency_hop_step_size_reg * 10000; // fetch the frequency hoppping step size
rfm22_init(lower_carrier_frequency_limit_Hz, upper_carrier_frequency_limit_Hz, freq_hop_step_size);
rfm22_setNominalCarrierFrequency(current_freq); // restore the nominal carrier frequency
return;
}
switch (rf_mode)
{
case RX_WAIT_PREAMBLE_MODE:
if (rfm22_int_timer >= timeout_ms)
{ // assume somethings locked up
rfm22_int_time_outs++;
rfm22_setRxMode(); // reset the RF module to rx mode
tx_data_rd = tx_data_wr = 0; // wipe TX buffer
break;
}
// go to transmit mode if we have data to send and the channel is clear to transmit on
if (tx_data_rd == 0 && tx_data_wr > 0 && rfm22_channelIsClear())
{
rfm22_setTxMode(TX_DATA_MODE); // transmit packet NOW
break;
}
break;
case RX_WAIT_SYNC_MODE:
if (rfm22_int_timer >= timeout_sync_ms)
{ // assume somethings locked up
rfm22_int_time_outs++;
rfm22_setRxMode(); // reset the RF module to rx mode
tx_data_rd = tx_data_wr = 0; // wipe TX buffer
break;
}
// go to transmit mode if we have data to send and the channel is clear to transmit on
if (tx_data_rd == 0 && tx_data_wr > 0 && rfm22_channelIsClear())
{
rfm22_setTxMode(TX_DATA_MODE); // transmit packet NOW
break;
}
break;
case RX_DATA_MODE:
case TX_DATA_MODE:
if (rfm22_int_timer >= timeout_data_ms)
{ // assume somethings locked up
rfm22_int_time_outs++;
rfm22_setRxMode(); // reset the RF module to rx mode
tx_data_rd = tx_data_wr = 0; // wipe TX buffer
break;
}
break;
case TX_CARRIER_MODE:
case TX_PN_MODE:
if (rfm22_int_timer >= TX_TEST_MODE_TIMELIMIT_MS)
{
rfm22_setRxMode(); // back to rx mode
tx_data_rd = tx_data_wr = 0; // wipe TX buffer
break;
}
break;
default:
// unknown mode - this should never happen, maybe we should do a complete CPU reset here?
rfm22_setRxMode(); // to rx mode
tx_data_rd = tx_data_wr = 0; // wipe TX buffer
break;
}
#if defined(RFM22_INT_TIMEOUT_DEBUG)
if (prev_rfm22_int_time_outs != rfm22_int_time_outs)
{
prev_rfm22_int_time_outs = rfm22_int_time_outs;
DEBUG_PRINTF("rf int timeouts %d\r\n", rfm22_int_time_outs);
}
#endif
}
// ************************************
// Initialize this hardware layer module and the rf module
int rfm22_init(uint32_t min_frequency_hz, uint32_t max_frequency_hz, uint32_t freq_hop_step_size)
{
initialized = false;
#if defined(RFM22_EXT_INT_USE)
rfm22_disableExtInt();
#endif
power_on_reset = false;
#if defined(RFM22_DEBUG)
DEBUG_PRINTF("\r\nRF init\r\n");
#endif
// ****************
#if defined(RFM22_EXT_INT_USE)
exec_using_spi = TRUE;
#endif
// ****************
// setup the SPI port
// chip select line HIGH
PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 1);
// set SPI port SCLK frequency .. 4.5MHz
PIOS_SPI_SetClockSpeed(RFM22_PIOS_SPI, PIOS_SPI_PRESCALER_16);
// ****************
// software reset the RF chip .. following procedure according to Si4x3x Errata (rev. B)
rfm22_write(rfm22_op_and_func_ctrl1, rfm22_opfc1_swres); // software reset the radio
PIOS_DELAY_WaitmS(26); // wait 26ms
for (int i = 50; i > 0; i--)
{
PIOS_DELAY_WaitmS(1); // wait 1ms
// read the status registers
int_status1 = rfm22_read(rfm22_interrupt_status1);
int_status2 = rfm22_read(rfm22_interrupt_status2);
if (int_status2 & rfm22_is2_ichiprdy) break;
}
// ****************
// read status - clears interrupt
device_status = rfm22_read(rfm22_device_status);
int_status1 = rfm22_read(rfm22_interrupt_status1);
int_status2 = rfm22_read(rfm22_interrupt_status2);
ezmac_status = rfm22_read(rfm22_ezmac_status);
// disable all interrupts
rfm22_write(rfm22_interrupt_enable1, 0x00);
rfm22_write(rfm22_interrupt_enable2, 0x00);
// ****************
#if defined(RFM22_EXT_INT_USE)
exec_using_spi = FALSE;
#endif
// ****************
#if defined(RFM22_EXT_INT_USE)
inside_ext_int = FALSE;
#endif
rf_mode = RX_WAIT_PREAMBLE_MODE;
device_status = int_status1 = int_status2 = ezmac_status = 0;
rssi = 0;
rssi_dBm = -200;
rx_buffer_current = 0;
rx_buffer_wr = 0;
rx_packet_wr = 0;
tx_data_addr = NULL;
tx_data_rd = tx_data_wr = 0;
lookup_index = 0;
rfm22_int_timer = 0;
rfm22_int_time_outs = 0;
prev_rfm22_int_time_outs = 0;
hbsel = 0;
frequency_step_size = 0.0f;
frequency_hop_channel = 0;
afc_correction = 0;
temperature_reg = 0;
// set the TX power
tx_power = RFM22_DEFAULT_RF_POWER;
tx_pwr = 0;
// ****************
// set the minimum and maximum carrier frequency allowed
if (min_frequency_hz < rfm22_min_carrier_frequency_Hz) min_frequency_hz = rfm22_min_carrier_frequency_Hz;
else
if (min_frequency_hz > rfm22_max_carrier_frequency_Hz) min_frequency_hz = rfm22_max_carrier_frequency_Hz;
if (max_frequency_hz < rfm22_min_carrier_frequency_Hz) max_frequency_hz = rfm22_min_carrier_frequency_Hz;
else
if (max_frequency_hz > rfm22_max_carrier_frequency_Hz) max_frequency_hz = rfm22_max_carrier_frequency_Hz;
if (min_frequency_hz > max_frequency_hz)
{ // swap them over
uint32_t tmp = min_frequency_hz;
min_frequency_hz = max_frequency_hz;
max_frequency_hz = tmp;
}
lower_carrier_frequency_limit_Hz = min_frequency_hz;
upper_carrier_frequency_limit_Hz = max_frequency_hz;
// ****************
freq_hop_step_size /= 10000; // in 10kHz increments
if (freq_hop_step_size > 255) freq_hop_step_size = 255;
frequency_hop_step_size_reg = freq_hop_step_size;
// ****************
// read the RF chip ID bytes
device_type = rfm22_read(rfm22_device_type) & rfm22_dt_mask; // read the device type
#if defined(RFM22_DEBUG)
DEBUG_PRINTF("rf device type: %d\r\n", device_type);
#endif
if (device_type != 0x08)
return -1; // incorrect RF module type
device_version = rfm22_read(rfm22_device_version) & rfm22_dv_mask; // read the device version
#if defined(RFM22_DEBUG)
DEBUG_PRINTF("rf device version: %d\r\n", device_version);
#endif
// if (device_version != RFM22_DEVICE_VERSION_V2) // V2
// return -2; // incorrect RF module version
// if (device_version != RFM22_DEVICE_VERSION_A0) // A0
// return -2; // incorrect RF module version
if (device_version != RFM22_DEVICE_VERSION_B1) // B1
return -2; // incorrect RF module version
// ****************
// disable Low Duty Cycle Mode
rfm22_write(rfm22_op_and_func_ctrl2, 0x00);
// calibrate our RF module to be exactly on frequency .. different for every module
if (serial_number_crc32 == 0x176C1EC6) rfm22_write(rfm22_xtal_osc_load_cap, OSC_LOAD_CAP_1);
else
if (serial_number_crc32 == 0xA524A3B0) rfm22_write(rfm22_xtal_osc_load_cap, OSC_LOAD_CAP_2);
else
if (serial_number_crc32 == 0x9F6393C1) rfm22_write(rfm22_xtal_osc_load_cap, OSC_LOAD_CAP_3);
else
if (serial_number_crc32 == 0x994ECD31) rfm22_write(rfm22_xtal_osc_load_cap, OSC_LOAD_CAP_4);
else
rfm22_write(rfm22_xtal_osc_load_cap, OSC_LOAD_CAP); // default
rfm22_write(rfm22_op_and_func_ctrl1, rfm22_opfc1_xton); // READY mode
// rfm22_write(rfm22_op_and_func_ctrl1, rfm22_opfc1_pllon); // TUNE mode
// choose the 3 GPIO pin functions
rfm22_write(rfm22_io_port_config, rfm22_io_port_default); // GPIO port use default value
rfm22_write(rfm22_gpio0_config, rfm22_gpio0_config_drv3 | rfm22_gpio0_config_txstate); // GPIO0 = TX State (to control RF Switch)
rfm22_write(rfm22_gpio1_config, rfm22_gpio1_config_drv3 | rfm22_gpio1_config_rxstate); // GPIO1 = RX State (to control RF Switch)
rfm22_write(rfm22_gpio2_config, rfm22_gpio2_config_drv3 | rfm22_gpio2_config_cca); // GPIO2 = Clear Channel Assessment
// set the RF datarate
rfm22_setDatarate(RFM22_DEFAULT_RF_DATARATE);
// Enable data whitening
// uint8_t txdtrtscale_bit = rfm22_read(rfm22_modulation_mode_control1) & rfm22_mmc1_txdtrtscale;
// rfm22_write(rfm22_modulation_mode_control1, txdtrtscale_bit | rfm22_mmc1_enwhite);
// FIFO mode, GFSK modulation
uint8_t fd_bit = rfm22_read(rfm22_modulation_mode_control2) & rfm22_mmc2_fd;
rfm22_write(rfm22_modulation_mode_control2, rfm22_mmc2_trclk_clk_none | rfm22_mmc2_dtmod_fifo | fd_bit | rfm22_mmc2_modtyp_gfsk);
rfm22_write(rfm22_cpu_output_clk, rfm22_coc_1MHz); // 1MHz clock output
// setup to read the internal temperature sensor
adc_config = rfm22_ac_adcsel_temp_sensor | rfm22_ac_adcref_bg; // ADC used to sample the temperature sensor
rfm22_write(rfm22_adc_config, adc_config); //
rfm22_write(rfm22_adc_sensor_amp_offset, 0); // adc offset
rfm22_write(rfm22_temp_sensor_calib, rfm22_tsc_tsrange0 | rfm22_tsc_entsoffs); // temp sensor calibration .. 40C to +64C 0.5C resolution
rfm22_write(rfm22_temp_value_offset, 0); // temp sensor offset
rfm22_write(rfm22_adc_config, adc_config | rfm22_ac_adcstartbusy); // start an ADC conversion
rfm22_write(rfm22_rssi_threshold_clear_chan_indicator, (-80 + 122) * 2); // set the RSSI threshold interrupt to about -80dBm
// enable the internal Tx & Rx packet handlers (with CRC)
// rfm22_write(rfm22_data_access_control, rfm22_dac_enpacrx | rfm22_dac_enpactx | rfm22_dac_encrc | rfm22_dac_crc_crc16);
// enable the internal Tx & Rx packet handlers (without CRC)
rfm22_write(rfm22_data_access_control, rfm22_dac_enpacrx | rfm22_dac_enpactx);
rfm22_write(rfm22_preamble_length, TX_PREAMBLE_NIBBLES); // x-nibbles tx preamble
rfm22_write(rfm22_preamble_detection_ctrl1, RX_PREAMBLE_NIBBLES << 3); // x-nibbles rx preamble detection
rfm22_write(rfm22_header_control1, rfm22_header_cntl1_bcen_none | rfm22_header_cntl1_hdch_none); // header control - we are not using the header
rfm22_write(rfm22_header_control2, rfm22_header_cntl2_hdlen_none | rfm22_header_cntl2_synclen_3210 | ((TX_PREAMBLE_NIBBLES >> 8) & 0x01)); // no header bytes, synchronization word length 3, 2, 1 & 0 used, packet length included in header.
rfm22_write(rfm22_sync_word3, SYNC_BYTE_1); // sync word
rfm22_write(rfm22_sync_word2, SYNC_BYTE_2); //
rfm22_write(rfm22_sync_word1, SYNC_BYTE_3); //
rfm22_write(rfm22_sync_word0, SYNC_BYTE_4); //
/*
rfm22_write(rfm22_transmit_header3, 'p'); // set tx header
rfm22_write(rfm22_transmit_header2, 'i'); //
rfm22_write(rfm22_transmit_header1, 'p'); //
rfm22_write(rfm22_transmit_header0, ' '); //
rfm22_write(rfm22_check_header3, 'p'); // set expected rx header
rfm22_write(rfm22_check_header2, 'i'); //
rfm22_write(rfm22_check_header1, 'p'); //
rfm22_write(rfm22_check_header0, ' '); //
// all the bits to be checked
rfm22_write(rfm22_header_enable3, 0xff);
rfm22_write(rfm22_header_enable2, 0xff);
rfm22_write(rfm22_header_enable1, 0xff);
rfm22_write(rfm22_header_enable0, 0xff);
*/ // no bits to be checked
rfm22_write(rfm22_header_enable3, 0x00);
rfm22_write(rfm22_header_enable2, 0x00);
rfm22_write(rfm22_header_enable1, 0x00);
rfm22_write(rfm22_header_enable0, 0x00);
// rfm22_write(rfm22_modem_test, 0x01);
rfm22_write(rfm22_agc_override1, rfm22_agc_ovr1_agcen);
// rfm22_write(rfm22_agc_override1, rfm22_agc_ovr1_sgi | rfm22_agc_ovr1_agcen);
rfm22_write(rfm22_frequency_hopping_step_size, frequency_hop_step_size_reg); // set frequency hopping channel step size (multiples of 10kHz)
rfm22_setNominalCarrierFrequency((min_frequency_hz + max_frequency_hz) / 2); // set our nominal carrier frequency
rfm22_write(rfm22_tx_power, rfm22_tx_pwr_papeaken | rfm22_tx_pwr_papeaklvl_0 | rfm22_tx_pwr_lna_sw | tx_power); // set the tx power
// rfm22_write(rfm22_vco_current_trimming, 0x7f);
// rfm22_write(rfm22_vco_calibration_override, 0x40);
// rfm22_write(rfm22_chargepump_current_trimming_override, 0x80);
rfm22_write(rfm22_tx_fifo_control1, TX_FIFO_HI_WATERMARK); // TX FIFO Almost Full Threshold (0 - 63)
rfm22_write(rfm22_tx_fifo_control2, TX_FIFO_LO_WATERMARK); // TX FIFO Almost Empty Threshold (0 - 63)
rfm22_write(rfm22_rx_fifo_control, RX_FIFO_HI_WATERMARK); // RX FIFO Almost Full Threshold (0 - 63)
#if defined(RFM22_EXT_INT_USE)
// Enable RF module external interrupt
rfm22_enableExtInt();
#endif
rfm22_setRxMode();
initialized = true;
return 0; // ok
}
// ************************************

View File

@ -0,0 +1,320 @@
/**
******************************************************************************
*
* @file saved_settings.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief RF Module hardware layer
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include <string.h> // memmove, memset
#include "crc.h"
#include "gpio_in.h"
#include "saved_settings.h"
#include "main.h"
#if defined(PIOS_COM_DEBUG)
#define SAVED_SETTINGS_DEBUG
#endif
// *****************************************************************
// default aes 128-bit encryption key
const uint8_t saved_settings_default_aes_key[16] = {0x65, 0x3b, 0x71, 0x89, 0x4a, 0xf4, 0xc8, 0xcb, 0x18, 0xd4, 0x9b, 0x4d, 0x4a, 0xbe, 0xc8, 0x37};
// *****************************************************************
#define pages 1 // number of flash pages to use
uint32_t eeprom_addr; // the address of the emulated EEPROM area in program flash area
uint16_t eeprom_page_size; // flash page size
volatile t_saved_settings saved_settings __attribute__ ((aligned(4))); // a RAM copy of the settings stored in EEPROM
t_saved_settings tmp_settings __attribute__ ((aligned(4)));
// *****************************************************************
// Private functions
bool saved_settings_page_empty(int page)
{ // return TRUE if the flash page is emtpy (erased), otherwise return FALSE
if (page < 0 || page >= pages)
return FALSE;
__IO uint32_t *addr = (__IO uint32_t *)(eeprom_addr + eeprom_page_size * page);
int32_t len = eeprom_page_size / 4;
for (int32_t i = len; i > 0; i--)
if (*addr++ != 0xffffffff)
return FALSE; // the page is not erased
return TRUE;
}
bool saved_settings_settings_empty(uint32_t addr)
{ // return TRUE if the settings flash area is emtpy (erased), otherwise return FALSE
__IO uint8_t *p = (__IO uint8_t *)addr;
for (int32_t i = sizeof(t_saved_settings); i > 0; i--)
if (*p++ != 0xff)
return FALSE; // the flash area is not empty/erased
return TRUE;
}
// *****************************************************************
int32_t saved_settings_read(void)
{ // look for the last valid settings saved in EEPROM
uint32_t flash_addr;
__IO uint8_t *p1;
uint8_t *p2;
flash_addr = eeprom_addr;
if (saved_settings_settings_empty(flash_addr))
{
#if defined(SAVED_SETTINGS_DEBUG)
DEBUG_PRINTF("settings Read, no settings found at %08X\r\n", flash_addr);
#endif
return -1; // no settings found at the specified addr
}
// copy the data from program flash area into temp settings area
p1 = (__IO uint8_t *)flash_addr;
p2 = (uint8_t *)&tmp_settings;
for (int32_t i = 0; i < sizeof(t_saved_settings); i++)
*p2++ = *p1++;
// calculate and check the CRC
uint32_t crc1 = tmp_settings.crc;
tmp_settings.crc = 0;
uint32_t crc2 = UpdateCRC32Data(0xffffffff, (void *)&tmp_settings, sizeof(t_saved_settings));
if (crc2 != crc1)
{
#if defined(SAVED_SETTINGS_DEBUG)
DEBUG_PRINTF("settings Read crc error: %08X %08X\r\n", crc1, crc2);
#endif
return -2; // error
}
memmove((void *)&saved_settings, (void *)&tmp_settings, sizeof(t_saved_settings));
#if defined(SAVED_SETTINGS_DEBUG)
DEBUG_PRINTF("settings Read OK!\r\n");
#endif
return 0; // OK
}
// *****************************************************************
// Public functions
int32_t saved_settings_save(void)
{ // save the settings into EEPROM
FLASH_Status fs;
uint32_t flash_addr;
uint8_t *p1;
__IO uint8_t *p2;
uint32_t *p3;
bool do_save;
// size of the settings aligned to 4 bytes
// uint16_t settings_size = (uint16_t)(sizeof(t_saved_settings) + 3) & 0xfffc;
// address of settings in FLASH area
flash_addr = eeprom_addr;
// *****************************************
// calculate and add the CRC
saved_settings.crc = 0;
saved_settings.crc = UpdateCRC32Data(0xffffffff, (void *)&saved_settings, sizeof(t_saved_settings));
// *****************************************
// first check to see if we need to save the settings
p1 = (uint8_t *)&saved_settings;
p2 = (__IO uint8_t *)flash_addr;
do_save = FALSE;
for (int32_t i = 0; i < sizeof(t_saved_settings); i++)
{
if (*p1++ != *p2++)
{ // we need to save the settings
do_save = TRUE;
break;
}
}
if (!do_save)
{
#if defined(SAVED_SETTINGS_DEBUG)
DEBUG_PRINTF("settings already saved OK\r\n");
#endif
return 0; // settings already saved .. all OK
}
// *****************************************
// Unlock the Flash Program Erase controller
FLASH_Unlock();
if (!saved_settings_page_empty(0))
{ // erase the page
#if defined(SAVED_SETTINGS_DEBUG)
DEBUG_PRINTF("settings erasing page .. ");
#endif
fs = FLASH_ErasePage(eeprom_addr);
if (fs != FLASH_COMPLETE)
{ // error
FLASH_Lock();
#if defined(SAVED_SETTINGS_DEBUG)
DEBUG_PRINTF("error %d\r\n", fs);
#endif
return -1;
}
#if defined(SAVED_SETTINGS_DEBUG)
DEBUG_PRINTF("OK\r\n");
#endif
}
else
{
#if defined(SAVED_SETTINGS_DEBUG)
DEBUG_PRINTF("settings page already erased\r\n");
#endif
}
// *****************************************
// save the settings into flash area (emulated EEPROM area)
p1 = (uint8_t *)&saved_settings;
p3 = (uint32_t *)flash_addr;
// write 4 bytes at a time into program flash area (emulated EEPROM area)
for (int32_t i = 0; i < sizeof(t_saved_settings); p3++)
{
uint32_t value = 0;
if (i < sizeof(t_saved_settings)) value |= (uint32_t)*p1++ << 0; else value |= 0x000000ff; i++;
if (i < sizeof(t_saved_settings)) value |= (uint32_t)*p1++ << 8; else value |= 0x0000ff00; i++;
if (i < sizeof(t_saved_settings)) value |= (uint32_t)*p1++ << 16; else value |= 0x00ff0000; i++;
if (i < sizeof(t_saved_settings)) value |= (uint32_t)*p1++ << 24; else value |= 0xff000000; i++;
fs = FLASH_ProgramWord((uint32_t)p3, value); // write a 32-bit value
if (fs != FLASH_COMPLETE)
{
FLASH_Lock();
#if defined(SAVED_SETTINGS_DEBUG)
DEBUG_PRINTF("settings FLASH_ProgramWord error: %d\r\n", fs);
#endif
return -2; // error
}
}
// Lock the Flash Program Erase controller
FLASH_Lock();
// *****************************************
// now error check it by reading it back (simple compare)
p1 = (uint8_t *)&saved_settings;
p2 = (__IO uint8_t *)flash_addr;
for (int32_t i = 0; i < sizeof(t_saved_settings); i++)
{
if (*p1++ != *p2++)
{
#if defined(SAVED_SETTINGS_DEBUG)
DEBUG_PRINTF("settings WriteSettings compare error\r\n");
#endif
return -3; // error
}
}
// *****************************************
#if defined(SAVED_SETTINGS_DEBUG)
DEBUG_PRINTF("settings Save OK!\r\n");
#endif
return 0; // OK
}
void saved_settings_init(void)
{
// **********
// determine emulated EEPROM details
if (flash_size < 256000)
eeprom_page_size = 1024; // 1 kByte
else
eeprom_page_size = 2048; // 2 kByte
// place emulated eeprom at end of program flash area
eeprom_addr = (0x08000000 + flash_size) - (eeprom_page_size * pages);
#if defined(SAVED_SETTINGS_DEBUG)
DEBUG_PRINTF("\r\n");
DEBUG_PRINTF("settings eeprom addr: %08x\r\n", eeprom_addr);
DEBUG_PRINTF("settings eeprom page size: %u\r\n", eeprom_page_size);
DEBUG_PRINTF("settings eeprom pages: %u\r\n", pages);
#endif
// **********
// default settings
memset((void *)&saved_settings, 0xff, sizeof(t_saved_settings));
saved_settings.destination_id = 0;
saved_settings.frequency_band = freqBand_UNKNOWN;
saved_settings.rf_xtal_cap = 0x7f;
saved_settings.aes_enable = FALSE;
memmove((void *)&saved_settings.aes_key, saved_settings_default_aes_key, sizeof(saved_settings.aes_key));
// saved_settings.crc = 0;
// saved_settings.crc = UpdateCRC32Data(0xffffffff, (void *)&saved_settings, sizeof(t_saved_settings));
// **********
// Lock the Flash Program Erase controller
FLASH_Lock();
saved_settings_read();
// **********
}
// *****************************************************************

View File

@ -0,0 +1,216 @@
/**
******************************************************************************
*
* @file transparent_comms.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief Serial communication port handling routines
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include <string.h>
#include "stm32f10x.h"
#include "gpio_in.h"
#include "transparent_comms.h"
#include "packet_handler.h"
#include "main.h"
#if defined(PIOS_COM_DEBUG)
#define TRANS_DEBUG
#endif
// *****************************************************************************
// local variables
int8_t trans_previous_com_port = -1;
volatile uint16_t trans_rx_timer = 0;
volatile uint16_t trans_tx_timer = 0;
uint8_t trans_temp_buffer1[128];
uint8_t trans_temp_buffer2[128];
uint16_t trans_temp_buffer2_wr;
// *****************************************************************************
// can be called from an interrupt if you wish
void trans_1ms_tick(void)
{ // call this once every 1ms
if (trans_rx_timer < 0xffff) trans_rx_timer++;
if (trans_tx_timer < 0xffff) trans_tx_timer++;
}
// *****************************************************************************
// call this as often as possible - not from an interrupt
void trans_process(void)
{ // copy data from comm-port RX buffer to RF packet handler TX buffer, and from RF packet handler RX buffer to comm-port TX buffer
// ********************
// decide which comm-port we are using (usart or usb)
bool usb_comms = false; // TRUE if we are using the usb port for comms.
uint8_t comm_port = PIOS_COM_SERIAL; // default to using the usart comm-port
#if defined(PIOS_INCLUDE_USB_HID)
if (PIOS_USB_HID_CheckAvailable(0))
{ // USB comms is up, use the USB comm-port instead of the USART comm-port
usb_comms = true;
comm_port = PIOS_COM_TELEM_USB;
}
#endif
// ********************
// check to see if the local communication port has changed (usart/usb)
if (trans_previous_com_port < 0 && trans_previous_com_port != comm_port)
{ // the local communications port has changed .. remove any data in the buffers
trans_temp_buffer2_wr = 0;
}
else
if (usb_comms)
{ // we're using the USB for comms - keep the USART rx buffer empty
int32_t bytes = PIOS_COM_ReceiveBufferUsed(PIOS_COM_SERIAL);
while (bytes > 0)
{
PIOS_COM_ReceiveBuffer(PIOS_COM_SERIAL);
bytes--;
}
}
trans_previous_com_port = comm_port; // remember the current comm-port we are using
// ********************
uint16_t connection_index = 0; // the RF connection we are using
// ********************
// send the data received down the comm-port to the RF packet handler TX buffer
// free space size in the RF packet handler tx buffer
uint16_t ph_num = ph_putData_free(connection_index);
// get the number of data bytes received down the comm-port
int32_t com_num = PIOS_COM_ReceiveBufferUsed(comm_port);
// set the USART RTS handshaking line
if (!usb_comms)
{
if (ph_num < 32 || !ph_connected(connection_index))
SERIAL_RTS_CLEAR; // lower the USART RTS line - we don't have space in the buffer for anymore bytes
else
SERIAL_RTS_SET; // release the USART RTS line - we have space in the buffer for now bytes
}
else
SERIAL_RTS_SET; // release the USART RTS line
// limit number of bytes we will get to the size of the temp buffer
if (com_num > sizeof(trans_temp_buffer1))
com_num = sizeof(trans_temp_buffer1);
// limit number of bytes we will get to the size of the free space in the RF packet handler TX buffer
if (com_num > ph_num)
com_num = ph_num;
// copy data received down the comm-port into our temp buffer
register uint16_t bytes_saved = 0;
while (bytes_saved < com_num)
trans_temp_buffer1[bytes_saved++] = PIOS_COM_ReceiveBuffer(comm_port);
// put the received comm-port data bytes into the RF packet handler TX buffer
if (bytes_saved > 0)
{
trans_rx_timer = 0;
ph_putData(connection_index, trans_temp_buffer1, bytes_saved);
}
// ********************
// send the data received via the RF link out the comm-port
if (trans_temp_buffer2_wr < sizeof(trans_temp_buffer2))
{
// get number of data bytes received via the RF link
ph_num = ph_getData_used(connection_index);
// limit to how much space we have in the temp buffer
if (ph_num > sizeof(trans_temp_buffer2) - trans_temp_buffer2_wr)
ph_num = sizeof(trans_temp_buffer2) - trans_temp_buffer2_wr;
if (ph_num > 0)
{ // fetch the data bytes received via the RF link and save into our temp buffer
ph_num = ph_getData(connection_index, trans_temp_buffer2 + trans_temp_buffer2_wr, ph_num);
trans_temp_buffer2_wr += ph_num;
}
}
#if (defined(PIOS_COM_DEBUG) && (PIOS_COM_DEBUG == PIOS_COM_SERIAL))
if (!usb_comms)
{ // the serial-port is being used for debugging - don't send data down it
trans_temp_buffer2_wr = 0;
trans_tx_timer = 0;
return;
}
#endif
if (trans_temp_buffer2_wr > 0)
{ // we have data in our temp buffer that needs sending out the comm-port
if (usb_comms || (!usb_comms && GPIO_IN(SERIAL_CTS_PIN)))
{ // we are OK to send the data out the comm-port
// send the data out the comm-port
int32_t res;
// if (usb_comms)
// res = PIOS_COM_SendBuffer(comm_port, trans_temp_buffer2, trans_temp_buffer2_wr);
// else
res = PIOS_COM_SendBufferNonBlocking(comm_port, trans_temp_buffer2, trans_temp_buffer2_wr); // this one doesn't work properly with USB :(
if (res >= 0)
{ // data was sent out the comm-port OK .. remove the sent data from the temp buffer
trans_temp_buffer2_wr = 0;
trans_tx_timer = 0;
}
else
{ // failed to send the data out the comm-port
#if defined(TRANS_DEBUG)
DEBUG_PRINTF("PIOS_COM_SendBuffer %d %d\r\n", trans_temp_buffer2_wr, res);
#endif
if (trans_tx_timer >= 5000)
trans_temp_buffer2_wr = 0; // seems we can't send our data for at least the last 5 seconds - delete it
}
}
}
// ********************
}
// *****************************************************************************
void trans_init(void)
{
trans_previous_com_port = -1;
trans_temp_buffer2_wr = 0;
trans_rx_timer = 0;
trans_tx_timer = 0;
}
// *****************************************************************************

View File

@ -0,0 +1,442 @@
/**
******************************************************************************
*
* @file uavtalk_comms.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief RF Module hardware layer
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
// see http://newwiki.openpilot.org/display/Doc/UAVTalk .. for UAVTalk protocol description
//
// This module scans for OP UAVTalk packets in the comm-port or RF data streams.
// It will discard any corrupt/invalid packets and only pass valid ones.
#include <string.h>
#include "stm32f10x.h"
#include "gpio_in.h"
#include "uavtalk_comms.h"
#include "packet_handler.h"
#include "main.h"
#if defined(PIOS_COM_DEBUG)
#define UAVTALK_DEBUG
#endif
// *****************************************************************************
typedef struct
{
uint8_t sync_byte;
uint8_t message_type;
uint16_t packet_size; // not including CRC byte
uint32_t object_id;
} __attribute__((__packed__)) t_uav_header1;
typedef struct
{
uint8_t sync_byte;
uint8_t message_type;
uint16_t packet_size; // not including CRC byte
uint32_t object_id;
uint16_t instance_id;
} __attribute__((__packed__)) t_uav_header2;
#define SYNC_VAL 0x3C
#define TYPE_MASK 0xFC
#define TYPE_VER 0x20
#define TYPE_OBJ (TYPE_VER | 0x00)
#define TYPE_OBJ_REQ (TYPE_VER | 0x01)
#define TYPE_OBJ_ACK (TYPE_VER | 0x02)
#define TYPE_ACK (TYPE_VER | 0x03)
#define MIN_HEADER_LENGTH sizeof(t_uav_header1)
#define MAX_HEADER_LENGTH sizeof(t_uav_header2)
#define MAX_PAYLOAD_LENGTH 256
#define CHECKSUM_LENGTH 1
#define MAX_PACKET_LENGTH (MAX_HEADER_LENGTH + MAX_PAYLOAD_LENGTH + CHECKSUM_LENGTH)
// CRC lookup table
static const uint8_t crc_table[256] = {
0x00, 0x07, 0x0e, 0x09, 0x1c, 0x1b, 0x12, 0x15, 0x38, 0x3f, 0x36, 0x31, 0x24, 0x23, 0x2a, 0x2d,
0x70, 0x77, 0x7e, 0x79, 0x6c, 0x6b, 0x62, 0x65, 0x48, 0x4f, 0x46, 0x41, 0x54, 0x53, 0x5a, 0x5d,
0xe0, 0xe7, 0xee, 0xe9, 0xfc, 0xfb, 0xf2, 0xf5, 0xd8, 0xdf, 0xd6, 0xd1, 0xc4, 0xc3, 0xca, 0xcd,
0x90, 0x97, 0x9e, 0x99, 0x8c, 0x8b, 0x82, 0x85, 0xa8, 0xaf, 0xa6, 0xa1, 0xb4, 0xb3, 0xba, 0xbd,
0xc7, 0xc0, 0xc9, 0xce, 0xdb, 0xdc, 0xd5, 0xd2, 0xff, 0xf8, 0xf1, 0xf6, 0xe3, 0xe4, 0xed, 0xea,
0xb7, 0xb0, 0xb9, 0xbe, 0xab, 0xac, 0xa5, 0xa2, 0x8f, 0x88, 0x81, 0x86, 0x93, 0x94, 0x9d, 0x9a,
0x27, 0x20, 0x29, 0x2e, 0x3b, 0x3c, 0x35, 0x32, 0x1f, 0x18, 0x11, 0x16, 0x03, 0x04, 0x0d, 0x0a,
0x57, 0x50, 0x59, 0x5e, 0x4b, 0x4c, 0x45, 0x42, 0x6f, 0x68, 0x61, 0x66, 0x73, 0x74, 0x7d, 0x7a,
0x89, 0x8e, 0x87, 0x80, 0x95, 0x92, 0x9b, 0x9c, 0xb1, 0xb6, 0xbf, 0xb8, 0xad, 0xaa, 0xa3, 0xa4,
0xf9, 0xfe, 0xf7, 0xf0, 0xe5, 0xe2, 0xeb, 0xec, 0xc1, 0xc6, 0xcf, 0xc8, 0xdd, 0xda, 0xd3, 0xd4,
0x69, 0x6e, 0x67, 0x60, 0x75, 0x72, 0x7b, 0x7c, 0x51, 0x56, 0x5f, 0x58, 0x4d, 0x4a, 0x43, 0x44,
0x19, 0x1e, 0x17, 0x10, 0x05, 0x02, 0x0b, 0x0c, 0x21, 0x26, 0x2f, 0x28, 0x3d, 0x3a, 0x33, 0x34,
0x4e, 0x49, 0x40, 0x47, 0x52, 0x55, 0x5c, 0x5b, 0x76, 0x71, 0x78, 0x7f, 0x6a, 0x6d, 0x64, 0x63,
0x3e, 0x39, 0x30, 0x37, 0x22, 0x25, 0x2c, 0x2b, 0x06, 0x01, 0x08, 0x0f, 0x1a, 0x1d, 0x14, 0x13,
0xae, 0xa9, 0xa0, 0xa7, 0xb2, 0xb5, 0xbc, 0xbb, 0x96, 0x91, 0x98, 0x9f, 0x8a, 0x8d, 0x84, 0x83,
0xde, 0xd9, 0xd0, 0xd7, 0xc2, 0xc5, 0xcc, 0xcb, 0xe6, 0xe1, 0xe8, 0xef, 0xfa, 0xfd, 0xf4, 0xf3
};
// *****************************************************************************
// local variables
int8_t uavtalk_previous_com_port = -1;
volatile uint16_t uavtalk_rx_timer = 0;
volatile uint16_t uavtalk_tx_timer = 0;
uint8_t uavtalk_rx_buffer[MAX_PACKET_LENGTH] __attribute__ ((aligned(4)));
uint16_t uavtalk_rx_buffer_wr;
uint8_t uavtalk_tx_buffer[MAX_PACKET_LENGTH] __attribute__ ((aligned(4)));
uint16_t uavtalk_tx_buffer_wr;
// *****************************************************************************
// 8-bit CRC updating
uint8_t uavtalk_updateCRC_byte(uint8_t crc, uint8_t b)
{
return crc_table[crc ^ b];
}
uint8_t uavtalk_updateCRC_buffer(uint8_t crc, const void *data, int32_t length)
{
// use registers for speed
register uint8_t crc8 = crc;
register const uint8_t *p = (uint8_t *)data;
for (register int32_t i = length; i > 0; i--)
crc8 = crc_table[crc8 ^ *p++];
return crc8;
}
// *****************************************************************************
// returned value < 0 if no valid packet detected.
// otherwise returned value is the total size of the valid UAVTalk packet found in the buffer.
//
// any corrupt/invalid UAVTalk packets/data are deleted from the buffer and we scan for the next valid packet.
int16_t uavtalk_scanForPacket(void *buf, uint16_t *len)
{
uint8_t *buffer = (uint8_t *)buf;
t_uav_header1 *header1 = (t_uav_header1 *)buf;
// t_uav_header2 *header2 = (t_uav_header2 *)buf;
register uint16_t num_bytes = *len;
if (num_bytes < MIN_HEADER_LENGTH + CHECKSUM_LENGTH)
return -1; // not yet enough bytes for a complete packet
while (TRUE)
{
// scan the buffer for the start of a UAVTalk packet
for (uint16_t i = 0; i < num_bytes; i++)
{
if (uavtalk_rx_buffer[i] != SYNC_VAL)
continue; // not the start of a packet - move on to the next byte in the buffer
// possible start of packet found - we found a SYNC byte
if (i > 0)
{ // remove/delete leading bytes before the SYNC byte
num_bytes -= i;
if (num_bytes > 0)
memmove(buffer, buffer + i, num_bytes);
*len = num_bytes;
}
break;
}
if (num_bytes < MIN_HEADER_LENGTH + CHECKSUM_LENGTH)
return -2; // not yet enough bytes for a complete packet
if (header1->sync_byte != SYNC_VAL)
{ // SYNC byte was not found - start of UAVTalk packet not found in any of the data in the buffer
*len = 0; // empty the entire buffer
return -3;
}
if (header1->packet_size < MIN_HEADER_LENGTH || header1->packet_size > MAX_HEADER_LENGTH + MAX_PAYLOAD_LENGTH)
{ // the packet size value is too small or too big - assume either a corrupt UAVTalk packet or we are at the start of a packet
// if (--num_bytes > 0)
// memmove(buffer, buffer + 1, num_bytes); // remove 1st byte
// *len = num_bytes;
buffer[0] ^= 0xaa; // corrupt the sync byte - we'll move the buffer bytes down further up in the code
continue; // continue scanning for a valid packet in the buffer
}
if (num_bytes < header1->packet_size + CHECKSUM_LENGTH)
{ // not yet enough bytes for a complete packet
return -4;
}
// check the packet CRC
uint8_t crc1 = uavtalk_updateCRC_buffer(0, buffer, header1->packet_size);
uint8_t crc2 = buffer[header1->packet_size];
if (crc1 != crc2)
{ // faulty CRC
// if (--num_bytes > 0)
// memmove(buffer, buffer + 1, num_bytes); // remove 1st byte
// *len = num_bytes;
buffer[0] ^= 0xaa; // corrupt the sync byte - we'll move the buffer bytes down further up in the code
#if defined(UAVTALK_DEBUG)
DEBUG_PRINTF("UAVTalk packet corrupt %d\r\n", header1->packet_size + 1);
#endif
continue; // continue scanning for a valid packet in the buffer
}
#if defined(UAVTALK_DEBUG)
DEBUG_PRINTF("UAVTalk packet found %d\r\n", header1->packet_size + 1);
#endif
return (header1->packet_size + CHECKSUM_LENGTH); // return the size of the UAVTalk packet
}
return -5;
}
// *****************************************************************************
// can be called from an interrupt if you wish
void uavtalk_1ms_tick(void)
{ // call this once every 1ms
if (uavtalk_rx_timer < 0xffff) uavtalk_rx_timer++;
if (uavtalk_tx_timer < 0xffff) uavtalk_tx_timer++;
}
// *****************************************************************************
// call this as often as possible - not from an interrupt
void uavtalk_process(void)
{ // copy data from comm-port RX buffer to RF packet handler TX buffer, and from RF packet handler RX buffer to comm-port TX buffer
// ********************
// decide which comm-port we are using (usart or usb)
bool usb_comms = false; // TRUE if we are using the usb port for comms.
uint8_t comm_port = PIOS_COM_SERIAL; // default to using the usart comm-port
#if defined(PIOS_INCLUDE_USB_HID)
if (PIOS_USB_HID_CheckAvailable(0))
{ // USB comms is up, use the USB comm-port instead of the USART comm-port
usb_comms = true;
comm_port = PIOS_COM_TELEM_USB;
}
#endif
// ********************
// check to see if the local communication port has changed (usart/usb)
if (uavtalk_previous_com_port < 0 && uavtalk_previous_com_port != comm_port)
{ // the local communications port has changed .. remove any data in the buffers
uavtalk_rx_buffer_wr = 0;
uavtalk_tx_buffer_wr = 0;
}
else
if (usb_comms)
{ // we're using the USB for comms - keep the USART rx buffer empty
int32_t bytes = PIOS_COM_ReceiveBufferUsed(PIOS_COM_SERIAL);
while (bytes > 0)
{
PIOS_COM_ReceiveBuffer(PIOS_COM_SERIAL);
bytes--;
}
}
uavtalk_previous_com_port = comm_port; // remember the current comm-port we are using
// ********************
uint16_t connection_index = 0; // the RF connection we are using
// ********************
// send the data received down the comm-port to the RF packet handler TX buffer
while (TRUE)
{
// free space size in the RF packet handler tx buffer
uint16_t ph_num = ph_putData_free(connection_index);
// get the number of data bytes received down the comm-port
int32_t com_num = PIOS_COM_ReceiveBufferUsed(comm_port);
// set the USART RTS handshaking line
if (!usb_comms && ph_connected(connection_index))
{
if (ph_num < 32)
SERIAL_RTS_CLEAR; // lower the USART RTS line - we don't have space in the buffer for anymore bytes
else
SERIAL_RTS_SET; // release the USART RTS line - we have space in the buffer for now bytes
}
else
SERIAL_RTS_SET; // release the USART RTS line
// limit number of bytes we will get to how much space we have in our RX buffer
if (com_num > sizeof(uavtalk_rx_buffer) - uavtalk_rx_buffer_wr)
com_num = sizeof(uavtalk_rx_buffer) - uavtalk_rx_buffer_wr;
while (com_num > 0)
{ // fetch a byte from the comm-port RX buffer and save it into our RX buffer
uavtalk_rx_buffer[uavtalk_rx_buffer_wr++] = PIOS_COM_ReceiveBuffer(comm_port);
com_num--;
}
int16_t packet_size = uavtalk_scanForPacket(uavtalk_rx_buffer, &uavtalk_rx_buffer_wr);
if (packet_size < 0)
break; // no UAVTalk packet in our RX buffer
uavtalk_rx_timer = 0;
if (!ph_connected(connection_index))
{ // we don't have a link to a remote modem .. remove the UAVTalk packet from our RX buffer
if (uavtalk_rx_buffer_wr > packet_size)
{
uavtalk_rx_buffer_wr -= packet_size;
memmove(uavtalk_rx_buffer, uavtalk_rx_buffer + packet_size, uavtalk_rx_buffer_wr);
}
else
uavtalk_rx_buffer_wr = 0;
continue;
}
if (ph_num < packet_size)
break; // not enough room in the RF packet handler TX buffer for the UAVTalk packet
// copy the rx'ed UAVTalk packet into the RF packet handler TX buffer for sending over the RF link
ph_putData(connection_index, uavtalk_rx_buffer, packet_size);
// remove the UAVTalk packet from our RX buffer
if (uavtalk_rx_buffer_wr > packet_size)
{
uavtalk_rx_buffer_wr -= packet_size;
memmove(uavtalk_rx_buffer, uavtalk_rx_buffer + packet_size, uavtalk_rx_buffer_wr);
}
else
uavtalk_rx_buffer_wr = 0;
}
// ********************
// send the data received via the RF link out the comm-port
while (TRUE)
{
// get number of data bytes received via the RF link
uint16_t ph_num = ph_getData_used(connection_index);
// limit to how much space we have in the temp TX buffer
if (ph_num > sizeof(uavtalk_tx_buffer) - uavtalk_tx_buffer_wr)
ph_num = sizeof(uavtalk_tx_buffer) - uavtalk_tx_buffer_wr;
if (ph_num > 0)
{ // fetch the data bytes received via the RF link and save into our temp buffer
ph_num = ph_getData(connection_index, uavtalk_tx_buffer + uavtalk_tx_buffer_wr, ph_num);
uavtalk_tx_buffer_wr += ph_num;
}
int16_t packet_size = uavtalk_scanForPacket(uavtalk_tx_buffer, &uavtalk_tx_buffer_wr);
if (packet_size <= 0)
break; // no UAV Talk packet found
// we have a UAVTalk packet to send down the comm-port
/*
#if (defined(PIOS_COM_DEBUG) && (PIOS_COM_DEBUG == PIOS_COM_SERIAL))
if (!usb_comms)
{ // the serial-port is being used for debugging - don't send data down it
uavtalk_tx_buffer_wr = 0;
uavtalk_tx_timer = 0;
continue;
}
#endif
*/
if (!usb_comms && !GPIO_IN(SERIAL_CTS_PIN))
break; // we can't yet send data down the comm-port
// send the data out the comm-port
int32_t res;
// if (usb_comms)
// res = PIOS_COM_SendBuffer(comm_port, uavtalk_tx_buffer, packet_size);
// else
res = PIOS_COM_SendBufferNonBlocking(comm_port, uavtalk_tx_buffer, packet_size); // this one doesn't work properly with USB :(
if (res < 0)
{ // failed to send the data out the comm-port
#if defined(UAVTALK_DEBUG)
DEBUG_PRINTF("PIOS_COM_SendBuffer %d %d\r\n", packet_size, res);
#endif
if (uavtalk_tx_timer >= 5000)
{ // seems we can't send our data for at least the last 5 seconds - delete it
if (uavtalk_tx_buffer_wr > packet_size)
{
uavtalk_tx_buffer_wr -= packet_size;
memmove(uavtalk_tx_buffer, uavtalk_tx_buffer + packet_size, uavtalk_tx_buffer_wr);
}
else
uavtalk_tx_buffer_wr = 0;
}
break;
}
// data was sent out the comm-port OK .. remove the sent data from our buffer
if (uavtalk_tx_buffer_wr > packet_size)
{
uavtalk_tx_buffer_wr -= packet_size;
memmove(uavtalk_tx_buffer, uavtalk_tx_buffer + packet_size, uavtalk_tx_buffer_wr);
}
else
uavtalk_tx_buffer_wr = 0;
uavtalk_tx_timer = 0;
}
// ********************
}
// *****************************************************************************
void uavtalk_init(void)
{
uavtalk_previous_com_port = -1;
uavtalk_rx_buffer_wr = 0;
uavtalk_tx_buffer_wr = 0;
uavtalk_rx_timer = 0;
uavtalk_tx_timer = 0;
}
// *****************************************************************************