1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2024-12-01 09:24:10 +01:00

OP-378 - OP/INS - Add initial support for INS. HMC5883, BMP085, BMA180, IMU300 all added. Throrough verification has not been done on any of them. main() simply calls self-test functions on all of the hardware.

AHRS_comms still needs to be implemented.  INS/GPS functionality still needs to be implemented.  Double-check of the new drivers still needs to be done.


git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@3162 ebee16cc-31ac-478f-84a7-5cbb03baadba
This commit is contained in:
chebuzz 2011-04-14 12:46:39 +00:00 committed by chebuzz
parent 7fcde2f248
commit 06443b4281
17 changed files with 3744 additions and 1 deletions

View File

@ -266,7 +266,7 @@ uavobjects_clean:
#
##############################
FW_TARGETS := openpilot ahrs coptercontrol pipxtreme
FW_TARGETS := openpilot ahrs coptercontrol pipxtreme ins
BL_TARGETS := $(addprefix bl_, $(FW_TARGETS))
.PHONY: all_fw all_fw_clean
@ -377,6 +377,31 @@ bl_pipxtreme_clean:
$(V0) @echo " CLEAN $@"
$(V1) $(RM) -fr $(BUILD_DIR)/bl_pipxtreme
.PHONY: ins
ins: ins_bin
ins_%: uavobjects_flight
$(V1) mkdir -p $(BUILD_DIR)/ins/dep
$(V1) $(MAKE) -r --no-print-directory OUTDIR="$(BUILD_DIR)/ins" TCHAIN_PREFIX="$(ARM_SDK_PREFIX)" REMOVE_CMD="$(RM)" OOCD_EXE="$(OPENOCD)" -C $(ROOT_DIR)/flight/INS $*
.PHONY: ins_clean
ins_clean:
$(V0) @echo " CLEAN $@"
$(V1) $(RM) -fr $(BUILD_DIR)/ins
.PHONY: bl_ins
bl_ins: bl_ins_elf
bl_ins_%:
$(V1) mkdir -p $(BUILD_DIR)/bl_ins/dep
$(V1) $(MAKE) -r --no-print-directory OUTDIR="$(BUILD_DIR)/bl_ins" TCHAIN_PREFIX="$(ARM_SDK_PREFIX)" REMOVE_CMD="$(RM)" OOCD_EXE="$(OPENOCD)" -C $(ROOT_DIR)/flight/Bootloaders/INS $*
.PHONY: bl_ins_clean
bl_ins_clean:
$(V0) @echo " CLEAN $@"
$(V1) $(RM) -fr $(BUILD_DIR)/bl_ins
.PHONY: sim_posix
sim_posix: sim_posix_elf

479
flight/INS/Makefile Normal file
View File

@ -0,0 +1,479 @@
#####
# Project: OpenPilot INS
#
#
# Makefile for OpenPilot INS project
#
# The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2011.
#
#
# 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
#####
WHEREAMI := $(dir $(lastword $(MAKEFILE_LIST)))
TOP := $(realpath $(WHEREAMI)/../../)
include $(TOP)/make/firmware-defs.mk
# Set developer code and compile options
# Set to YES for debugging
DEBUG ?= YES
USE_BOOTLOADER ?= NO
# Set to YES when using Code Sourcery toolchain
CODE_SOURCERY ?= YES
ifeq ($(CODE_SOURCERY), YES)
REMOVE_CMD = cs-rm
else
REMOVE_CMD = rm
endif
FLASH_TOOL = OPENOCD
# MCU name, submodel and board
# - MCU used for compiler-option (-mcpu)
# - MODEL used for linker-script name (-T) and passed as define
# - BOARD just passed as define (optional)
MCU = cortex-m3
CHIP = STM32F103RET
BOARD = STM3210E_INS
MODEL = HD
ifeq ($(USE_BOOTLOADER), YES)
BOOT_MODEL = $(MODEL)_BL
else
BOOT_MODEL = $(MODEL)_NB
endif
# Directory for output files (lst, obj, dep, elf, sym, map, hex, bin etc.)
OUTDIR = $(TOP)/build/ins
# Target file name (without extension).
TARGET = INS
# Paths
INS = ./
INSINC = $(INS)/inc
PIOS = ../PiOS
PIOSINC = $(PIOS)/inc
FLIGHTLIB = ../Libraries
FLIGHTLIBINC = ../Libraries/inc
PIOSSTM32F10X = $(PIOS)/STM32F10x
PIOSCOMMON = $(PIOS)/Common
PIOSBOARDS = $(PIOS)/Boards
APPLIBDIR = $(PIOSSTM32F10X)/Libraries
STMLIBDIR = $(APPLIBDIR)
STMSPDDIR = $(STMLIBDIR)/STM32F10x_StdPeriph_Driver
STMUSBDIR = $(STMLIBDIR)/STM32_USB-FS-Device_Driver
STMSPDSRCDIR = $(STMSPDDIR)/src
STMSPDINCDIR = $(STMSPDDIR)/inc
CMSISDIR = $(STMLIBDIR)/CMSIS/Core/CM3
OPDIR = ../OpenPilot
OPUAVOBJ = ../UAVObjects
OPUAVOBJINC = $(OPUAVOBJ)/inc
OPSYSINC = $(OPDIR)/System/inc
BOOT = ../Bootloaders/INS
BOOTINC = $(BOOT)/inc
OPUAVSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/flight
# List C source files here. (C dependencies are automatically generated.)
# use file-extension c for "c-only"-files
## INS:
SRC = ins.c
SRC += pios_board.c
#SRC += ins_timer.c
#SRC += insgps13state.c
SRC += $(FLIGHTLIB)/fifo_buffer.c
#SRC += $(FLIGHTLIB)/ins_spi_comm.c
#SRC += $(FLIGHTLIB)/ins_comm_objects.c
#SRC += $(FLIGHTLIB)/CoordinateConversions.c
#SRC += $(BOOT)/ins_spi_program_slave.c
#SRC += $(BOOT)/ins_slave_test.c
#SRC += $(BOOT)/ins_spi_program.c
## PIOS Hardware (STM32F10x)
SRC += $(PIOSSTM32F10X)/pios_sys.c
SRC += $(PIOSSTM32F10X)/pios_led.c
SRC += $(PIOSSTM32F10X)/pios_delay.c
SRC += $(PIOSSTM32F10X)/pios_usart.c
SRC += $(PIOSSTM32F10X)/pios_irq.c
SRC += $(PIOSSTM32F10X)/pios_i2c.c
SRC += $(PIOSSTM32F10X)/pios_debug.c
SRC += $(PIOSSTM32F10X)/pios_gpio.c
SRC += $(PIOSSTM32F10X)/pios_spi.c
SRC += $(PIOSSTM32F10X)/pios_exti.c
## PIOS Hardware (Common)
SRC += $(PIOSCOMMON)/pios_com.c
SRC += $(PIOSCOMMON)/printf-stdarg.c
SRC += $(PIOSCOMMON)/pios_iap.c
SRC += $(PIOSCOMMON)/pios_bma180.c
SRC += $(PIOSCOMMON)/pios_hmc5883.c
SRC += $(PIOSCOMMON)/pios_bmp085.c
SRC += $(PIOSCOMMON)/pios_imu3000.c
## CMSIS for STM32
SRC += $(CMSISDIR)/core_cm3.c
SRC += $(CMSISDIR)/system_stm32f10x.c
## Used parts of the STM-Library
SRC += $(STMSPDSRCDIR)/stm32f10x_adc.c
SRC += $(STMSPDSRCDIR)/stm32f10x_bkp.c
SRC += $(STMSPDSRCDIR)/stm32f10x_crc.c
SRC += $(STMSPDSRCDIR)/stm32f10x_dac.c
SRC += $(STMSPDSRCDIR)/stm32f10x_dma.c
SRC += $(STMSPDSRCDIR)/stm32f10x_exti.c
SRC += $(STMSPDSRCDIR)/stm32f10x_flash.c
SRC += $(STMSPDSRCDIR)/stm32f10x_gpio.c
SRC += $(STMSPDSRCDIR)/stm32f10x_i2c.c
SRC += $(STMSPDSRCDIR)/stm32f10x_pwr.c
SRC += $(STMSPDSRCDIR)/stm32f10x_rcc.c
SRC += $(STMSPDSRCDIR)/stm32f10x_rtc.c
SRC += $(STMSPDSRCDIR)/stm32f10x_spi.c
SRC += $(STMSPDSRCDIR)/stm32f10x_tim.c
SRC += $(STMSPDSRCDIR)/stm32f10x_usart.c
SRC += $(STMSPDSRCDIR)/misc.c
# List C source files here which must be compiled in ARM-Mode (no -mthumb).
# use file-extension c for "c-only"-files
## just for testing, timer.c could be compiled in thumb-mode too
SRCARM =
# List C++ source files here.
# use file-extension .cpp for C++-files (not .C)
CPPSRC =
# List C++ source files here which must be compiled in ARM-Mode.
# use file-extension .cpp for C++-files (not .C)
#CPPSRCARM = $(TARGET).cpp
CPPSRCARM =
# List Assembler source files here.
# Make them always end in a capital .S. Files ending in a lowercase .s
# will not be considered source files but generated files (assembler
# output from the compiler), and will be deleted upon "make clean"!
# Even though the DOS/Win* filesystem matches both .s and .S the same,
# it will preserve the spelling of the filenames, and gcc itself does
# care about how the name is spelled on its command-line.
ASRC = $(PIOSSTM32F10X)/startup_stm32f10x_$(MODEL).S
# List Assembler source files here which must be assembled in ARM-Mode..
ASRCARM =
# List any extra directories to look for include files here.
# Each directory must be seperated by a space.
EXTRAINCDIRS += $(PIOS)
EXTRAINCDIRS += $(PIOSINC)
EXTRAINCDIRS += $(FLIGHTLIBINC)
EXTRAINCDIRS += $(PIOSSTM32F10X)
EXTRAINCDIRS += $(PIOSCOMMON)
EXTRAINCDIRS += $(PIOSBOARDS)
EXTRAINCDIRS += $(STMSPDINCDIR)
EXTRAINCDIRS += $(CMSISDIR)
EXTRAINCDIRS += $(INSINC)
EXTRAINCDIRS += $(OPUAVSYNTHDIR)
EXTRAINCDIRS += $(BOOTINC)
# List any extra directories to look for library files here.
# Also add directories where the linker should search for
# includes from linker-script to the list
# Each directory must be seperated by a space.
EXTRA_LIBDIRS =
# Extra Libraries
# Each library-name must be seperated by a space.
# i.e. to link with libxyz.a, libabc.a and libefsl.a:
# EXTRA_LIBS = xyz abc efsl
# for newlib-lpc (file: libnewlibc-lpc.a):
# EXTRA_LIBS = newlib-lpc
EXTRA_LIBS =
# Path to Linker-Scripts
LINKERSCRIPTPATH = $(PIOSSTM32F10X)
# Optimization level, can be [0, 1, 2, 3, s].
# 0 = turn off optimization. s = optimize for size.
# (Note: 3 is not always the best optimization level. See avr-libc FAQ.)
ifeq ($(DEBUG),YES)
CFLAGS += -Os
CFLAGS += -DGENERAL_COV
else
CFLAGS += -Os
endif
# Output format. (can be ihex or binary or both)
# binary to create a load-image in raw-binary format i.e. for SAM-BA,
# ihex to create a load-image in Intel hex format
#LOADFORMAT = ihex
#LOADFORMAT = binary
LOADFORMAT = both
# Debugging format.
DEBUGF = dwarf-2
# Place project-specific -D (define) and/or
# -U options for C here.
CDEFS = -DSTM32F10X_$(MODEL)
CDEFS += -DUSE_STDPERIPH_DRIVER
CDEFS += -DUSE_$(BOARD)
CDEFS += -DIN_INS
ifeq ($(USE_BOOTLOADER), YES)
CDEFS += -DUSE_BOOTLOADER
endif
# Place project-specific -D and/or -U options for
# Assembler with preprocessor here.
#ADEFS = -DUSE_IRQ_ASM_WRAPPER
ADEFS = -D__ASSEMBLY__
# Compiler flag to set the C Standard level.
# c89 - "ANSI" C
# gnu89 - c89 plus GCC extensions
# c99 - ISO C99 standard (not yet fully implemented)
# gnu99 - c99 plus GCC extensions
CSTANDARD = -std=gnu99
#-----
# Compiler flags.
# -g*: generate debugging information
# -O*: optimization level
# -f...: tuning, see GCC manual and avr-libc documentation
# -Wall...: warning level
# -Wa,...: tell GCC to pass this to the assembler.
# -adhlns...: create assembler listing
#
# Flags for C and C++ (arm-elf-gcc/arm-elf-g++)
ifeq ($(DEBUG),YES)
CFLAGS += -g$(DEBUGF) #-DDEBUG
else
CFLAGS += -g$(DEBUGF)
endif
CFLAGS += -ffast-math
CFLAGS += -mcpu=$(MCU)
CFLAGS += $(CDEFS)
CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I.
CFLAGS += -mapcs-frame
CFLAGS += -fomit-frame-pointer
ifeq ($(CODE_SOURCERY), YES)
CFLAGS += -fpromote-loop-indices
endif
CFLAGS += -Wall
#CFLAGS += -Werror
CFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<))))
# Compiler flags to generate dependency files:
CFLAGS += -MD -MP -MF $(OUTDIR)/dep/$(@F).d
# flags only for C
#CONLYFLAGS += -Wnested-externs
CONLYFLAGS += $(CSTANDARD)
# Assembler flags.
# -Wa,...: tell GCC to pass this to the assembler.
# -ahlns: create listing
ASFLAGS = -mcpu=$(MCU) -I. -x assembler-with-cpp
ASFLAGS += $(ADEFS)
ASFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<))))
ASFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS))
MATH_LIB = -lm
# Linker flags.
# -Wl,...: tell GCC to pass this to linker.
# -Map: create map file
# --cref: add cross reference to map file
LDFLAGS = -nostartfiles -Wl,-Map=$(OUTDIR)/$(TARGET).map,--cref,--gc-sections
LDFLAGS += $(patsubst %,-L%,$(EXTRA_LIBDIRS))
LDFLAGS += -lc
LDFLAGS += $(patsubst %,-l%,$(EXTRA_LIBS))
LDFLAGS += $(MATH_LIB)
LDFLAGS += -lc -lgcc
# Set linker-script name depending on selected submodel name
LDFLAGS +=-T$(LINKERSCRIPTPATH)/link_$(BOARD)_$(BOOT_MODEL).ld
# ---------------------------------------------------------------------------
# Options for OpenOCD flash-programming
# see openocd.pdf/openocd.texi for further information
#
OOCD_LOADFILE+=$(OUTDIR)/$(TARGET).elf
# if OpenOCD is in the $PATH just set OPENOCDEXE=openocd
OOCD_EXE=openocd
# debug level
OOCD_CL=-d0
# interface and board/target settings (using the OOCD target-library here)
UNAME := $(shell uname)
ifeq ($(UNAME), Darwin)
OOCD_CL+=-f ../Project/OpenOCD/floss-jtag.openpilot.osx.cfg -f ../Project/OpenOCD/stm32.cfg
else
OOCD_CL+=-f ../Project/OpenOCD/floss-jtag.openpilot.cfg -f ../Project/OpenOCD/stm32.cfg
endif
# initialize
OOCD_CL+=-c init
# show the targets
OOCD_CL+=-c targets
# commands to prepare flash-write
OOCD_CL+= -c "reset halt"
# flash erase
OOCD_CL+=-c "stm32x mass_erase 0"
# flash-write
OOCD_CL+=-c "flash write_image $(OOCD_LOADFILE)"
# Verify
OOCD_CL+=-c "verify_image $(OOCD_LOADFILE)"
# reset target
OOCD_CL+=-c "reset run"
# terminate OOCD after programming
OOCD_CL+=-c shutdown
# ---------------------------------------------------------------------------
# Define programs and commands.
REMOVE = $(REMOVE_CMD) -f
###SHELL = sh
###COPY = cp
# List of all source files.
ALLSRC = $(ASRCARM) $(ASRC) $(SRCARM) $(SRC) $(CPPSRCARM) $(CPPSRC)
# List of all source files without directory and file-extension.
ALLSRCBASE = $(notdir $(basename $(ALLSRC)))
# Define all object files.
ALLOBJ = $(addprefix $(OUTDIR)/, $(addsuffix .o, $(ALLSRCBASE)))
# Define all listing files (used for make clean).
LSTFILES = $(addprefix $(OUTDIR)/, $(addsuffix .lst, $(ALLSRCBASE)))
# Define all depedency-files (used for make clean).
DEPFILES = $(addprefix $(OUTDIR)/dep/, $(addsuffix .o.d, $(ALLSRCBASE)))
# Default target.
all: gccversion build
ifeq ($(LOADFORMAT),ihex)
build: elf hex lss sym
else
ifeq ($(LOADFORMAT),binary)
build: elf bin lss sym
else
ifeq ($(LOADFORMAT),both)
build: elf hex bin lss sym
else
$(error "$(MSG_FORMATERROR) $(FORMAT)")
endif
endif
endif
# 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)
# Program the device with Dominic Rath's OPENOCD in "batch-mode", needs cfg and "reset-script".
program: $(OUTDIR)/$(TARGET).elf
@echo ${quote}Programming with OPENOCD${quote}
$(OOCD_EXE) $(OOCD_CL)
endif
endif
# Link: create ELF output file from object files.
$(eval $(call LINK_TEMPLATE, $(OUTDIR)/$(TARGET).elf, $(ALLOBJ)))
# Assemble: create object files from assembler source files.
$(foreach src, $(ASRC), $(eval $(call ASSEMBLE_TEMPLATE, $(src))))
# Assemble: create object files from assembler source files. ARM-only
$(foreach src, $(ASRCARM), $(eval $(call ASSEMBLE_ARM_TEMPLATE, $(src))))
# Compile: create object files from C source files.
$(foreach src, $(SRC), $(eval $(call COMPILE_C_TEMPLATE, $(src))))
# Compile: create object files from C source files. ARM-only
$(foreach src, $(SRCARM), $(eval $(call COMPILE_C_ARM_TEMPLATE, $(src))))
# Compile: create object files from C++ source files.
$(foreach src, $(CPPSRC), $(eval $(call COMPILE_CPP_TEMPLATE, $(src))))
# Compile: create object files from C++ source files. ARM-only
$(foreach src, $(CPPSRCARM), $(eval $(call COMPILE_CPP_ARM_TEMPLATE, $(src))))
# Compile: create assembler files from C source files. ARM/Thumb
$(eval $(call PARTIAL_COMPILE_TEMPLATE, SRC))
# Compile: create assembler files from C source files. ARM only
$(eval $(call PARTIAL_COMPILE_ARM_TEMPLATE, SRCARM))
.PHONY: elf lss sym hex bin
elf: $(OUTDIR)/$(TARGET).elf
lss: $(OUTDIR)/$(TARGET).lss
sym: $(OUTDIR)/$(TARGET).sym
hex: $(OUTDIR)/$(TARGET).hex
bin: $(OUTDIR)/$(TARGET).bin
# Display sizes of sections.
$(eval $(call SIZE_TEMPLATE, $(OUTDIR)/$(TARGET).elf))
.PHONY: size
size: $(OUTDIR)/$(TARGET).elf_size
# Generate Doxygen documents
docs:
doxygen $(DOXYGENDIR)/doxygen.cfg
# Target: clean project.
clean: clean_list
clean_list :
@echo $(MSG_CLEANING)
$(V1) $(REMOVE) $(OUTDIR)/$(TARGET).map
$(V1) $(REMOVE) $(OUTDIR)/$(TARGET).elf
$(V1) $(REMOVE) $(OUTDIR)/$(TARGET).hex
$(V1) $(REMOVE) $(OUTDIR)/$(TARGET).bin
$(V1) $(REMOVE) $(OUTDIR)/$(TARGET).sym
$(V1) $(REMOVE) $(OUTDIR)/$(TARGET).lss
$(V1) $(REMOVE) $(ALLOBJ)
$(V1) $(REMOVE) $(LSTFILES)
$(V1) $(REMOVE) $(DEPFILES)
$(V1) $(REMOVE) $(SRC:.c=.s)
$(V1) $(REMOVE) $(SRCARM:.c=.s)
$(V1) $(REMOVE) $(CPPSRC:.cpp=.s)
$(V1) $(REMOVE) $(CPPSRCARM:.cpp=.s)
# Create output files directory
# all known MS Windows OS define the ComSpec environment variable
ifdef ComSpec
$(shell md $(subst /,\\,$(OUTDIR)) 2>NUL)
else
$(shell mkdir -p $(OUTDIR) 2>/dev/null)
endif
# Include the dependency files.
ifdef ComSpec
-include $(shell md $(subst /,\\,$(OUTDIR))\dep 2>NUL) $(wildcard $(OUTDIR)/dep/*)
else
-include $(shell mkdir $(OUTDIR) 2>/dev/null) $(shell mkdir $(OUTDIR)/dep 2>/dev/null) $(wildcard $(OUTDIR)/dep/*)
endif
# Listing of phony targets.
.PHONY : all build clean clean_list program

129
flight/INS/inc/ins.h Normal file
View File

@ -0,0 +1,129 @@
/**
******************************************************************************
* @addtogroup INS INS
* @brief The main INS headers
*
* @{
* @addtogroup INS_Main
* @brief INS headers
* @{
*
* @file ins.h
* @author David "Buzz" Carlson (buzz@chebuzz.com)
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011.
* @brief INS Headers
* @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 INS_H
#define INS_H
/* PIOS Includes */
#include <pios.h>
struct mag_sensor {
uint8_t id[4];
uint8_t updated;
struct {
int16_t axis[3];
} raw;
struct {
float axis[3];
} scaled;
struct {
float bias[3];
float scale[3];
float variance[3];
} calibration;
};
//! Contains the data from the accelerometer
struct accel_sensor {
struct {
uint16_t x;
uint16_t y;
uint16_t z;
} raw;
struct {
float x;
float y;
float z;
} filtered;
struct {
float scale[3][4];
float variance[3];
} calibration;
};
//! Contains the data from the gyro
struct gyro_sensor {
struct {
uint16_t x;
uint16_t y;
uint16_t z;
} raw;
struct {
float x;
float y;
float z;
} filtered;
struct {
float bias[3];
float scale[3];
float variance[3];
float tempcompfactor[3];
} calibration;
struct {
uint16_t xy;
uint16_t z;
} temp;
};
//! Conains the current estimate of the attitude
struct attitude_solution {
struct {
float q1;
float q2;
float q3;
float q4;
} quaternion;
};
//! Contains data from the altitude sensor
struct altitude_sensor {
float altitude;
bool updated;
};
//! Contains data from the GPS (via the SPI link)
struct gps_sensor {
float NED[3];
float heading;
float groundspeed;
float quality;
bool updated;
};
#endif /* INS_H */
/**
* @}
* @}
*/

View File

@ -0,0 +1,67 @@
/**
******************************************************************************
* @addtogroup INS INS
* @brief The INS configuration
*
* @{
* @addtogroup INS_Main
* @brief INS configuration
* @{
*
* @file pios_config.h
* @author David "Buzz" Carlson (buzz@chebuzz.com)
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011.
* @brief PiOS configuration header.
* - Central compile time config for the project.
* @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 PIOS_CONFIG_H
#define PIOS_CONFIG_H
/* Enable/Disable PiOS Modules */
#define PIOS_INCLUDE_DELAY
#define PIOS_INCLUDE_I2C
#define PIOS_INCLUDE_IRQ
#define PIOS_INCLUDE_LED
#define PIOS_INCLUDE_SPI
#define PIOS_INCLUDE_SYS
#define PIOS_INCLUDE_USART
#define PIOS_INCLUDE_COM
#define PIOS_INCLUDE_GPS
#define PIOS_INCLUDE_HMC5883
#define PIOS_INCLUDE_BMP085
#define PIOS_INCLUDE_IMU3000
#define PIOS_INCLUDE_GPIO
#define PIOS_INCLUDE_EXTI
#define PIOS_INCLUDE_BMA180
/* COM Module */
#define GPS_BAUDRATE 19200
#define AUXUART_ENABLED 0
#define AUXUART_BAUDRATE 19200
#endif /* PIOS_CONFIG_H */
/**
* @}
* @}
*/

218
flight/INS/ins.c Normal file
View File

@ -0,0 +1,218 @@
/**
******************************************************************************
* @addtogroup INS INS
* @brief The INS Modules perform
*
* @{
* @addtogroup INS_Main
* @brief Main function which does the hardware dependent stuff
* @{
*
*
* @file ins.c
* @author David "Buzz" Carlson (buzz@chebuzz.com)
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011.
* @brief INSGPS Test Program
* @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
*/
/* OpenPilot Includes */
#include "ins.h"
#include "pios.h"
#include <stdbool.h>
#include "fifo_buffer.h"
void reset_values();
/**
* @addtogroup INS_Global_Data INS Global Data
* @{
* Public data. Used by both EKF and the sender
*/
//! Contains the data from the mag sensor chip
struct mag_sensor mag_data;
//! Contains the data from the accelerometer
struct accel_sensor accel_data;
//! Contains the data from the gyro
struct gyro_sensor gyro_data;
//! Conains the current estimate of the attitude
struct attitude_solution attitude_data;
//! Contains data from the altitude sensor
struct altitude_sensor altitude_data;
//! Contains data from the GPS (via the SPI link)
struct gps_sensor gps_data;
//! Offset correction of barometric alt, to match gps data
//static float baro_offset = 0;
//static float mag_len = 0;
typedef enum { INS_IDLE, INS_DATA_READY, INS_PROCESSING } states;
volatile int32_t ekf_too_slow;
volatile int32_t total_conversion_blocks;
/**
* @}
*/
/* INS functions */
void blink(int led, int times)
{
for(int i=0; i<times; i++)
{
PIOS_LED_Toggle(led);
PIOS_DELAY_WaitmS(250);
PIOS_LED_Toggle(led);
PIOS_DELAY_WaitmS(250);
}
}
void test_accel()
{
if(PIOS_BMA180_Test())
blink(LED1, 1);
else
blink(LED2, 1);
}
#if defined (PIOS_INCLUDE_HMC5883)
void test_mag()
{
if(PIOS_HMC5883_Test())
blink(LED1, 2);
else
blink(LED2, 2);
}
#endif
#if defined (PIOS_INCLUDE_BMP085)
void test_pressure()
{
if(PIOS_BMP085_Test())
blink(LED1, 3);
else
blink(LED2, 3);
}
#endif
#if defined (PIOS_INCLUDE_IMU3000)
void test_imu()
{
if(PIOS_IMU3000_Test())
blink(LED1, 4);
else
blink(LED2, 4);
}
#endif
extern void PIOS_Board_Init(void);
struct pios_bma180_data bma180_data;
/**
* @brief INS Main function
*/
int main()
{
reset_values();
PIOS_Board_Init();
while (1)
{
test_accel();
PIOS_DELAY_WaitmS(1000);
#if defined (PIOS_INCLUDE_HMC5883)
test_mag();
PIOS_DELAY_WaitmS(1000);
#endif
#if defined (PIOS_INCLUDE_BMP085)
test_pressure();
PIOS_DELAY_WaitmS(1000);
#endif
#if defined (PIOS_INCLUDE_IMU3000)
test_imu();
PIOS_DELAY_WaitmS(1000);
#endif
PIOS_DELAY_WaitmS(3000);
}
}
/**
* @brief Populate fields with initial values
*/
void reset_values()
{
accel_data.calibration.scale[0][1] = 0;
accel_data.calibration.scale[1][0] = 0;
accel_data.calibration.scale[0][2] = 0;
accel_data.calibration.scale[2][0] = 0;
accel_data.calibration.scale[1][2] = 0;
accel_data.calibration.scale[2][1] = 0;
accel_data.calibration.scale[0][0] = 0.0359;
accel_data.calibration.scale[1][1] = 0.0359;
accel_data.calibration.scale[2][2] = 0.0359;
accel_data.calibration.scale[0][3] = -73.5;
accel_data.calibration.scale[1][3] = -73.5;
accel_data.calibration.scale[2][3] = -73.5;
accel_data.calibration.variance[0] = 1e-4;
accel_data.calibration.variance[1] = 1e-4;
accel_data.calibration.variance[2] = 1e-4;
gyro_data.calibration.scale[0] = -0.014;
gyro_data.calibration.scale[1] = 0.014;
gyro_data.calibration.scale[2] = -0.014;
gyro_data.calibration.bias[0] = -24;
gyro_data.calibration.bias[1] = -24;
gyro_data.calibration.bias[2] = -24;
gyro_data.calibration.variance[0] = 1;
gyro_data.calibration.variance[1] = 1;
gyro_data.calibration.variance[2] = 1;
mag_data.calibration.scale[0] = 1;
mag_data.calibration.scale[1] = 1;
mag_data.calibration.scale[2] = 1;
mag_data.calibration.bias[0] = 0;
mag_data.calibration.bias[1] = 0;
mag_data.calibration.bias[2] = 0;
mag_data.calibration.variance[0] = 50;
mag_data.calibration.variance[1] = 50;
mag_data.calibration.variance[2] = 50;
}
/**
* @}
*/

602
flight/INS/pios_board.c Normal file
View File

@ -0,0 +1,602 @@
/**
******************************************************************************
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_HMC5883 HMC5883 Functions
* @brief Deals with the hardware interface to the magnetometers
* @{
*
* @file pios_board.c
* @author David "Buzz" Carlson (buzz@chebuzz.com)
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011.
* @brief Defines board specific static initializers for hardware for the INS board.
* @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 <pios.h>
#if defined(PIOS_INCLUDE_SPI)
#include <pios_spi_priv.h>
/* SPI2 Interface
* - Used for mainboard communications and magnetometer
*
* 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).
*/
void PIOS_SPI_op_mag_irq_handler(void);
void DMA1_Channel5_IRQHandler() __attribute__ ((alias("PIOS_SPI_op_mag_irq_handler")));
void DMA1_Channel4_IRQHandler() __attribute__ ((alias("PIOS_SPI_op_mag_irq_handler")));
static const struct pios_spi_cfg pios_spi_op_mag_cfg = {
.regs = SPI2,
.init = {
.SPI_Mode = SPI_Mode_Slave,
.SPI_Direction = SPI_Direction_2Lines_FullDuplex,
.SPI_DataSize = SPI_DataSize_8b,
.SPI_NSS = SPI_NSS_Hard,
.SPI_FirstBit = SPI_FirstBit_MSB,
.SPI_CRCPolynomial = 7,
.SPI_CPOL = SPI_CPOL_High,
.SPI_CPHA = SPI_CPHA_2Edge,
},
.use_crc = TRUE,
.dma = {
.ahb_clk = RCC_AHBPeriph_DMA1,
.irq = {
.handler = PIOS_SPI_op_mag_irq_handler,
.flags =
(DMA1_FLAG_TC4 | DMA1_FLAG_TE4 | DMA1_FLAG_HT4 |
DMA1_FLAG_GL4),
.init = {
.NVIC_IRQChannel = DMA1_Channel4_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.channel = DMA1_Channel4,
.init = {
.DMA_PeripheralBaseAddr =
(uint32_t) & (SPI2->DR),
.DMA_DIR = DMA_DIR_PeripheralSRC,
.DMA_PeripheralInc =
DMA_PeripheralInc_Disable,
.DMA_MemoryInc = DMA_MemoryInc_Enable,
.DMA_PeripheralDataSize =
DMA_PeripheralDataSize_Byte,
.DMA_MemoryDataSize =
DMA_MemoryDataSize_Byte,
.DMA_Mode = DMA_Mode_Normal,
.DMA_Priority = DMA_Priority_Medium,
.DMA_M2M = DMA_M2M_Disable,
},
},
.tx = {
.channel = DMA1_Channel5,
.init = {
.DMA_PeripheralBaseAddr =
(uint32_t) & (SPI2->DR),
.DMA_DIR = DMA_DIR_PeripheralDST,
.DMA_PeripheralInc =
DMA_PeripheralInc_Disable,
.DMA_MemoryInc = DMA_MemoryInc_Enable,
.DMA_PeripheralDataSize =
DMA_PeripheralDataSize_Byte,
.DMA_MemoryDataSize =
DMA_MemoryDataSize_Byte,
.DMA_Mode = DMA_Mode_Normal,
.DMA_Priority = DMA_Priority_Medium,
.DMA_M2M = DMA_M2M_Disable,
},
},
},
.ssel = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_12,
.GPIO_Speed = GPIO_Speed_10MHz,
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
},
},
.sclk = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_13,
.GPIO_Speed = GPIO_Speed_10MHz,
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
},
},
.miso = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_14,
.GPIO_Speed = GPIO_Speed_10MHz,
.GPIO_Mode = GPIO_Mode_AF_PP,
},
},
.mosi = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_15,
.GPIO_Speed = GPIO_Speed_10MHz,
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
},
},
};
uint32_t pios_spi_op_mag_id;
void PIOS_SPI_op_mag_irq_handler(void)
{
/* Call into the generic code to handle the IRQ for this specific device */
PIOS_SPI_IRQ_Handler(pios_spi_op_mag_id);
}
/* SPI1 Interface
* - Used for BMA180 accelerometer
*/
void PIOS_SPI_accel_irq_handler(void);
void DMA1_Channel2_IRQHandler() __attribute__ ((alias("PIOS_SPI_accel_irq_handler")));
void DMA1_Channel3_IRQHandler() __attribute__ ((alias("PIOS_SPI_accel_irq_handler")));
static const struct pios_spi_cfg pios_spi_accel_cfg = {
.regs = SPI1,
.init = {
.SPI_Mode = SPI_Mode_Master,
.SPI_Direction = SPI_Direction_2Lines_FullDuplex,
.SPI_DataSize = SPI_DataSize_8b,
.SPI_NSS = SPI_NSS_Soft,
.SPI_FirstBit = SPI_FirstBit_MSB,
.SPI_CRCPolynomial = 7,
.SPI_CPOL = SPI_CPOL_High,
.SPI_CPHA = SPI_CPHA_1Edge,
.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_2,
},
.use_crc = FALSE,
.dma = {
.ahb_clk = RCC_AHBPeriph_DMA1,
.irq = {
.handler = PIOS_SPI_accel_irq_handler,
.flags = (DMA1_FLAG_TC2 | DMA1_FLAG_TE2 | DMA1_FLAG_HT2 | DMA1_FLAG_GL2),
.init = {
.NVIC_IRQChannel = DMA1_Channel2_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.channel = DMA1_Channel2,
.init = {
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI1->DR),
.DMA_DIR = DMA_DIR_PeripheralSRC,
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
.DMA_MemoryInc = DMA_MemoryInc_Enable,
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
.DMA_Mode = DMA_Mode_Normal,
.DMA_Priority = DMA_Priority_Medium,
.DMA_M2M = DMA_M2M_Disable,
},
},
.tx = {
.channel = DMA1_Channel3,
.init = {
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI1->DR),
.DMA_DIR = DMA_DIR_PeripheralDST,
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
.DMA_MemoryInc = DMA_MemoryInc_Enable,
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
.DMA_Mode = DMA_Mode_Normal,
.DMA_Priority = DMA_Priority_High,
.DMA_M2M = DMA_M2M_Disable,
},
},
},
.ssel = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_4,
.GPIO_Speed = GPIO_Speed_10MHz,
.GPIO_Mode = GPIO_Mode_Out_PP,
},
},
.sclk = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_5,
.GPIO_Speed = GPIO_Speed_10MHz,
.GPIO_Mode = GPIO_Mode_AF_PP,
},
},
.miso = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_6,
.GPIO_Speed = GPIO_Speed_10MHz,
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
},
},
.mosi = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_7,
.GPIO_Speed = GPIO_Speed_10MHz,
.GPIO_Mode = GPIO_Mode_AF_PP,
},
},
};
static uint32_t pios_spi_accel_id;
void PIOS_SPI_accel_irq_handler(void)
{
/* Call into the generic code to handle the IRQ for this specific device */
PIOS_SPI_IRQ_Handler(pios_spi_accel_id);
}
#endif /* PIOS_INCLUDE_SPI */
#if defined(PIOS_INCLUDE_GPS)
#include <pios_usart_priv.h>
/*
* GPS USART
*/
void PIOS_USART_gps_irq_handler(void);
void USART1_IRQHandler()
__attribute__ ((alias("PIOS_USART_gps_irq_handler")));
const struct pios_usart_cfg pios_usart_gps_cfg = {
.regs = USART1,
.init = {
#if defined (PIOS_USART_BAUDRATE)
.USART_BaudRate = PIOS_USART_BAUDRATE,
#else
.USART_BaudRate = 57600,
#endif
.USART_WordLength = USART_WordLength_8b,
.USART_Parity = USART_Parity_No,
.USART_StopBits = USART_StopBits_1,
.USART_HardwareFlowControl =
USART_HardwareFlowControl_None,
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
},
.irq = {
.handler = PIOS_USART_gps_irq_handler,
.init = {
.NVIC_IRQChannel = USART1_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_10,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_IPU,
},
},
.tx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_9,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF_PP,
},
},
};
static uint32_t pios_usart_gps_id;
void PIOS_USART_gps_irq_handler(void)
{
PIOS_USART_IRQ_Handler(pios_usart_gps_id);
}
#endif /* PIOS_INCLUDE_GPS */
#ifdef PIOS_COM_AUX
/*
* AUX USART
*/
void PIOS_USART_aux_irq_handler(void);
void USART4_IRQHandler()
__attribute__ ((alias("PIOS_USART_aux_irq_handler")));
const struct pios_usart_cfg pios_usart_aux_cfg = {
.regs = USART4,
.init = {
#if defined (PIOS_USART_BAUDRATE)
.USART_BaudRate = PIOS_USART_BAUDRATE,
#else
.USART_BaudRate = 57600,
#endif
.USART_WordLength = USART_WordLength_8b,
.USART_Parity = USART_Parity_No,
.USART_StopBits = USART_StopBits_1,
.USART_HardwareFlowControl =
USART_HardwareFlowControl_None,
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
},
.irq = {
.handler = PIOS_USART_aux_irq_handler,
.init = {
.NVIC_IRQChannel = USART4_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_11,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_IPU,
},
},
.tx = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_10,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF_PP,
},
},
};
static uint32_t pios_usart_aux_id;
void PIOS_USART_aux_irq_handler(void)
{
PIOS_USART_IRQ_Handler(pios_usart_aux_id);
}
#endif /* PIOS_COM_AUX */
#if defined(PIOS_INCLUDE_I2C)
#include <pios_i2c_priv.h>
/*
* I2C Adapters
*/
void PIOS_I2C_pres_mag_adapter_ev_irq_handler(void);
void PIOS_I2C_pres_mag_adapter_er_irq_handler(void);
void I2C1_EV_IRQHandler()
__attribute__ ((alias("PIOS_I2C_pres_mag_adapter_ev_irq_handler")));
void I2C1_ER_IRQHandler()
__attribute__ ((alias("PIOS_I2C_pres_mag_adapter_er_irq_handler")));
const struct pios_i2c_adapter_cfg pios_i2c_pres_mag_adapter_cfg = {
.regs = I2C1,
.init = {
.I2C_Mode = I2C_Mode_I2C,
.I2C_OwnAddress1 = 0,
.I2C_Ack = I2C_Ack_Enable,
.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit,
.I2C_DutyCycle = I2C_DutyCycle_2,
.I2C_ClockSpeed = 200000, /* bits/s */
},
.transfer_timeout_ms = 50,
.scl = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_6,
.GPIO_Speed = GPIO_Speed_10MHz,
.GPIO_Mode = GPIO_Mode_AF_OD,
},
},
.sda = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_7,
.GPIO_Speed = GPIO_Speed_10MHz,
.GPIO_Mode = GPIO_Mode_AF_OD,
},
},
.event = {
.handler = PIOS_I2C_pres_mag_adapter_ev_irq_handler,
.flags = 0, /* FIXME: check this */
.init = {
.NVIC_IRQChannel = I2C1_EV_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.error = {
.handler = PIOS_I2C_pres_mag_adapter_er_irq_handler,
.flags = 0, /* FIXME: check this */
.init = {
.NVIC_IRQChannel = I2C1_ER_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
};
uint32_t pios_i2c_pres_mag_adapter_id;
void PIOS_I2C_pres_mag_adapter_ev_irq_handler(void)
{
/* Call into the generic code to handle the IRQ for this specific device */
PIOS_I2C_EV_IRQ_Handler(pios_i2c_pres_mag_adapter_id);
}
void PIOS_I2C_pres_mag_adapter_er_irq_handler(void)
{
/* Call into the generic code to handle the IRQ for this specific device */
PIOS_I2C_ER_IRQ_Handler(pios_i2c_pres_mag_adapter_id);
}
void PIOS_I2C_gyro_adapter_ev_irq_handler(void);
void PIOS_I2C_gyro_adapter_er_irq_handler(void);
void I2C2_EV_IRQHandler() __attribute__ ((alias ("PIOS_I2C_gyro_adapter_ev_irq_handler")));
void I2C2_ER_IRQHandler() __attribute__ ((alias ("PIOS_I2C_gyro_adapter_er_irq_handler")));
const struct pios_i2c_adapter_cfg pios_i2c_gyro_adapter_cfg = {
.regs = I2C2,
.init = {
.I2C_Mode = I2C_Mode_I2C,
.I2C_OwnAddress1 = 0,
.I2C_Ack = I2C_Ack_Enable,
.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit,
.I2C_DutyCycle = I2C_DutyCycle_2,
.I2C_ClockSpeed = 400000, /* bits/s */
},
.transfer_timeout_ms = 50,
.scl = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_10,
.GPIO_Speed = GPIO_Speed_10MHz,
.GPIO_Mode = GPIO_Mode_AF_OD,
},
},
.sda = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_11,
.GPIO_Speed = GPIO_Speed_10MHz,
.GPIO_Mode = GPIO_Mode_AF_OD,
},
},
.event = {
.handler = PIOS_I2C_gyro_adapter_ev_irq_handler,
.flags = 0, /* FIXME: check this */
.init = {
.NVIC_IRQChannel = I2C2_EV_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.error = {
.handler = PIOS_I2C_gyro_adapter_er_irq_handler,
.flags = 0, /* FIXME: check this */
.init = {
.NVIC_IRQChannel = I2C2_ER_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
};
uint32_t pios_i2c_gyro_adapter_id;
void PIOS_I2C_gyro_adapter_ev_irq_handler(void)
{
/* Call into the generic code to handle the IRQ for this specific device */
PIOS_I2C_EV_IRQ_Handler(pios_i2c_gyro_adapter_id);
}
void PIOS_I2C_gyro_adapter_er_irq_handler(void)
{
/* Call into the generic code to handle the IRQ for this specific device */
PIOS_I2C_ER_IRQ_Handler(pios_i2c_gyro_adapter_id);
}
#endif /* PIOS_INCLUDE_I2C */
extern const struct pios_com_driver pios_usart_com_driver;
uint32_t pios_com_aux_id;
uint32_t pios_com_gps_id;
/**
* PIOS_Board_Init()
* initializes all the core subsystems on this specific hardware
* called from System/openpilot.c
*/
void PIOS_Board_Init(void) {
/* Brings up System using CMSIS functions, enables the LEDs. */
PIOS_SYS_Init();
/* Delay system */
PIOS_DELAY_Init();
/* IAP System Setup */
PIOS_IAP_Init();
#if defined(PIOS_INCLUDE_COM)
#if defined(PIOS_INCLUDE_GPS)
if (PIOS_USART_Init(&pios_usart_gps_id, &pios_usart_gps_cfg)) {
PIOS_DEBUG_Assert(0);
}
if (PIOS_COM_Init(&pios_com_gps_id, &pios_usart_com_driver, pios_usart_gps_id)) {
PIOS_DEBUG_Assert(0);
}
#endif /* PIOS_INCLUDE_GPS */
#endif /* PIOS_INCLUDE_COM */
#if defined (PIOS_INCLUDE_I2C)
if (PIOS_I2C_Init(&pios_i2c_pres_mag_adapter_id, &pios_i2c_pres_mag_adapter_cfg)) {
PIOS_DEBUG_Assert(0);
}
#if defined (PIOS_INCLUDE_BMP085)
PIOS_BMP085_Init();
#endif /* PIOS_INCLUDE_BMP085 */
#if defined (PIOS_INCLUDE_HMC5883)
PIOS_HMC5883_Init();
#endif /* PIOS_INCLUDE_HMC5883 */
#if defined(PIOS_INCLUDE_IMU3000)
if (PIOS_I2C_Init(&pios_i2c_gyro_adapter_id, &pios_i2c_gyro_adapter_cfg)) {
PIOS_DEBUG_Assert(0);
}
PIOS_IMU3000_Init();
#endif /* PIOS_INCLUDE_IMU3000 */
#endif /* PIOS_INCLUDE_I2C */
#if defined(PIOS_INCLUDE_SPI)
/* Set up the SPI interface to the accelerometer*/
if (PIOS_SPI_Init(&pios_spi_accel_id, &pios_spi_accel_cfg)) {
PIOS_DEBUG_Assert(0);
}
PIOS_BMA180_Attach(pios_spi_accel_id);
// #include "ahrs_spi_comm.h"
// InsInitComms();
//
// /* Set up the SPI interface to the OP board */
// if (PIOS_SPI_Init(&pios_spi_op_id, &pios_spi_op_cfg)) {
// PIOS_DEBUG_Assert(0);
// }
//
// InsConnect(pios_spi_op_id);
#endif /* PIOS_INCLUDE_SPI */
}
/**
* @}
* @}
*/

View File

@ -0,0 +1,246 @@
/**
******************************************************************************
* @addtogroup OpenPilotSystem OpenPilot System
* @{
* @addtogroup OpenPilotCore OpenPilot Core
* @{
* @file pios_board.h
* @author David "Buzz" Carlson (buzz@chebuzz.com)
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011.
* @brief Defines board hardware for the OpenPilot Version 1.1 hardware.
* @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 STM3210E_INS_H_
#define STM3210E_INS_H_
//------------------------
// Timers and Channels Used
//------------------------
/*
Timer | Channel 1 | Channel 2 | Channel 3 | Channel 4
------+-----------+-----------+-----------+----------
TIM1 | | | |
TIM2 | --------------- PIOS_DELAY -----------------
TIM3 | | | |
TIM4 | | | |
TIM5 | | | |
TIM6 | | | |
TIM7 | | | |
TIM8 | | | |
------+-----------+-----------+-----------+----------
*/
//------------------------
// DMA Channels Used
//------------------------
/* Channel 1 - */
/* Channel 2 - SPI1 RX */
/* Channel 3 - SPI1 TX */
/* Channel 4 - SPI2 RX */
/* Channel 5 - SPI2 TX */
/* Channel 6 - */
/* Channel 7 - */
/* Channel 8 - */
/* Channel 9 - */
/* Channel 10 - */
/* Channel 11 - */
/* Channel 12 - */
//------------------------
// BOOTLOADER_SETTINGS
//------------------------
//#define FUNC_ID 1
//#define HW_VERSION 01
#define BOOTLOADER_VERSION 0
#define BOARD_TYPE 0x05 // INS board
#define BOARD_REVISION 0x01 // Beta version
//#define HW_VERSION (BOARD_TYPE << 8) | BOARD_REVISION
#define MEM_SIZE 524288 //512K
#define SIZE_OF_DESCRIPTION (uint8_t) 100
#define START_OF_USER_CODE (uint32_t)0x08005000//REMEMBER SET ALSO IN link_stm32f10x_HD_BL.ld
#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
//------------------------
// PIOS_LED
//------------------------
#define PIOS_LED_LED1_GPIO_PORT GPIOA
#define PIOS_LED_LED1_GPIO_PIN GPIO_Pin_3
#define PIOS_LED_LED1_GPIO_CLK RCC_APB2Periph_GPIOA
#define PIOS_LED_LED2_GPIO_PORT GPIOA
#define PIOS_LED_LED2_GPIO_PIN GPIO_Pin_2
#define PIOS_LED_LED2_GPIO_CLK RCC_APB2Periph_GPIOA
#define PIOS_LED_NUM 2
#define PIOS_LED_PORTS { PIOS_LED_LED1_GPIO_PORT, PIOS_LED_LED2_GPIO_PORT }
#define PIOS_LED_PINS { PIOS_LED_LED1_GPIO_PIN, PIOS_LED_LED2_GPIO_PIN }
#define PIOS_LED_CLKS { PIOS_LED_LED1_GPIO_CLK, PIOS_LED_LED2_GPIO_CLK }
//------------------------
// PIOS_SPI
// See also pios_board.c
//------------------------
#define PIOS_SPI_MAX_DEVS 2
//------------------------
// PIOS_I2C
// See also pios_board.c
//------------------------
#define PIOS_I2C_MAX_DEVS 3
extern uint32_t pios_i2c_pres_mag_adapter_id;
#define PIOS_I2C_MAIN_ADAPTER (pios_i2c_pres_mag_adapter_id)
extern uint32_t pios_i2c_gyro_adapter_id;
#define PIOS_I2C_GYRO_ADAPTER (pios_i2c_gyro_adapter_id)
//------------------------
// PIOS_BMP085
//------------------------
#define PIOS_BMP085_EOC_GPIO_PORT GPIOC
#define PIOS_BMP085_EOC_GPIO_PIN GPIO_Pin_2
#define PIOS_BMP085_EOC_PORT_SOURCE GPIO_PortSourceGPIOC
#define PIOS_BMP085_EOC_PIN_SOURCE GPIO_PinSource2
#define PIOS_BMP085_EOC_CLK RCC_APB2Periph_GPIOC
#define PIOS_BMP085_EOC_EXTI_LINE EXTI_Line2
#define PIOS_BMP085_EOC_IRQn EXTI15_10_IRQn
#define PIOS_BMP085_EOC_PRIO PIOS_IRQ_PRIO_LOW
#define PIOS_BMP085_XCLR_GPIO_PORT GPIOC
#define PIOS_BMP085_XCLR_GPIO_PIN GPIO_Pin_1
#define PIOS_BMP085_OVERSAMPLING 3
//-------------------------
// PIOS_USART
//
// See also pios_board.c
//-------------------------
#define PIOS_USART_MAX_DEVS 2
#define PIOS_USART_RX_BUFFER_SIZE 256
#define PIOS_USART_TX_BUFFER_SIZE 256
//-------------------------
// PIOS_COM
//
// See also pios_board.c
//-------------------------
#define PIOS_COM_MAX_DEVS 2
#define PIOS_COM_GPS_BAUDRATE 57600
extern uint32_t pios_com_gps_id;
#define PIOS_COM_GPS (pios_com_gps_id)
#ifdef PIOS_ENABLE_AUX_UART
#define PIOS_COM_AUX_BAUDRATE 57600
extern uint32_t pios_com_aux_id;
#define PIOS_COM_AUX (pios_com_aux_id)
#define PIOS_COM_DEBUG PIOS_COM_AUX
#endif
//-------------------------
// Delay Timer
//-------------------------
#define PIOS_DELAY_TIMER TIM2
#define PIOS_DELAY_TIMER_RCC_FUNC RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE)
//-------------------------
// System Settings
//-------------------------
#define PIOS_MASTER_CLOCK 72000000
#define PIOS_PERIPHERAL_CLOCK (PIOS_MASTER_CLOCK / 2)
#if defined(USE_BOOTLOADER)
#define PIOS_NVIC_VECTTAB_FLASH (START_OF_USER_CODE)
#else
#define PIOS_NVIC_VECTTAB_FLASH ((uint32_t)0x08000000)
#endif
//-------------------------
// Interrupt Priorities
//-------------------------
#define PIOS_IRQ_PRIO_LOW 12 // lower than RTOS
#define PIOS_IRQ_PRIO_MID 8 // higher than RTOS
#define PIOS_IRQ_PRIO_HIGH 5 // for SPI, ADC, I2C etc...
#define PIOS_IRQ_PRIO_HIGHEST 4 // for USART etc...
//-------------------------
// ADC
// None.
//-------------------------
//-------------------------
// GPIO
// Not used, but pios_gpio.c expects something
//-------------------------
#define PIOS_GPIO_1_PORT GPIOA
#define PIOS_GPIO_1_PIN GPIO_Pin_1
#define PIOS_GPIO_1_GPIO_CLK RCC_APB2Periph_GPIOA
#define PIOS_GPIO_PORTS { PIOS_GPIO_1_PORT }
#define PIOS_GPIO_PINS { PIOS_GPIO_1_PIN }
#define PIOS_GPIO_CLKS { PIOS_GPIO_1_GPIO_CLK }
#define PIOS_GPIO_NUM 1
#define PIOS_BMA_ENABLE PIOS_SPI_RC_PinSet(PIOS_SPI_ACCEL,0)
#define PIOS_BMA_DISABLE PIOS_SPI_RC_PinSet(PIOS_SPI_ACCEL,1)
//------------------------
// PIOS_HMC5883
//------------------------
#define PIOS_HMC5883_DRDY_GPIO_PORT GPIOB
#define PIOS_HMC5883_DRDY_GPIO_PIN GPIO_Pin_8
#define PIOS_HMC5883_DRDY_PORT_SOURCE GPIO_PortSourceGPIOB
#define PIOS_HMC5883_DRDY_PIN_SOURCE GPIO_PinSource8
#define PIOS_HMC5883_DRDY_CLK RCC_APB2Periph_GPIOB
#define PIOS_HMC5883_DRDY_EXTI_LINE EXTI_Line8
#define PIOS_HMC5883_DRDY_IRQn EXTI9_5_IRQn
#define PIOS_HMC5883_DRDY_PRIO PIOS_IRQ_PRIO_LOW
//------------------------
// PIOS_IMU3000
//------------------------
#define PIOS_IMU3000_INT_GPIO_PORT GPIOB
#define PIOS_IMU3000_INT_GPIO_PIN GPIO_Pin_1
#define PIOS_IMU3000_INT_PORT_SOURCE GPIO_PortSourceGPIOB
#define PIOS_IMU3000_INT_PIN_SOURCE GPIO_PinSource1
#define PIOS_IMU3000_INT_CLK RCC_APB2Periph_GPIOB
#define PIOS_IMU3000_INT_EXTI_LINE EXTI_Line1
#define PIOS_IMU3000_INT_IRQn EXTI1_IRQn
#define PIOS_IMU3000_INT_PRIO PIOS_IRQ_PRIO_HIGH
#endif /* STM3210E_INS_H_ */
/**
* @}
* @}
*/

View File

@ -9,6 +9,8 @@
#include "STM32103CB_PIPXTREME_Rev1.h"
#elif USE_STM32103CB_CC_Rev1
#include "STM32103CB_CC_Rev1.h"
#elif USE_STM3210E_INS
#include "STM3210E_INS.h"
#endif
#endif /* PIOS_BOARD_H_ */

View File

@ -0,0 +1,212 @@
/**
******************************************************************************
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_BMA180 BMA180 Functions
* @brief Deals with the hardware interface to the BMA180 3-axis accelerometer
* @{
*
* @file pios_bma180.h
* @author David "Buzz" Carlson (buzz@chebuzz.com)
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011.
* @brief PiOS BMA180 digital accelerometer driver.
* - Driver for the BMA180 digital accelerometer on the SPI bus.
* @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 "pios.h"
static uint32_t PIOS_SPI_ACCEL;
static uint8_t EEPROM_WRITEABLE=0;
/**
* @brief Claim the SPI bus for the accel communications and select this chip
*/
void PIOS_BMA180_ClaimBus()
{
PIOS_SPI_ClaimBus(PIOS_SPI_ACCEL);
PIOS_BMA_ENABLE;
}
/**
* @brief Release the SPI bus for the accel communications and end the transaction
*/
void PIOS_BMA180_ReleaseBus()
{
PIOS_BMA_DISABLE;
PIOS_SPI_ReleaseBus(PIOS_SPI_ACCEL);
}
/**
* @brief Set the EEPROM write-enable bit. Must be set to 1 (unlocked) before writing control registers.
* @return none
* @param _we[in] bit to set, 1 to enable writes or 0 to disable writes
*/
void PIOS_BMA180_WriteEnable(uint8_t _we)
{
uint8_t addr_reg[2] = {BMA_WE_ADDR,0};
PIOS_BMA180_ClaimBus();
addr_reg[1] = PIOS_SPI_TransferByte(PIOS_SPI_ACCEL,(0x80 | BMA_WE_ADDR) );
addr_reg[1] &= 0xEF;
addr_reg[1] |= ( (0x01 & _we) << 4);
PIOS_SPI_TransferBlock(PIOS_SPI_ACCEL,addr_reg,NULL,sizeof(addr_reg),NULL);
PIOS_BMA180_ReleaseBus();
EEPROM_WRITEABLE=_we;
}
/**
* @brief Read a register from BMA180
* @returns The register value
* @param reg[in] Register address to be read
*/
uint8_t PIOS_BMA180_GetReg(uint8_t reg)
{
uint8_t data;
PIOS_BMA180_ClaimBus();
data = PIOS_SPI_TransferByte(PIOS_SPI_ACCEL,(0x80 | reg) );
PIOS_BMA180_ReleaseBus();
return(data);
}
/**
* @brief Write a BMA180 register. EEPROM must be unlocked before calling this function.
* @return none
* @param reg[in] address of register to be written
* @param data[in] data that is to be written to register
*/
void PIOS_BMA180_SetReg(uint8_t reg, uint8_t data)
{
uint8_t reg_data[2] = { (0x7F & reg), data};
PIOS_BMA180_ClaimBus();
PIOS_SPI_TransferBlock(PIOS_SPI_ACCEL,reg_data,NULL,2,NULL);
PIOS_BMA180_ReleaseBus();
}
/**
* @brief Select the bandwidth the digital filter pass allows.
* @return none
* @param rate[in] Bandwidth setting to be used
*
* EEPROM must be write-enabled before calling this function.
*/
void PIOS_BMA180_SelectBW(uint8_t bw)
{
uint8_t addr_reg[2] = { BMA_BW_ADDR, 0};
PIOS_BMA180_ClaimBus();
addr_reg[1] = PIOS_SPI_TransferByte(PIOS_SPI_ACCEL,(0x80|BMA_BW_ADDR));
addr_reg[1] &= 0x0F;
addr_reg[1] |= (bw << 4);
PIOS_SPI_TransferBlock(PIOS_SPI_ACCEL,addr_reg,NULL,sizeof(addr_reg),NULL);
PIOS_BMA180_ReleaseBus();
}
/**
* @brief Select the full scale acceleration range.
* @return none
* @param rate[in] Range setting to be used
*
*/
void PIOS_BMA180_SetRange(uint8_t range)
{
uint8_t addr_reg[2] = { BMA_RANGE_ADDR, 0};
PIOS_BMA180_ClaimBus();
addr_reg[1] = PIOS_SPI_TransferByte(PIOS_SPI_ACCEL,(0x80|BMA_RANGE_ADDR));
addr_reg[1] &= 0x0F;
addr_reg[1] |= (range << 4);
PIOS_SPI_TransferBlock(PIOS_SPI_ACCEL,addr_reg,NULL,sizeof(addr_reg),NULL);
PIOS_BMA180_ReleaseBus();
}
/**
* @brief Connect to the correct SPI bus
*/
void PIOS_BMA180_Attach(uint32_t spi_id)
{
PIOS_SPI_ACCEL = spi_id;
}
/**
* @brief Initialize with good default settings
*/
void PIOS_BMA180_Init()
{
/*
PIOS_BMA180_ReleaseBus();
PIOS_BMA180_WriteEnable(1);
PIOS_BMA180_SelectRate(BMA_RATE_3200);
PIOS_BMA180_SetRange(BMA_RANGE_8G);
PIOS_BMA180_FifoDepth(16);
PIOS_BMA180_SetMeasure(1);
PIOS_BMA180_WriteEnable(0);
*/
}
/**
* @brief Read a single set of values from the x y z channels
* @returns The number of samples remaining in the fifo
*/
uint8_t PIOS_BMA180_Read(struct pios_bma180_data * data)
{
// To save memory use same buffer for in and out but offset by
// a byte
uint8_t buf[7] = {0,0,0,0,0,0};
uint8_t rec[7] = {0,0,0,0,0,0};
buf[0] = BMA_X_LSB_ADDR | 0x80 ; // Multibyte read starting at X LSB
PIOS_BMA180_ClaimBus();
PIOS_SPI_TransferBlock(PIOS_SPI_ACCEL,&buf[0],&rec[0],7,NULL);
PIOS_BMA180_ReleaseBus();
// | MSB | LSB | 0 | new_data |
data->x = ( (rec[2] << 8) | rec[1] ) >> 2;
data->y = ( (rec[4] << 8) | rec[3] ) >> 2;
data->z = ( (rec[6] << 8) | rec[5] ) >> 2;
return 0; // return number of remaining entries
}
/**
* @brief Test SPI and chip functionality by reading chip ID register
* @return 0 if test failed, any other value signals test succeeded.
*
*/
uint8_t PIOS_BMA180_Test()
{
uint8_t data = 0;
uint8_t pass = 0;
PIOS_BMA180_ClaimBus();
data = PIOS_SPI_TransferByte(PIOS_SPI_ACCEL,(0x80 | BMA_CHIPID_ADDR) );
data &= 0x07;
if(0x03 == data)
pass = 1;
data = PIOS_SPI_TransferByte(PIOS_SPI_ACCEL,(0x80 | BMA_VERSION_ADDR) );
if(0x12 == data)
pass = 1 && pass; // Only passes if first and second test passS
PIOS_BMA180_ReleaseBus();
return pass;
}
/**
* @}
* @}
*/

View File

@ -0,0 +1,393 @@
/**
******************************************************************************
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_HMC5883 HMC5883 Functions
* @brief Deals with the hardware interface to the magnetometers
* @{
*
* @file pios_hmc5883.c
* @author David "Buzz" Carlson (buzz@chebuzz.com)
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011.
* @brief HMC5883 Magnetic Sensor Functions from AHRS
* @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
*/
/* Project Includes */
#include "pios.h"
#if defined(PIOS_INCLUDE_HMC5883)
/* Global Variables */
/* Local Types */
typedef struct {
uint8_t M_ODR; /* OUTPUT DATA RATE --> here below the relative define (See datasheet page 11 for more details) */
uint8_t Meas_Conf; /* Measurement Configuration,: Normal, positive bias, or negative bias --> here below the relative define */
uint8_t Gain; /* Gain Configuration, select the full scale --> here below the relative define (See datasheet page 11 for more details) */
uint8_t Mode;
} PIOS_HMC5883_ConfigTypeDef;
/* Local Variables */
volatile bool pios_hmc5883_data_ready;
static void PIOS_HMC5883_Config(PIOS_HMC5883_ConfigTypeDef * HMC5883_Config_Struct);
static bool PIOS_HMC5883_Read(uint8_t address, uint8_t * buffer, uint8_t len);
static bool PIOS_HMC5883_Write(uint8_t address, uint8_t buffer);
/**
* @brief Initialize the HMC5883 magnetometer sensor.
* @return none
*/
void PIOS_HMC5883_Init(void)
{
GPIO_InitTypeDef GPIO_InitStructure;
EXTI_InitTypeDef EXTI_InitStructure;
NVIC_InitTypeDef NVIC_InitStructure;
/* Enable DRDY GPIO clock */
RCC_APB2PeriphClockCmd(PIOS_HMC5883_DRDY_CLK | RCC_APB2Periph_AFIO, ENABLE);
/* Configure EOC pin as input floating */
GPIO_InitStructure.GPIO_Pin = PIOS_HMC5883_DRDY_GPIO_PIN;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
GPIO_Init(PIOS_HMC5883_DRDY_GPIO_PORT, &GPIO_InitStructure);
/* Configure the End Of Conversion (EOC) interrupt */
GPIO_EXTILineConfig(PIOS_HMC5883_DRDY_PORT_SOURCE, PIOS_HMC5883_DRDY_PIN_SOURCE);
EXTI_InitStructure.EXTI_Line = PIOS_HMC5883_DRDY_EXTI_LINE;
EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt;
EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising;
EXTI_InitStructure.EXTI_LineCmd = ENABLE;
EXTI_Init(&EXTI_InitStructure);
/* Enable and set EOC EXTI Interrupt to the lowest priority */
NVIC_InitStructure.NVIC_IRQChannel = PIOS_HMC5883_DRDY_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = PIOS_HMC5883_DRDY_PRIO;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
/* Configure the HMC5883 Sensor */
PIOS_HMC5883_ConfigTypeDef HMC5883_InitStructure;
HMC5883_InitStructure.M_ODR = PIOS_HMC5883_ODR_15;
HMC5883_InitStructure.Meas_Conf = PIOS_HMC5883_MEASCONF_NORMAL;
HMC5883_InitStructure.Gain = PIOS_HMC5883_GAIN_1_9;
HMC5883_InitStructure.Mode = PIOS_HMC5883_MODE_CONTINUOUS;
PIOS_HMC5883_Config(&HMC5883_InitStructure);
pios_hmc5883_data_ready = false;
}
/**
* @brief Initialize the HMC5883 magnetometer sensor
* \return none
* \param[in] PIOS_HMC5883_ConfigTypeDef struct to be used to configure sensor.
*
* CTRL_REGA: Control Register A
* Read Write
* Default value: 0x10
* 7:5 0 These bits must be cleared for correct operation.
* 4:2 DO2-DO0: Data Output Rate Bits
* DO2 | DO1 | DO0 | Minimum Data Output Rate (Hz)
* ------------------------------------------------------
* 0 | 0 | 0 | 0.75
* 0 | 0 | 1 | 1.5
* 0 | 1 | 0 | 3
* 0 | 1 | 1 | 7.5
* 1 | 0 | 0 | 15 (default)
* 1 | 0 | 1 | 30
* 1 | 1 | 0 | 75
* 1 | 1 | 1 | Not Used
* 1:0 MS1-MS0: Measurement Configuration Bits
* MS1 | MS0 | MODE
* ------------------------------
* 0 | 0 | Normal
* 0 | 1 | Positive Bias
* 1 | 0 | Negative Bias
* 1 | 1 | Not Used
*
* CTRL_REGB: Control RegisterB
* Read Write
* Default value: 0x20
* 7:5 GN2-GN0: Gain Configuration Bits.
* GN2 | GN1 | GN0 | Mag Input | Gain | Output Range
* | | | Range[Ga] | [LSB/mGa] |
* ------------------------------------------------------
* 0 | 0 | 0 | ±0.88Ga | 1370 | 0xF800–0x07FF (-2048:2047)
* 0 | 0 | 1 | ±1.3Ga (def) | 1090 | 0xF800–0x07FF (-2048:2047)
* 0 | 1 | 0 | ±1.9Ga | 820 | 0xF800–0x07FF (-2048:2047)
* 0 | 1 | 1 | ±2.5Ga | 660 | 0xF800–0x07FF (-2048:2047)
* 1 | 0 | 0 | ±4.0Ga | 440 | 0xF800–0x07FF (-2048:2047)
* 1 | 0 | 1 | ±4.7Ga | 390 | 0xF800–0x07FF (-2048:2047)
* 1 | 1 | 0 | ±5.6Ga | 330 | 0xF800–0x07FF (-2048:2047)
* 1 | 1 | 1 | ±8.1Ga | 230 | 0xF800–0x07FF (-2048:2047)
* |Not recommended|
*
* 4:0 CRB4-CRB: 0 This bit must be cleared for correct operation.
*
* _MODE_REG: Mode Register
* Read Write
* Default value: 0x02
* 7:2 0 These bits must be cleared for correct operation.
* 1:0 MD1-MD0: Mode Select Bits
* MS1 | MS0 | MODE
* ------------------------------
* 0 | 0 | Continuous-Conversion Mode.
* 0 | 1 | Single-Conversion Mode
* 1 | 0 | Negative Bias
* 1 | 1 | Sleep Mode
*/
static void PIOS_HMC5883_Config(PIOS_HMC5883_ConfigTypeDef * HMC5883_Config_Struct)
{
uint8_t CTRLA = 0x00;
uint8_t CTRLB = 0x00;
uint8_t MODE = 0x00;
CTRLA |= (uint8_t) (HMC5883_Config_Struct->M_ODR | HMC5883_Config_Struct->Meas_Conf);
CTRLB |= (uint8_t) (HMC5883_Config_Struct->Gain);
MODE |= (uint8_t) (HMC5883_Config_Struct->Mode);
// CRTL_REGA
while (!PIOS_HMC5883_Write(PIOS_HMC5883_CONFIG_REG_A, CTRLA)) ;
// CRTL_REGB
while (!PIOS_HMC5883_Write(PIOS_HMC5883_CONFIG_REG_B, CTRLB)) ;
// Mode register
while (!PIOS_HMC5883_Write(PIOS_HMC5883_MODE_REG, MODE)) ;
}
/**
* @brief Read current X, Z, Y values (in that order)
* \param[out] int16_t array of size 3 to store X, Z, and Y magnetometer readings
* \return none
*/
void PIOS_HMC5883_ReadMag(int16_t out[3])
{
uint8_t buffer[6];
uint8_t ctrlB;
pios_hmc5883_data_ready = false;
while (!PIOS_HMC5883_Read(PIOS_HMC5883_CONFIG_REG_B, &ctrlB, 1)) ;
while (!PIOS_HMC5883_Read(PIOS_HMC5883_DATAOUT_XMSB_REG, buffer, 6)) ;
switch (ctrlB & 0xE0) {
case 0x00:
for (int i = 0; i < 3; i++)
out[i] = ((int16_t) ((uint16_t) buffer[2 * i] << 8)
+ buffer[2 * i + 1]) * 1000 / PIOS_HMC5883_Sensitivity_0_88Ga;
break;
case 0x20:
for (int i = 0; i < 3; i++)
out[i] = ((int16_t) ((uint16_t) buffer[2 * i] << 8)
+ buffer[2 * i + 1]) * 1000 / PIOS_HMC5883_Sensitivity_1_3Ga;
break;
case 0x40:
for (int i = 0; i < 3; i++)
out[i] = (int16_t) (((uint16_t) buffer[2 * i] << 8)
+ buffer[2 * i + 1]) * 1000 / PIOS_HMC5883_Sensitivity_1_9Ga;
break;
case 0x60:
for (int i = 0; i < 3; i++)
out[i] = (int16_t) (((uint16_t) buffer[2 * i] << 8)
+ buffer[2 * i + 1]) * 1000 / PIOS_HMC5883_Sensitivity_2_5Ga;
break;
case 0x80:
for (int i = 0; i < 3; i++)
out[i] = (int16_t) (((uint16_t) buffer[2 * i] << 8)
+ buffer[2 * i + 1]) * 1000 / PIOS_HMC5883_Sensitivity_4_0Ga;
break;
case 0xA0:
for (int i = 0; i < 3; i++)
out[i] = (int16_t) (((uint16_t) buffer[2 * i] << 8)
+ buffer[2 * i + 1]) * 1000 / PIOS_HMC5883_Sensitivity_4_7Ga;
break;
case 0xC0:
for (int i = 0; i < 3; i++)
out[i] = (int16_t) (((uint16_t) buffer[2 * i] << 8)
+ buffer[2 * i + 1]) * 1000 / PIOS_HMC5883_Sensitivity_5_6Ga;
break;
case 0xE0:
for (int i = 0; i < 3; i++)
out[i] = (int16_t) (((uint16_t) buffer[2 * i] << 8)
+ buffer[2 * i + 1]) * 1000 / PIOS_HMC5883_Sensitivity_8_1Ga;
break;
}
}
/**
* @brief Read the identification bytes from the HMC5883 sensor
* \param[out] uint8_t array of size 4 to store HMC5883 ID.
* \return none
*/
void PIOS_HMC5883_ReadID(uint8_t out[4])
{
while (!PIOS_HMC5883_Read(PIOS_HMC5883_DATAOUT_IDA_REG, out, 3)) ;
out[3] = '\0';
}
/**
* @brief Tells whether new magnetometer readings are available
* \return true if new data is available
* \return false if new data is not available
*/
bool PIOS_HMC5883_NewDataAvailable(void)
{
return (pios_hmc5883_data_ready);
}
/**
* @brief Reads one or more bytes into a buffer
* \param[in] address HMC5883 register address (depends on size)
* \param[out] buffer destination buffer
* \param[in] len number of bytes which should be read
* \return 0 if operation was successful
* \return -1 if error during I2C transfer
* \return -4 if invalid length
*/
static bool PIOS_HMC5883_Read(uint8_t address, uint8_t * buffer, uint8_t len)
{
uint8_t addr_buffer[] = {
address,
};
const struct pios_i2c_txn txn_list[] = {
{
.info = __func__,
.addr = PIOS_HMC5883_I2C_ADDR,
.rw = PIOS_I2C_TXN_WRITE,
.len = sizeof(addr_buffer),
.buf = addr_buffer,
}
,
{
.info = __func__,
.addr = PIOS_HMC5883_I2C_ADDR,
.rw = PIOS_I2C_TXN_READ,
.len = len,
.buf = buffer,
}
};
return PIOS_I2C_Transfer(PIOS_I2C_MAIN_ADAPTER, txn_list, NELEMENTS(txn_list));
}
/**
* @brief Writes one or more bytes to the HMC5883
* \param[in] address Register address
* \param[in] buffer source buffer
* \return 0 if operation was successful
* \return -1 if error during I2C transfer
*/
static bool PIOS_HMC5883_Write(uint8_t address, uint8_t buffer)
{
uint8_t data[] = {
address,
buffer,
};
const struct pios_i2c_txn txn_list[] = {
{
.info = __func__,
.addr = PIOS_HMC5883_I2C_ADDR,
.rw = PIOS_I2C_TXN_WRITE,
.len = sizeof(data),
.buf = data,
}
,
};
return PIOS_I2C_Transfer(PIOS_I2C_MAIN_ADAPTER, txn_list, NELEMENTS(txn_list));
}
/**
* @brief Run self-test operation. Do not call this during operational use!!
* \return 0 if test failed
* \return non-zero value if test succeeded
*/
int32_t PIOS_HMC5883_Test(void)
{
/* Verify that ID matches (HMC5883 ID is null-terminated ASCII string "H43") */
char id[4];
PIOS_HMC5883_ReadID((uint8_t *)id);
if(!strncmp("H43\0",id,4))
return 0;
else
return 1;
int32_t passed = 1;
uint8_t registers[3] = {0,0,0};
/* Backup existing configuration */
while (!PIOS_HMC5883_Read(PIOS_HMC5883_CONFIG_REG_A,registers,3) );
/*
* Put HMC5883 into self test mode
* This is done by placing measurement config into positive (0x01) or negative (0x10) bias
* and then placing the mode register into single-measurement mode. This causes the HMC5883
* to create an artificial magnetic field of ~1.1 Gauss.
*
* If gain were PIOS_HMC5883_GAIN_2_5, for example, X and Y will read around +766 LSB
* (1.16 Ga * 660 LSB/Ga) and Z would read around +713 LSB (1.08 Ga * 660 LSB/Ga)
*
* Changing measurement config back to PIOS_HMC5883_MEASCONF_NORMAL will leave self-test mode.
*/
while (!PIOS_HMC5883_Write(PIOS_HMC5883_CONFIG_REG_A, PIOS_HMC5883_MEASCONF_BIAS_POS | PIOS_HMC5883_ODR_15)) ;
while (!PIOS_HMC5883_Write(PIOS_HMC5883_CONFIG_REG_B, PIOS_HMC5883_GAIN_2_5)) ;
while (!PIOS_HMC5883_Write(PIOS_HMC5883_MODE_REG, PIOS_HMC5883_MODE_SINGLE)) ;
uint8_t values[6];
while (!PIOS_HMC5883_Read(PIOS_HMC5883_DATAOUT_XMSB_REG, values, 6)) ;
int16_t x = (int16_t) (((uint16_t) values[0] << 8) + values[1]);
int16_t y = (int16_t) (((uint16_t) values[2] << 8) + values[3]);
int16_t z = (int16_t) (((uint16_t) values[4] << 8) + values[5]);
if(abs(abs(x) - 766) > 20)
passed &= 0;
if(abs(abs(y) - 766) > 20)
passed &= 0;
if(abs(abs(z) - 713) > 20)
passed &= 0;
/* Restore backup configuration */
while (!PIOS_HMC5883_Write(PIOS_HMC5883_CONFIG_REG_A,registers[0]) );
while (!PIOS_HMC5883_Write(PIOS_HMC5883_CONFIG_REG_B,registers[1]) );
while (!PIOS_HMC5883_Write(PIOS_HMC5883_MODE_REG,registers[2]) );
return passed;
}
/**
* @brief IRQ Handler
*/
void PIOS_HMC5883_IRQHandler(void)
{
pios_hmc5883_data_ready = true;
}
#endif /* PIOS_INCLUDE_HMC5883 */
/**
* @}
* @}
*/

View File

@ -0,0 +1,238 @@
/**
******************************************************************************
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_IMU3000 IMU3000 Functions
* @brief Deals with the hardware interface to the 3-axis gyro
* @{
*
* @file pios_IMU3000.c
* @author David "Buzz" Carlson (buzz@chebuzz.com)
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011.
* @brief IMU3000 3-axis gyor functions from INS
* @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
*/
/* Project Includes */
#include "pios.h"
#if defined(PIOS_INCLUDE_IMU3000)
/* Global Variables */
/* Local Types */
typedef struct {
uint8_t Fifo_store; /* FIFO storage of different readings (See datasheet page 31 for more details) */
uint8_t Smpl_rate_div; /* Sample rate divider to use (See datasheet page 32 for more details) */
uint8_t DigLPF_Scale; /* Digital low-pass filter and full-range scale (See datasheet page 33 for more details) */
uint8_t Interrupt_cfg; /* Interrupt configuration (See datasheet page 35 for more details) */
uint8_t User_ctl; /* User control settings (See datasheet page 41 for more details) */
uint8_t Pwr_mgmt_clk; /* Power management and clock selection (See datasheet page 32 for more details) */
} PIOS_IMU3000_ConfigTypeDef;
/* Local Variables */
static void PIOS_IMU3000_Config(PIOS_IMU3000_ConfigTypeDef * IMU3000_Config_Struct);
static bool PIOS_IMU3000_Read(uint8_t address, uint8_t * buffer, uint8_t len);
static bool PIOS_IMU3000_Write(uint8_t address, uint8_t buffer);
/**
* @brief Initialize the IMU3000 3-axis gyro sensor.
* @return none
*/
void PIOS_IMU3000_Init(void)
{
GPIO_InitTypeDef GPIO_InitStructure;
EXTI_InitTypeDef EXTI_InitStructure;
NVIC_InitTypeDef NVIC_InitStructure;
/* Enable INT GPIO clock */
RCC_APB2PeriphClockCmd(PIOS_IMU3000_INT_CLK | RCC_APB2Periph_AFIO, ENABLE);
/* Configure IMU3000 interrupt pin as input floating */
GPIO_InitStructure.GPIO_Pin = PIOS_IMU3000_INT_GPIO_PIN;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
GPIO_Init(PIOS_IMU3000_INT_GPIO_PORT, &GPIO_InitStructure);
/* Configure the End Of Conversion (EOC) interrupt */
GPIO_EXTILineConfig(PIOS_IMU3000_INT_PORT_SOURCE, PIOS_IMU3000_INT_PIN_SOURCE);
EXTI_InitStructure.EXTI_Line = PIOS_IMU3000_INT_EXTI_LINE;
EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt;
EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising;
EXTI_InitStructure.EXTI_LineCmd = ENABLE;
EXTI_Init(&EXTI_InitStructure);
/* Enable and set EOC EXTI Interrupt to the lowest priority */
NVIC_InitStructure.NVIC_IRQChannel = PIOS_IMU3000_INT_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = PIOS_IMU3000_INT_PRIO;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
/* Configure the IMU3000 Sensor */
PIOS_IMU3000_ConfigTypeDef IMU3000_InitStructure;
IMU3000_InitStructure.Fifo_store = PIOS_IMU3000_FIFO_TEMP_OUT | PIOS_IMU3000_FIFO_GYRO_X_OUT |
PIOS_IMU3000_FIFO_GYRO_Y_OUT | PIOS_IMU3000_FIFO_GYRO_Z_OUT | PIOS_IMU3000_FIFO_FOOTER;
IMU3000_InitStructure.Smpl_rate_div = 8;
IMU3000_InitStructure.DigLPF_Scale = PIOS_IMU3000_LOWPASS_256_HZ | PIOS_IMU3000_SCALE_500_DEG;
IMU3000_InitStructure.Interrupt_cfg = PIOS_IMU3000_INT_CLR_ANYRD | PIOS_IMU3000_INT_DATA_RDY;
IMU3000_InitStructure.User_ctl = PIOS_IMU3000_USERCTL_FIFO_EN;
IMU3000_InitStructure.Pwr_mgmt_clk = PIOS_IMU3000_PWRMGMT_PLL_X_CLK;
PIOS_IMU3000_Config(&IMU3000_InitStructure);
}
/**
* @brief Initialize the IMU3000 3-axis gyro sensor
* \return none
* \param[in] PIOS_IMU3000_ConfigTypeDef struct to be used to configure sensor.
*
*/
static void PIOS_IMU3000_Config(PIOS_IMU3000_ConfigTypeDef * IMU3000_Config_Struct)
{
// TODO: Add checks against current config so we only update what has changed
// FIFO storage
while (!PIOS_IMU3000_Write(PIOS_IMU3000_FIFO_EN_REG, IMU3000_Config_Struct->Fifo_store)) ;
// Sample rate divider
while (!PIOS_IMU3000_Write(PIOS_IMU3000_SMPLRT_DIV_REG, IMU3000_Config_Struct->Smpl_rate_div)) ;
// Digital low-pass filter and scale
while (!PIOS_IMU3000_Write(PIOS_IMU3000_DLPF_CFG_REG, IMU3000_Config_Struct->DigLPF_Scale)) ;
// Interrupt configuration
while (!PIOS_IMU3000_Write(PIOS_IMU3000_INT_CFG_REG, IMU3000_Config_Struct->Interrupt_cfg)) ;
// Interrupt configuration
while (!PIOS_IMU3000_Write(PIOS_IMU3000_USER_CTRL_REG, IMU3000_Config_Struct->User_ctl)) ;
// Interrupt configuration
while (!PIOS_IMU3000_Write(PIOS_IMU3000_PWR_MGMT_REG, IMU3000_Config_Struct->Pwr_mgmt_clk)) ;
}
/**
* @brief Read current X, Z, Y values (in that order)
* \param[out] int16_t array of size 3 to store X, Z, and Y magnetometer readings
* \return none
*/
void PIOS_IMU3000_ReadGyros(int16_t out[3])
{
}
/**
* @brief Read the identification bytes from the IMU3000 sensor
* \return ID read from IMU3000
*/
uint8_t PIOS_IMU3000_ReadID()
{
uint8_t id;
while (!PIOS_IMU3000_Read(0x00, &id, 1)) ;
return id;
}
/**
* @brief Reads one or more bytes from IMU3000 into a buffer
* \param[in] address IMU3000 register address (depends on size)
* \param[out] buffer destination buffer
* \param[in] len number of bytes which should be read
* \return 0 if operation was successful
* \return -1 if error during I2C transfer
* \return -4 if invalid length
*/
static bool PIOS_IMU3000_Read(uint8_t address, uint8_t * buffer, uint8_t len)
{
uint8_t addr_buffer[] = {
address,
};
const struct pios_i2c_txn txn_list[] = {
{
.info = __func__,
.addr = PIOS_IMU3000_I2C_ADDR,
.rw = PIOS_I2C_TXN_WRITE,
.len = sizeof(addr_buffer),
.buf = addr_buffer,
}
,
{
.info = __func__,
.addr = PIOS_IMU3000_I2C_ADDR,
.rw = PIOS_I2C_TXN_READ,
.len = len,
.buf = buffer,
}
};
return PIOS_I2C_Transfer(PIOS_I2C_MAIN_ADAPTER, txn_list, NELEMENTS(txn_list));
}
/**
* @brief Writes one or more bytes to the IMU3000
* \param[in] address Register address
* \param[in] buffer source buffer
* \return 0 if operation was successful
* \return -1 if error during I2C transfer
*/
static bool PIOS_IMU3000_Write(uint8_t address, uint8_t buffer)
{
uint8_t data[] = {
address,
buffer,
};
const struct pios_i2c_txn txn_list[] = {
{
.info = __func__,
.addr = PIOS_IMU3000_I2C_ADDR,
.rw = PIOS_I2C_TXN_WRITE,
.len = sizeof(data),
.buf = data,
}
,
};
return PIOS_I2C_Transfer(PIOS_I2C_MAIN_ADAPTER, txn_list, NELEMENTS(txn_list));
}
/**
* @brief Run self-test operation.
* \return 0 if test failed
* \return non-zero value if test succeeded
*/
uint8_t PIOS_IMU3000_Test(void)
{
/* Verify that ID matches (IMU3000 ID is 0x69) */
return (0x69 ^ PIOS_IMU3000_ReadID() );
}
/**
* @brief IRQ Handler
*/
void PIOS_IMU3000_IRQHandler(void)
{
}
#endif /* PIOS_INCLUDE_IMU3000 */
/**
* @}
* @}
*/

View File

@ -0,0 +1,402 @@
/**
******************************************************************************
*
* @file link_STM3210E_INS_HD_BL.ld
* @author David "Buzz" Carlson (buzz@chebuzz.com)
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011.
* @brief PiOS linker for the OpenPilot INS board
* @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
*/
/* Memory Spaces Definitions */
MEMORY
{
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 64K
FLASH (rx) : ORIGIN = 0x08005000, LENGTH = 492K
FLASHB1 (rx) : ORIGIN = 0x00000000, LENGTH = 0
EXTMEMB0 (rx) : ORIGIN = 0x00000000, LENGTH = 0
EXTMEMB1 (rx) : ORIGIN = 0x00000000, LENGTH = 0
EXTMEMB2 (rx) : ORIGIN = 0x00000000, LENGTH = 0
EXTMEMB3 (rx) : ORIGIN = 0x00000000, LENGTH = 0
}
_estack = 0x20004FF0;
/* This is the size of the stack for early init and for all FreeRTOS IRQs */
_irq_stack_size = 0x400;
/* Check valid alignment for VTOR */
ASSERT(ORIGIN(FLASH) == ALIGN(ORIGIN(FLASH), 0x80), "Start of memory region flash not aligned for startup vector table");
/*
this sends all unreferenced IRQHandlers to reset
*/
PROVIDE ( Undefined_Handler = 0 ) ;
PROVIDE ( SWI_Handler = 0 ) ;
PROVIDE ( IRQ_Handler = 0 ) ;
PROVIDE ( Prefetch_Handler = 0 ) ;
PROVIDE ( Abort_Handler = 0 ) ;
PROVIDE ( FIQ_Handler = 0 ) ;
PROVIDE ( NMI_Handler = 0 ) ;
PROVIDE ( HardFault_Handler = 0 ) ;
PROVIDE ( MemManage_Handler = 0 ) ;
PROVIDE ( BusFault_Handler = 0 ) ;
PROVIDE ( UsageFault_Handler = 0 ) ;
PROVIDE ( SVC_Handler = 0 ) ;
PROVIDE ( DebugMon_Handler = 0 ) ;
PROVIDE ( PendSV_Handler = 0 ) ;
PROVIDE ( SysTick_Handler = 0 ) ;
PROVIDE ( WWDG_IRQHandler = 0 ) ;
PROVIDE ( PVD_IRQHandler = 0 ) ;
PROVIDE ( TAMPER_IRQHandler = 0 ) ;
PROVIDE ( RTC_IRQHandler = 0 ) ;
PROVIDE ( FLASH_IRQHandler = 0 ) ;
PROVIDE ( RCC_IRQHandler = 0 ) ;
PROVIDE ( EXTI0_IRQHandler = 0 ) ;
PROVIDE ( EXTI1_IRQHandler = 0 ) ;
PROVIDE ( EXTI2_IRQHandler = 0 ) ;
PROVIDE ( EXTI3_IRQHandler = 0 ) ;
PROVIDE ( EXTI4_IRQHandler = 0 ) ;
PROVIDE ( DMAChannel1_IRQHandler = 0 ) ;
PROVIDE ( DMAChannel2_IRQHandler = 0 ) ;
PROVIDE ( DMAChannel3_IRQHandler = 0 ) ;
PROVIDE ( DMAChannel4_IRQHandler = 0 ) ;
PROVIDE ( DMAChannel5_IRQHandler = 0 ) ;
PROVIDE ( DMAChannel6_IRQHandler = 0 ) ;
PROVIDE ( DMAChannel7_IRQHandler = 0 ) ;
PROVIDE ( ADC_IRQHandler = 0 ) ;
PROVIDE ( USB_HP_CAN1_TX_IRQHandler = 0 ) ;
PROVIDE ( USB_LP_CAN1_RX0_IRQHandler = 0 ) ;
PROVIDE ( CAN1_RX1_IRQHandler = 0 ) ;
PROVIDE ( CAN1_SCE_IRQHandler = 0 ) ;
PROVIDE ( EXTI9_5_IRQHandler = 0 ) ;
PROVIDE ( TIM1_BRK_IRQHandler = 0 ) ;
PROVIDE ( TIM1_UP_IRQHandler = 0 ) ;
PROVIDE ( TIM1_TRG_COM_IRQHandler = 0 ) ;
PROVIDE ( TIM1_CC_IRQHandler = 0 ) ;
PROVIDE ( TIM2_IRQHandler = 0 ) ;
PROVIDE ( TIM3_IRQHandler = 0 ) ;
PROVIDE ( TIM4_IRQHandler = 0 ) ;
PROVIDE ( I2C1_EV_IRQHandler = 0 ) ;
PROVIDE ( I2C1_ER_IRQHandler = 0 ) ;
PROVIDE ( I2C2_EV_IRQHandler = 0 ) ;
PROVIDE ( I2C2_ER_IRQHandler = 0 ) ;
PROVIDE ( SPI1_IRQHandler = 0 ) ;
PROVIDE ( SPI2_IRQHandler = 0 ) ;
PROVIDE ( USART1_IRQHandler = 0 ) ;
PROVIDE ( USART2_IRQHandler = 0 ) ;
PROVIDE ( USART3_IRQHandler = 0 ) ;
PROVIDE ( EXTI15_10_IRQHandler = 0 ) ;
PROVIDE ( RTCAlarm_IRQHandler = 0 ) ;
PROVIDE ( USBWakeUp_IRQHandler = 0 ) ;
PROVIDE ( TIM8_BRK_IRQHandler = 0 ) ;
PROVIDE ( TIM8_UP_IRQHandler = 0 ) ;
PROVIDE ( TIM8_TRG_COM_IRQHandler = 0 ) ;
PROVIDE ( TIM8_CC_IRQHandler = 0 ) ;
PROVIDE ( ADC3_IRQHandler = 0 ) ;
PROVIDE ( FSMC_IRQHandler = 0 ) ;
PROVIDE ( SDIO_IRQHandler = 0 ) ;
PROVIDE ( TIM5_IRQHandler = 0 ) ;
PROVIDE ( SPI3_IRQHandler = 0 ) ;
PROVIDE ( UART4_IRQHandler = 0 ) ;
PROVIDE ( UART5_IRQHandler = 0 ) ;
PROVIDE ( TIM6_IRQHandler = 0 ) ;
PROVIDE ( TIM7_IRQHandler = 0 ) ;
PROVIDE ( DMA2_Channel1_IRQHandler = 0 ) ;
PROVIDE ( DMA2_Channel2_IRQHandler = 0 ) ;
PROVIDE ( DMA2_Channel3_IRQHandler = 0 ) ;
PROVIDE ( DMA2_Channel4_5_IRQHandler = 0 ) ;
/******************************************************************************/
/* Peripheral memory map */
/******************************************************************************/
/*this allows to compile the ST lib in "non-debug" mode*/
/* Peripheral and SRAM base address in the alias region */
PERIPH_BB_BASE = 0x42000000;
SRAM_BB_BASE = 0x22000000;
/* Peripheral and SRAM base address in the bit-band region */
SRAM_BASE = 0x20000000;
PERIPH_BASE = 0x40000000;
/* Flash registers base address */
PROVIDE ( FLASH_BASE = 0x40022000);
/* Flash Option Bytes base address */
PROVIDE ( OB_BASE = 0x1FFFF800);
/* Peripheral memory map */
APB1PERIPH_BASE = PERIPH_BASE ;
APB2PERIPH_BASE = (PERIPH_BASE + 0x10000) ;
AHBPERIPH_BASE = (PERIPH_BASE + 0x20000) ;
PROVIDE ( TIM2 = (APB1PERIPH_BASE + 0x0000) ) ;
PROVIDE ( TIM3 = (APB1PERIPH_BASE + 0x0400) ) ;
PROVIDE ( TIM4 = (APB1PERIPH_BASE + 0x0800) ) ;
PROVIDE ( RTC = (APB1PERIPH_BASE + 0x2800) ) ;
PROVIDE ( WWDG = (APB1PERIPH_BASE + 0x2C00) ) ;
PROVIDE ( IWDG = (APB1PERIPH_BASE + 0x3000) ) ;
PROVIDE ( SPI2 = (APB1PERIPH_BASE + 0x3800) ) ;
PROVIDE ( USART2 = (APB1PERIPH_BASE + 0x4400) ) ;
PROVIDE ( USART3 = (APB1PERIPH_BASE + 0x4800) ) ;
PROVIDE ( I2C1 = (APB1PERIPH_BASE + 0x5400) ) ;
PROVIDE ( I2C2 = (APB1PERIPH_BASE + 0x5800) ) ;
PROVIDE ( CAN = (APB1PERIPH_BASE + 0x6400) ) ;
PROVIDE ( BKP = (APB1PERIPH_BASE + 0x6C00) ) ;
PROVIDE ( PWR = (APB1PERIPH_BASE + 0x7000) ) ;
PROVIDE ( AFIO = (APB2PERIPH_BASE + 0x0000) ) ;
PROVIDE ( EXTI = (APB2PERIPH_BASE + 0x0400) ) ;
PROVIDE ( GPIOA = (APB2PERIPH_BASE + 0x0800) ) ;
PROVIDE ( GPIOB = (APB2PERIPH_BASE + 0x0C00) ) ;
PROVIDE ( GPIOC = (APB2PERIPH_BASE + 0x1000) ) ;
PROVIDE ( GPIOD = (APB2PERIPH_BASE + 0x1400) ) ;
PROVIDE ( GPIOE = (APB2PERIPH_BASE + 0x1800) ) ;
PROVIDE ( ADC1 = (APB2PERIPH_BASE + 0x2400) ) ;
PROVIDE ( ADC2 = (APB2PERIPH_BASE + 0x2800) ) ;
PROVIDE ( TIM1 = (APB2PERIPH_BASE + 0x2C00) ) ;
PROVIDE ( SPI1 = (APB2PERIPH_BASE + 0x3000) ) ;
PROVIDE ( USART1 = (APB2PERIPH_BASE + 0x3800) ) ;
PROVIDE ( DMA = (AHBPERIPH_BASE + 0x0000) ) ;
PROVIDE ( DMA_Channel1 = (AHBPERIPH_BASE + 0x0008) ) ;
PROVIDE ( DMA_Channel2 = (AHBPERIPH_BASE + 0x001C) ) ;
PROVIDE ( DMA_Channel3 = (AHBPERIPH_BASE + 0x0030) ) ;
PROVIDE ( DMA_Channel4 = (AHBPERIPH_BASE + 0x0044) ) ;
PROVIDE ( DMA_Channel5 = (AHBPERIPH_BASE + 0x0058) ) ;
PROVIDE ( DMA_Channel6 = (AHBPERIPH_BASE + 0x006C) ) ;
PROVIDE ( DMA_Channel7 = (AHBPERIPH_BASE + 0x0080) ) ;
PROVIDE ( RCC = (AHBPERIPH_BASE + 0x1000) ) ;
/* System Control Space memory map */
SCS_BASE = 0xE000E000;
PROVIDE ( SysTick = (SCS_BASE + 0x0010) ) ;
PROVIDE ( NVIC = (SCS_BASE + 0x0100) ) ;
PROVIDE ( SCB = (SCS_BASE + 0x0D00) ) ;
/* Sections Definitions */
SECTIONS
{
/* for Cortex devices, the beginning of the startup code is stored in the .isr_vector section, which goes to FLASH */
.isr_vector :
{
KEEP(*(.isr_vector)) /* Startup code */
. = ALIGN(4);
} >FLASH
/* for some STRx devices, the beginning of the startup code is stored in the .flashtext section, which goes to FLASH */
.flashtext :
{
. = ALIGN(4);
*(.flashtext) /* Startup code */
. = ALIGN(4);
} >FLASH
/* init sections */
.initcalluavobj.init :
{
. = ALIGN(4);
__uavobj_initcall_start = .;
KEEP(*(.initcalluavobj.init))
. = ALIGN(4);
__uavobj_initcall_end = .;
} >FLASH
/* the program code is stored in the .text section, which goes to Flash */
.text :
{
. = ALIGN(4);
*(.text) /* remaining code */
*(.text.*) /* remaining code */
*(.rodata) /* read-only data (constants) */
*(.rodata*)
*(.glue_7)
*(.glue_7t)
. = ALIGN(4);
_etext = .;
/* This is used by the startup in order to initialize the .data secion */
_sidata = _etext;
} >FLASH
/*
* This stack is used both as the initial sp during early init as well as ultimately
* being used as the STM32's MSP (Main Stack Pointer) which is the same stack that
* is used for _all_ interrupt handlers. The end of this stack should be placed
* against the lowest address in RAM so that a stack overrun results in a hard fault
* at the first access beyond the end of the stack.
*/
.irq_stack :
{
. = ALIGN(4);
_irq_stack_end = . ;
. = . + _irq_stack_size ;
. = ALIGN(4);
_irq_stack_top = . - 4 ;
. = ALIGN(4);
} >RAM
/* This is the initialized data section
The program executes knowing that the data is in the RAM
but the loader puts the initial values in the FLASH (inidata).
It is one task of the startup to copy the initial values from FLASH to RAM. */
.data : AT ( _sidata )
{
. = ALIGN(4);
/* This is used by the startup in order to initialize the .data secion */
_sdata = . ;
*(.data)
*(.data.*)
. = ALIGN(4);
/* This is used by the startup in order to initialize the .data secion */
_edata = . ;
} >RAM
/* This is the uninitialized data section */
.bss :
{
. = ALIGN(4);
/* This is used by the startup in order to initialize the .bss secion */
_sbss = .;
*(.bss)
*(COMMON)
. = ALIGN(4);
/* This is used by the startup in order to initialize the .bss secion */
_ebss = . ;
} >RAM
PROVIDE ( end = _ebss );
PROVIDE ( _end = _ebss );
/* this is the FLASH Bank1 */
/* the C or assembly source must explicitly place the code or data there
using the "section" attribute */
.b1text :
{
*(.b1text) /* remaining code */
*(.b1rodata) /* read-only data (constants) */
*(.b1rodata*)
} >FLASHB1
/* this is the EXTMEM */
/* the C or assembly source must explicitly place the code or data there
using the "section" attribute */
/* EXTMEM Bank0 */
.eb0text :
{
*(.eb0text) /* remaining code */
*(.eb0rodata) /* read-only data (constants) */
*(.eb0rodata*)
} >EXTMEMB0
/* EXTMEM Bank1 */
.eb1text :
{
*(.eb1text) /* remaining code */
*(.eb1rodata) /* read-only data (constants) */
*(.eb1rodata*)
} >EXTMEMB1
/* EXTMEM Bank2 */
.eb2text :
{
*(.eb2text) /* remaining code */
*(.eb2rodata) /* read-only data (constants) */
*(.eb2rodata*)
} >EXTMEMB2
/* EXTMEM Bank0 */
.eb3text :
{
*(.eb3text) /* remaining code */
*(.eb3rodata) /* read-only data (constants) */
*(.eb3rodata*)
} >EXTMEMB3
__exidx_start = .;
__exidx_end = .;
/* after that it's only debugging information. */
/* remove the debugging information from the standard libraries */
/DISCARD/ :
{
libc.a ( * )
libm.a ( * )
libgcc.a ( * )
}
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
.stab.excl 0 : { *(.stab.excl) }
.stab.exclstr 0 : { *(.stab.exclstr) }
.stab.index 0 : { *(.stab.index) }
.stab.indexstr 0 : { *(.stab.indexstr) }
.comment 0 : { *(.comment) }
/* DWARF debug sections.
Symbols in the DWARF debugging sections are relative to the beginning
of the section so we begin them at 0. */
/* DWARF 1 */
.debug 0 : { *(.debug) }
.line 0 : { *(.line) }
/* GNU DWARF 1 extensions */
.debug_srcinfo 0 : { *(.debug_srcinfo) }
.debug_sfnames 0 : { *(.debug_sfnames) }
/* DWARF 1.1 and DWARF 2 */
.debug_aranges 0 : { *(.debug_aranges) }
.debug_pubnames 0 : { *(.debug_pubnames) }
/* DWARF 2 */
.debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_line 0 : { *(.debug_line) }
.debug_frame 0 : { *(.debug_frame) }
.debug_str 0 : { *(.debug_str) }
.debug_loc 0 : { *(.debug_loc) }
.debug_macinfo 0 : { *(.debug_macinfo) }
/* SGI/MIPS DWARF 2 extensions */
.debug_weaknames 0 : { *(.debug_weaknames) }
.debug_funcnames 0 : { *(.debug_funcnames) }
.debug_typenames 0 : { *(.debug_typenames) }
.debug_varnames 0 : { *(.debug_varnames) }
}

View File

@ -0,0 +1,402 @@
/**
******************************************************************************
*
* @file link_STM3210E_INS_HD_NB.ld
* @author David "Buzz" Carlson (buzz@chebuzz.com)
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011.
* @brief PiOS linker for the OpenPilot INS board
* @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
*/
/* Memory Spaces Definitions */
MEMORY
{
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 64K
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 512K
FLASHB1 (rx) : ORIGIN = 0x00000000, LENGTH = 0
EXTMEMB0 (rx) : ORIGIN = 0x00000000, LENGTH = 0
EXTMEMB1 (rx) : ORIGIN = 0x00000000, LENGTH = 0
EXTMEMB2 (rx) : ORIGIN = 0x00000000, LENGTH = 0
EXTMEMB3 (rx) : ORIGIN = 0x00000000, LENGTH = 0
}
_estack = 0x20004FF0;
/* This is the size of the stack for early init and for all FreeRTOS IRQs */
_irq_stack_size = 0x400;
/* Check valid alignment for VTOR */
ASSERT(ORIGIN(FLASH) == ALIGN(ORIGIN(FLASH), 0x80), "Start of memory region flash not aligned for startup vector table");
/*
this sends all unreferenced IRQHandlers to reset
*/
PROVIDE ( Undefined_Handler = 0 ) ;
PROVIDE ( SWI_Handler = 0 ) ;
PROVIDE ( IRQ_Handler = 0 ) ;
PROVIDE ( Prefetch_Handler = 0 ) ;
PROVIDE ( Abort_Handler = 0 ) ;
PROVIDE ( FIQ_Handler = 0 ) ;
PROVIDE ( NMI_Handler = 0 ) ;
PROVIDE ( HardFault_Handler = 0 ) ;
PROVIDE ( MemManage_Handler = 0 ) ;
PROVIDE ( BusFault_Handler = 0 ) ;
PROVIDE ( UsageFault_Handler = 0 ) ;
PROVIDE ( SVC_Handler = 0 ) ;
PROVIDE ( DebugMon_Handler = 0 ) ;
PROVIDE ( PendSV_Handler = 0 ) ;
PROVIDE ( SysTick_Handler = 0 ) ;
PROVIDE ( WWDG_IRQHandler = 0 ) ;
PROVIDE ( PVD_IRQHandler = 0 ) ;
PROVIDE ( TAMPER_IRQHandler = 0 ) ;
PROVIDE ( RTC_IRQHandler = 0 ) ;
PROVIDE ( FLASH_IRQHandler = 0 ) ;
PROVIDE ( RCC_IRQHandler = 0 ) ;
PROVIDE ( EXTI0_IRQHandler = 0 ) ;
PROVIDE ( EXTI1_IRQHandler = 0 ) ;
PROVIDE ( EXTI2_IRQHandler = 0 ) ;
PROVIDE ( EXTI3_IRQHandler = 0 ) ;
PROVIDE ( EXTI4_IRQHandler = 0 ) ;
PROVIDE ( DMAChannel1_IRQHandler = 0 ) ;
PROVIDE ( DMAChannel2_IRQHandler = 0 ) ;
PROVIDE ( DMAChannel3_IRQHandler = 0 ) ;
PROVIDE ( DMAChannel4_IRQHandler = 0 ) ;
PROVIDE ( DMAChannel5_IRQHandler = 0 ) ;
PROVIDE ( DMAChannel6_IRQHandler = 0 ) ;
PROVIDE ( DMAChannel7_IRQHandler = 0 ) ;
PROVIDE ( ADC_IRQHandler = 0 ) ;
PROVIDE ( USB_HP_CAN1_TX_IRQHandler = 0 ) ;
PROVIDE ( USB_LP_CAN1_RX0_IRQHandler = 0 ) ;
PROVIDE ( CAN1_RX1_IRQHandler = 0 ) ;
PROVIDE ( CAN1_SCE_IRQHandler = 0 ) ;
PROVIDE ( EXTI9_5_IRQHandler = 0 ) ;
PROVIDE ( TIM1_BRK_IRQHandler = 0 ) ;
PROVIDE ( TIM1_UP_IRQHandler = 0 ) ;
PROVIDE ( TIM1_TRG_COM_IRQHandler = 0 ) ;
PROVIDE ( TIM1_CC_IRQHandler = 0 ) ;
PROVIDE ( TIM2_IRQHandler = 0 ) ;
PROVIDE ( TIM3_IRQHandler = 0 ) ;
PROVIDE ( TIM4_IRQHandler = 0 ) ;
PROVIDE ( I2C1_EV_IRQHandler = 0 ) ;
PROVIDE ( I2C1_ER_IRQHandler = 0 ) ;
PROVIDE ( I2C2_EV_IRQHandler = 0 ) ;
PROVIDE ( I2C2_ER_IRQHandler = 0 ) ;
PROVIDE ( SPI1_IRQHandler = 0 ) ;
PROVIDE ( SPI2_IRQHandler = 0 ) ;
PROVIDE ( USART1_IRQHandler = 0 ) ;
PROVIDE ( USART2_IRQHandler = 0 ) ;
PROVIDE ( USART3_IRQHandler = 0 ) ;
PROVIDE ( EXTI15_10_IRQHandler = 0 ) ;
PROVIDE ( RTCAlarm_IRQHandler = 0 ) ;
PROVIDE ( USBWakeUp_IRQHandler = 0 ) ;
PROVIDE ( TIM8_BRK_IRQHandler = 0 ) ;
PROVIDE ( TIM8_UP_IRQHandler = 0 ) ;
PROVIDE ( TIM8_TRG_COM_IRQHandler = 0 ) ;
PROVIDE ( TIM8_CC_IRQHandler = 0 ) ;
PROVIDE ( ADC3_IRQHandler = 0 ) ;
PROVIDE ( FSMC_IRQHandler = 0 ) ;
PROVIDE ( SDIO_IRQHandler = 0 ) ;
PROVIDE ( TIM5_IRQHandler = 0 ) ;
PROVIDE ( SPI3_IRQHandler = 0 ) ;
PROVIDE ( UART4_IRQHandler = 0 ) ;
PROVIDE ( UART5_IRQHandler = 0 ) ;
PROVIDE ( TIM6_IRQHandler = 0 ) ;
PROVIDE ( TIM7_IRQHandler = 0 ) ;
PROVIDE ( DMA2_Channel1_IRQHandler = 0 ) ;
PROVIDE ( DMA2_Channel2_IRQHandler = 0 ) ;
PROVIDE ( DMA2_Channel3_IRQHandler = 0 ) ;
PROVIDE ( DMA2_Channel4_5_IRQHandler = 0 ) ;
/******************************************************************************/
/* Peripheral memory map */
/******************************************************************************/
/*this allows to compile the ST lib in "non-debug" mode*/
/* Peripheral and SRAM base address in the alias region */
PERIPH_BB_BASE = 0x42000000;
SRAM_BB_BASE = 0x22000000;
/* Peripheral and SRAM base address in the bit-band region */
SRAM_BASE = 0x20000000;
PERIPH_BASE = 0x40000000;
/* Flash registers base address */
PROVIDE ( FLASH_BASE = 0x40022000);
/* Flash Option Bytes base address */
PROVIDE ( OB_BASE = 0x1FFFF800);
/* Peripheral memory map */
APB1PERIPH_BASE = PERIPH_BASE ;
APB2PERIPH_BASE = (PERIPH_BASE + 0x10000) ;
AHBPERIPH_BASE = (PERIPH_BASE + 0x20000) ;
PROVIDE ( TIM2 = (APB1PERIPH_BASE + 0x0000) ) ;
PROVIDE ( TIM3 = (APB1PERIPH_BASE + 0x0400) ) ;
PROVIDE ( TIM4 = (APB1PERIPH_BASE + 0x0800) ) ;
PROVIDE ( RTC = (APB1PERIPH_BASE + 0x2800) ) ;
PROVIDE ( WWDG = (APB1PERIPH_BASE + 0x2C00) ) ;
PROVIDE ( IWDG = (APB1PERIPH_BASE + 0x3000) ) ;
PROVIDE ( SPI2 = (APB1PERIPH_BASE + 0x3800) ) ;
PROVIDE ( USART2 = (APB1PERIPH_BASE + 0x4400) ) ;
PROVIDE ( USART3 = (APB1PERIPH_BASE + 0x4800) ) ;
PROVIDE ( I2C1 = (APB1PERIPH_BASE + 0x5400) ) ;
PROVIDE ( I2C2 = (APB1PERIPH_BASE + 0x5800) ) ;
PROVIDE ( CAN = (APB1PERIPH_BASE + 0x6400) ) ;
PROVIDE ( BKP = (APB1PERIPH_BASE + 0x6C00) ) ;
PROVIDE ( PWR = (APB1PERIPH_BASE + 0x7000) ) ;
PROVIDE ( AFIO = (APB2PERIPH_BASE + 0x0000) ) ;
PROVIDE ( EXTI = (APB2PERIPH_BASE + 0x0400) ) ;
PROVIDE ( GPIOA = (APB2PERIPH_BASE + 0x0800) ) ;
PROVIDE ( GPIOB = (APB2PERIPH_BASE + 0x0C00) ) ;
PROVIDE ( GPIOC = (APB2PERIPH_BASE + 0x1000) ) ;
PROVIDE ( GPIOD = (APB2PERIPH_BASE + 0x1400) ) ;
PROVIDE ( GPIOE = (APB2PERIPH_BASE + 0x1800) ) ;
PROVIDE ( ADC1 = (APB2PERIPH_BASE + 0x2400) ) ;
PROVIDE ( ADC2 = (APB2PERIPH_BASE + 0x2800) ) ;
PROVIDE ( TIM1 = (APB2PERIPH_BASE + 0x2C00) ) ;
PROVIDE ( SPI1 = (APB2PERIPH_BASE + 0x3000) ) ;
PROVIDE ( USART1 = (APB2PERIPH_BASE + 0x3800) ) ;
PROVIDE ( DMA = (AHBPERIPH_BASE + 0x0000) ) ;
PROVIDE ( DMA_Channel1 = (AHBPERIPH_BASE + 0x0008) ) ;
PROVIDE ( DMA_Channel2 = (AHBPERIPH_BASE + 0x001C) ) ;
PROVIDE ( DMA_Channel3 = (AHBPERIPH_BASE + 0x0030) ) ;
PROVIDE ( DMA_Channel4 = (AHBPERIPH_BASE + 0x0044) ) ;
PROVIDE ( DMA_Channel5 = (AHBPERIPH_BASE + 0x0058) ) ;
PROVIDE ( DMA_Channel6 = (AHBPERIPH_BASE + 0x006C) ) ;
PROVIDE ( DMA_Channel7 = (AHBPERIPH_BASE + 0x0080) ) ;
PROVIDE ( RCC = (AHBPERIPH_BASE + 0x1000) ) ;
/* System Control Space memory map */
SCS_BASE = 0xE000E000;
PROVIDE ( SysTick = (SCS_BASE + 0x0010) ) ;
PROVIDE ( NVIC = (SCS_BASE + 0x0100) ) ;
PROVIDE ( SCB = (SCS_BASE + 0x0D00) ) ;
/* Sections Definitions */
SECTIONS
{
/* for Cortex devices, the beginning of the startup code is stored in the .isr_vector section, which goes to FLASH */
.isr_vector :
{
KEEP(*(.isr_vector)) /* Startup code */
. = ALIGN(4);
} >FLASH
/* for some STRx devices, the beginning of the startup code is stored in the .flashtext section, which goes to FLASH */
.flashtext :
{
. = ALIGN(4);
*(.flashtext) /* Startup code */
. = ALIGN(4);
} >FLASH
/* init sections */
.initcalluavobj.init :
{
. = ALIGN(4);
__uavobj_initcall_start = .;
KEEP(*(.initcalluavobj.init))
. = ALIGN(4);
__uavobj_initcall_end = .;
} >FLASH
/* the program code is stored in the .text section, which goes to Flash */
.text :
{
. = ALIGN(4);
*(.text) /* remaining code */
*(.text.*) /* remaining code */
*(.rodata) /* read-only data (constants) */
*(.rodata*)
*(.glue_7)
*(.glue_7t)
. = ALIGN(4);
_etext = .;
/* This is used by the startup in order to initialize the .data secion */
_sidata = _etext;
} >FLASH
/*
* This stack is used both as the initial sp during early init as well as ultimately
* being used as the STM32's MSP (Main Stack Pointer) which is the same stack that
* is used for _all_ interrupt handlers. The end of this stack should be placed
* against the lowest address in RAM so that a stack overrun results in a hard fault
* at the first access beyond the end of the stack.
*/
.irq_stack :
{
. = ALIGN(4);
_irq_stack_end = . ;
. = . + _irq_stack_size ;
. = ALIGN(4);
_irq_stack_top = . - 4 ;
. = ALIGN(4);
} >RAM
/* This is the initialized data section
The program executes knowing that the data is in the RAM
but the loader puts the initial values in the FLASH (inidata).
It is one task of the startup to copy the initial values from FLASH to RAM. */
.data : AT ( _sidata )
{
. = ALIGN(4);
/* This is used by the startup in order to initialize the .data secion */
_sdata = . ;
*(.data)
*(.data.*)
. = ALIGN(4);
/* This is used by the startup in order to initialize the .data secion */
_edata = . ;
} >RAM
/* This is the uninitialized data section */
.bss :
{
. = ALIGN(4);
/* This is used by the startup in order to initialize the .bss secion */
_sbss = .;
*(.bss)
*(COMMON)
. = ALIGN(4);
/* This is used by the startup in order to initialize the .bss secion */
_ebss = . ;
} >RAM
PROVIDE ( end = _ebss );
PROVIDE ( _end = _ebss );
/* this is the FLASH Bank1 */
/* the C or assembly source must explicitly place the code or data there
using the "section" attribute */
.b1text :
{
*(.b1text) /* remaining code */
*(.b1rodata) /* read-only data (constants) */
*(.b1rodata*)
} >FLASHB1
/* this is the EXTMEM */
/* the C or assembly source must explicitly place the code or data there
using the "section" attribute */
/* EXTMEM Bank0 */
.eb0text :
{
*(.eb0text) /* remaining code */
*(.eb0rodata) /* read-only data (constants) */
*(.eb0rodata*)
} >EXTMEMB0
/* EXTMEM Bank1 */
.eb1text :
{
*(.eb1text) /* remaining code */
*(.eb1rodata) /* read-only data (constants) */
*(.eb1rodata*)
} >EXTMEMB1
/* EXTMEM Bank2 */
.eb2text :
{
*(.eb2text) /* remaining code */
*(.eb2rodata) /* read-only data (constants) */
*(.eb2rodata*)
} >EXTMEMB2
/* EXTMEM Bank0 */
.eb3text :
{
*(.eb3text) /* remaining code */
*(.eb3rodata) /* read-only data (constants) */
*(.eb3rodata*)
} >EXTMEMB3
__exidx_start = .;
__exidx_end = .;
/* after that it's only debugging information. */
/* remove the debugging information from the standard libraries */
/DISCARD/ :
{
libc.a ( * )
libm.a ( * )
libgcc.a ( * )
}
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
.stab.excl 0 : { *(.stab.excl) }
.stab.exclstr 0 : { *(.stab.exclstr) }
.stab.index 0 : { *(.stab.index) }
.stab.indexstr 0 : { *(.stab.indexstr) }
.comment 0 : { *(.comment) }
/* DWARF debug sections.
Symbols in the DWARF debugging sections are relative to the beginning
of the section so we begin them at 0. */
/* DWARF 1 */
.debug 0 : { *(.debug) }
.line 0 : { *(.line) }
/* GNU DWARF 1 extensions */
.debug_srcinfo 0 : { *(.debug_srcinfo) }
.debug_sfnames 0 : { *(.debug_sfnames) }
/* DWARF 1.1 and DWARF 2 */
.debug_aranges 0 : { *(.debug_aranges) }
.debug_pubnames 0 : { *(.debug_pubnames) }
/* DWARF 2 */
.debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_line 0 : { *(.debug_line) }
.debug_frame 0 : { *(.debug_frame) }
.debug_str 0 : { *(.debug_str) }
.debug_loc 0 : { *(.debug_loc) }
.debug_macinfo 0 : { *(.debug_macinfo) }
/* SGI/MIPS DWARF 2 extensions */
.debug_weaknames 0 : { *(.debug_weaknames) }
.debug_funcnames 0 : { *(.debug_funcnames) }
.debug_typenames 0 : { *(.debug_typenames) }
.debug_varnames 0 : { *(.debug_varnames) }
}

View File

@ -0,0 +1,87 @@
/**
******************************************************************************
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_BMA180 BMA180 Functions
* @brief Deals with the hardware interface to the BMA180 3-axis accelerometer
* @{
*
* @file pios_bma180.h
* @author David "Buzz" Carlson (buzz@chebuzz.com)
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011.
* @brief PiOS BMA180 digital accelerometer driver.
* - Driver for the BMA180 digital accelerometer on the SPI bus.
* @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 PIOS_BMA180_H
#define PIOS_BMA180_H
/* BMA180 Addresses */
#define BMA_CHIPID_ADDR 0x00
#define BMA_VERSION_ADDR 0x00
#define BMA_X_LSB_ADDR 0x02
#define BMA_Y_LSB_ADDR 0x04
#define BMA_Z_LSB_ADDR 0x06
#define BMA_WE_ADDR 0x0D
#define BMA_BW_ADDR 0x20
#define BMA_RANGE_ADDR 0x35
/* Accel range */
#define BMA_RANGE_1G 0x00 // +/- 1G ADC resolution 0.13 mg/LSB
#define BMA_RANGE_1_5G 0x01 // +/- 1.5G ADC resolution 0.19 mg/LSB
#define BMA_RANGE_2G 0x02 // +/- 2G ADC resolution 0.25 mg/LSB *** default ***
#define BMA_RANGE_3G 0x03 // +/- 3G ADC resolution 0.38 mg/LSB
#define BMA_RANGE_4G 0x04 // +/- 4G ADC resolution 0.50 mg/LSB
#define BMA_RANGE_8G 0x05 // +/- 8G ADC resolution 0.99 mg/LSB
#define BMA_RANGE_16G 0x06 // +/- 16G ADC resolution 1.98 mg/LSB
/* Measurement bandwidth */
#define BMA_BW_10HZ 0x00
#define BMA_BW_20HZ 0x01
#define BMA_BW_40HZ 0x02
#define BMA_BW_75HZ 0x03
#define BMA_BW_150HZ 0x04 // *** default ***
#define BMA_BW_300HZ 0x05
#define BMA_BW_600HZ 0x06
#define BMA_BW_1200HZ 0x07
#define BMA_BW_HP1HZ 0x08 // High-pass, 1Hz
#define BMA_BW_BP0_300HZ 0x09 // Band-pass, 0.3Hz-300Hz
struct pios_bma180_data {
int16_t x;
int16_t y;
int16_t z;
};
/* Public Functions */
void PIOS_BMA180_WriteEnable(uint8_t _we);
uint8_t PIOS_BMA180_GetReg(uint8_t reg);
void PIOS_BMA180_SetReg(uint8_t reg, uint8_t data);
void PIOS_BMA180_Attach(uint32_t spi_id);
void PIOS_BMA180_Init();
uint8_t PIOS_BMA180_Read(struct pios_bma180_data * data);
uint8_t PIOS_BMA180_Test();
#endif /* PIOS_BMA180_H */
/**
* @}
* @}
*/

View File

@ -0,0 +1,105 @@
/**
******************************************************************************
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_HMC5883 HMC5883 Functions
* @brief Deals with the hardware interface to the magnetometers
* @{
*
* @file pios_hmc5883.h
* @author David "Buzz" Carlson (buzz@chebuzz.com)
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011.
* @brief HMC5883 functions 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 PIOS_HMC5883_H
#define PIOS_HMC5883_H
/* HMC5883 Addresses */
#define PIOS_HMC5883_I2C_ADDR 0x1E
#define PIOS_HMC5883_I2C_READ_ADDR 0x3D
#define PIOS_HMC5883_I2C_WRITE_ADDR 0x3C
#define PIOS_HMC5883_CONFIG_REG_A (uint8_t)0x00
#define PIOS_HMC5883_CONFIG_REG_B (uint8_t)0x01
#define PIOS_HMC5883_MODE_REG (uint8_t)0x02
#define PIOS_HMC5883_DATAOUT_XMSB_REG 0x03
#define PIOS_HMC5883_DATAOUT_XLSB_REG 0x04
#define PIOS_HMC5883_DATAOUT_ZMSB_REG 0x05
#define PIOS_HMC5883_DATAOUT_ZLSB_REG 0x06
#define PIOS_HMC5883_DATAOUT_YMSB_REG 0x07
#define PIOS_HMC5883_DATAOUT_YLSB_REG 0x08
#define PIOS_HMC5883_DATAOUT_STATUS_REG 0x09
#define PIOS_HMC5883_DATAOUT_IDA_REG 0x0A
#define PIOS_HMC5883_DATAOUT_IDB_REG 0x0B
#define PIOS_HMC5883_DATAOUT_IDC_REG 0x0C
/* Output Data Rate */
#define PIOS_HMC5883_ODR_0_75 0x00
#define PIOS_HMC5883_ODR_1_5 0x04
#define PIOS_HMC5883_ODR_3 0x08
#define PIOS_HMC5883_ODR_7_5 0x0C
#define PIOS_HMC5883_ODR_15 0x10
#define PIOS_HMC5883_ODR_30 0x14
#define PIOS_HMC5883_ODR_75 0x18
/* Measure configuration */
#define PIOS_HMC5883_MEASCONF_NORMAL 0x00
#define PIOS_HMC5883_MEASCONF_BIAS_POS 0x01
#define PIOS_HMC5883_MEASCONF_BIAS_NEG 0x02
/* Gain settings */
#define PIOS_HMC5883_GAIN_0_88 0x00
#define PIOS_HMC5883_GAIN_1_3 0x20
#define PIOS_HMC5883_GAIN_1_9 0x40
#define PIOS_HMC5883_GAIN_2_5 0x60
#define PIOS_HMC5883_GAIN_4_0 0x80
#define PIOS_HMC5883_GAIN_4_7 0xA0
#define PIOS_HMC5883_GAIN_5_6 0xC0
#define PIOS_HMC5883_GAIN_8_1 0xE0
/* Modes */
#define PIOS_HMC5883_MODE_CONTINUOUS 0x00
#define PIOS_HMC5883_MODE_SINGLE 0x01
#define PIOS_HMC5883_MODE_IDLE 0x02
#define PIOS_HMC5883_MODE_SLEEP 0x03
/* Sensitivity Conversion Values */
#define PIOS_HMC5883_Sensitivity_0_88Ga 1370 // LSB/Ga
#define PIOS_HMC5883_Sensitivity_1_3Ga 1090 // LSB/Ga
#define PIOS_HMC5883_Sensitivity_1_9Ga 820 // LSB/Ga
#define PIOS_HMC5883_Sensitivity_2_5Ga 660 // LSB/Ga
#define PIOS_HMC5883_Sensitivity_4_0Ga 440 // LSB/Ga
#define PIOS_HMC5883_Sensitivity_4_7Ga 390 // LSB/Ga
#define PIOS_HMC5883_Sensitivity_5_6Ga 330 // LSB/Ga
#define PIOS_HMC5883_Sensitivity_8_1Ga 230 // LSB/Ga --> NOT RECOMMENDED
/* Public Functions */
extern void PIOS_HMC5883_Init(void);
extern bool PIOS_HMC5883_NewDataAvailable(void);
extern void PIOS_HMC5883_ReadMag(int16_t out[3]);
extern void PIOS_HMC5883_ReadID(uint8_t out[4]);
extern int32_t PIOS_HMC5883_Test(void);
#endif /* PIOS_HMC5883_H */
/**
* @}
* @}
*/

View File

@ -0,0 +1,126 @@
/**
******************************************************************************
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_IMU3000 IMU3000 Functions
* @brief Deals with the hardware interface to the 3-axis gyro
* @{
*
* @file pios_imu3000.h
* @author David "Buzz" Carlson (buzz@chebuzz.com)
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011.
* @brief IMU3000 3-axis gyor function headers
* @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 PIOS_IMU3000_H
#define PIOS_IMU3000_H
/* IMU3000 Addresses */
#define PIOS_IMU3000_I2C_ADDR 0x69
#define PIOS_IMU3000_I2C_READ_ADDR 0xD2
#define PIOS_IMU3000_I2C_WRITE_ADDR 0xD3
#define PIOS_IMU3000_X_MSB_OFFSET_REG 0x0C
#define PIOS_IMU3000_X_LSB_OFFSET_REG 0x0D
#define PIOS_IMU3000_Y_MSB_OFFSET_REG 0x0E
#define PIOS_IMU3000_Y_LSB_OFFSET_REG 0x0F
#define PIOS_IMU3000_Z_MSB_OFFSET_REG 0x10
#define PIOS_IMU3000_Z_LSB_OFFSET_REG 0x11
#define PIOS_IMU3000_FIFO_EN_REG 0x12
#define PIOS_IMU3000_SMPLRT_DIV_REG 0X15
#define PIOS_IMU3000_DLPF_CFG_REG 0X16
#define PIOS_IMU3000_INT_CFG_REG 0x17
#define PIOS_IMU3000_INT_STATUS_REG 0x1A
#define PIOS_IMU3000_TEMP_OUT_MSB 0x1B
#define PIOS_IMU3000_TEMP_OUT_LSB 0x1C
#define PIOS_IMU3000_GYRO_X_OUT_MSB 0x1D
#define PIOS_IMU3000_GYRO_X_OUT_LSB 0x1E
#define PIOS_IMU3000_GYRO_Y_OUT_MSB 0x1F
#define PIOS_IMU3000_GYRO_Y_OUT_LSB 0x20
#define PIOS_IMU3000_GYRO_Z_OUT_MSB 0x21
#define PIOS_IMU3000_GYRO_Z_OUT_LSB 0x22
#define PIOS_IMU3000_FIFO_CNT_MSB 0x3A
#define PIOS_IMU3000_FIFO_CNT_LSB 0x3B
#define PIOS_IMU3000_FIFO_REG 0x3C
#define PIOS_IMU3000_USER_CTRL_REG 0x3D
#define PIOS_IMU3000_PWR_MGMT_REG 0x3E
/* FIFO enable for storing different values */
#define PIOS_IMU3000_FIFO_TEMP_OUT 0x80
#define PIOS_IMU3000_FIFO_GYRO_X_OUT 0x40
#define PIOS_IMU3000_FIFO_GYRO_Y_OUT 0x20
#define PIOS_IMU3000_FIFO_GYRO_Z_OUT 0x10
#define PIOS_IMU3000_FIFO_FOOTER 0x01
/* Gyro full-scale range */
#define PIOS_IMU3000_SCALE_250_DEG 0x00
#define PIOS_IMU3000_SCALE_500_DEG 0x01
#define PIOS_IMU3000_SCALE_1000_DEG 0x02
#define PIOS_IMU3000_SCALE_2000_DEG 0x03
/* Digital low-pass filter configuration */
#define PIOS_IMU3000_LOWPASS_256_HZ 0x00
#define PIOS_IMU3000_LOWPASS_188_HZ 0x01
#define PIOS_IMU3000_LOWPASS_98_HZ 0x02
#define PIOS_IMU3000_LOWPASS_42_HZ 0x03
#define PIOS_IMU3000_LOWPASS_20_HZ 0x04
#define PIOS_IMU3000_LOWPASS_10_HZ 0x05
#define PIOS_IMU3000_LOWPASS_5_HZ 0x06
/* Interrupt Configuration */
#define PIOS_IMU3000_INT_ACTL 0x80
#define PIOS_IMU3000_INT_OPEN 0x40
#define PIOS_IMU3000_INT_LATCH_EN 0x20
#define PIOS_IMU3000_INT_CLR_ANYRD 0x10
#define PIOS_IMU3000_INT_IMU_RDY 0x04
#define PIOS_IMU3000_INT_DATA_RDY 0x01
/* Interrupt status */
#define PIOS_IMU3000_INT_STATUS_FIFO_FULL 0x80
#define PIOS_IMU3000_INT_STATUS_IMU_RDY 0X04
#define PIOS_IMU3000_INT_STATUS_DATA_RDY 0X01
/* User control functionality */
#define PIOS_IMU3000_USERCTL_FIFO_EN 0X40
#define PIOS_IMU3000_USERCTL_FIFO_RST 0X02
#define PIOS_IMU3000_USERCTL_GYRO_RST 0X01
/* Power management and clock selection */
#define PIOS_IMU3000_PWRMGMT_IMU_RST 0X80
#define PIOS_IMU3000_PWRMGMT_INTERN_CLK 0X00
#define PIOS_IMU3000_PWRMGMT_PLL_X_CLK 0X01
#define PIOS_IMU3000_PWRMGMT_PLL_Y_CLK 0X02
#define PIOS_IMU3000_PWRMGMT_PLL_Z_CLK 0X03
#define PIOS_IMU3000_PWRMGMT_STOP_CLK 0X07
/* Public Functions */
extern void PIOS_IMU3000_Init(void);
extern bool PIOS_IMU3000_NewDataAvailable(void);
extern void PIOS_IMU3000_ReadGyros(int16_t out[3]);
extern uint8_t PIOS_IMU3000_ReadID();
extern uint8_t PIOS_IMU3000_Test();
#endif /* PIOS_IMU3000_H */
/**
* @}
* @}
*/

View File

@ -98,15 +98,25 @@
#if defined(PIOS_INCLUDE_HMC5843)
#include <pios_hmc5843.h>
#endif
#if defined(PIOS_INCLUDE_HMC5883)
#include <pios_hmc5883.h>
#endif
#if defined(PIOS_INCLUDE_I2C_ESC)
#include <pios_i2c_esc.h>
#endif
#if defined(PIOS_INCLUDE_IMU3000)
#include <pios_imu3000.h>
#endif
#include <pios_iap.h>
#if defined(PIOS_INCLUDE_ADXL345)
#include <pios_adxl345.h>
#endif
#if defined(PIOS_INCLUDE_BMA180)
#include <pios_bma180.h>
#endif
#if defined(PIOS_INCLUDE_FLASH)
#include <pios_flash_w25x.h>
#endif